A class for storing a map of point cloud handlers. More...
| Public Member Functions | |
| CloudServer () | |
| ~CloudServer () | |
| Protected Member Functions | |
| void | handleMissingEntryError (const point_cloud_server::StoreCloudGoalConstPtr &goal) | 
| Convenience function 2 to handle errors. | |
| void | handleOtherError (const std::string &text) | 
| Convenience function 4 to handle errors. | |
| void | handleTFError (const point_cloud_server::StoreCloudGoalConstPtr &goal) | 
| Convenience function 3 to handle errors. | |
| void | handleTopicError (const point_cloud_server::StoreCloudGoalConstPtr &goal, const std::string &resolved_topic) | 
| Convenience function 1 to handle errors. | |
| void | storeCloud (const point_cloud_server::StoreCloudGoalConstPtr &goal) | 
| The action goal callback. Implements the StoreCLoudAction API. | |
| Protected Attributes | |
| std::map< std::string, boost::shared_ptr < CloudContainer > > | cloud_map_ | 
| A map of cloud handlers, allowing us to fetch clouds by name. | |
| std::map< std::string, boost::shared_ptr < CloudContainer > >::iterator | cloud_map_it_ | 
| A convenience handle for accessing cloud handlers in the map. | |
| ros::NodeHandle | nh_ | 
| Node handles. | |
| ros::NodeHandle | pnh_ | 
| std::string | store_cloud_name_ | 
| The name of this action server. | |
| actionlib::SimpleActionServer < point_cloud_server::StoreCloudAction > | store_cloud_server_ | 
| The actual action server. | |
| tf::TransformListener | tfl_ | 
| TF listener for doing transforms. | |
A class for storing a map of point cloud handlers.
Definition at line 49 of file cloud_server.cpp.
| CloudServer::CloudServer | ( | ) |  [inline] | 
Definition at line 53 of file cloud_server.cpp.
| CloudServer::~CloudServer | ( | ) |  [inline] | 
Definition at line 63 of file cloud_server.cpp.
| void CloudServer::handleMissingEntryError | ( | const point_cloud_server::StoreCloudGoalConstPtr & | goal | ) |  [inline, protected] | 
Convenience function 2 to handle errors.
Definition at line 83 of file cloud_server.cpp.
| void CloudServer::handleOtherError | ( | const std::string & | text | ) |  [inline, protected] | 
Convenience function 4 to handle errors.
Definition at line 106 of file cloud_server.cpp.
| void CloudServer::handleTFError | ( | const point_cloud_server::StoreCloudGoalConstPtr & | goal | ) |  [inline, protected] | 
Convenience function 3 to handle errors.
Definition at line 95 of file cloud_server.cpp.
| void CloudServer::handleTopicError | ( | const point_cloud_server::StoreCloudGoalConstPtr & | goal, | 
| const std::string & | resolved_topic | ||
| ) |  [inline, protected] | 
Convenience function 1 to handle errors.
Definition at line 71 of file cloud_server.cpp.
| void CloudServer::storeCloud | ( | const point_cloud_server::StoreCloudGoalConstPtr & | goal | ) |  [inline, protected] | 
The action goal callback. Implements the StoreCLoudAction API.
Definition at line 117 of file cloud_server.cpp.
| std::map< std::string, boost::shared_ptr<CloudContainer> > CloudServer::cloud_map_  [protected] | 
A map of cloud handlers, allowing us to fetch clouds by name.
Definition at line 313 of file cloud_server.cpp.
| std::map< std::string, boost::shared_ptr<CloudContainer> >::iterator CloudServer::cloud_map_it_  [protected] | 
A convenience handle for accessing cloud handlers in the map.
Definition at line 316 of file cloud_server.cpp.
| ros::NodeHandle CloudServer::nh_  [protected] | 
Node handles.
Definition at line 306 of file cloud_server.cpp.
| ros::NodeHandle CloudServer::pnh_  [protected] | 
Definition at line 307 of file cloud_server.cpp.
| std::string CloudServer::store_cloud_name_  [protected] | 
The name of this action server.
Definition at line 319 of file cloud_server.cpp.
| actionlib::SimpleActionServer<point_cloud_server::StoreCloudAction> CloudServer::store_cloud_server_  [protected] | 
The actual action server.
Definition at line 322 of file cloud_server.cpp.
| tf::TransformListener CloudServer::tfl_  [protected] | 
TF listener for doing transforms.
Definition at line 310 of file cloud_server.cpp.