#include <cloud_handler.h>
Public Member Functions | |
| void | clear () |
| Clear the cloud stored in this object. | |
| CloudHandler (ros::NodeHandle *nh, tf::TransformListener *tfl, std::string marker_name, std::string topic_name, std::string server_name, object_manipulator::MechanismInterface &mechanism, std::string cloud_frame) | |
| sensor_msgs::PointCloud2 | get () |
| Get the cloud stored in this object. | |
| void | get (sensor_msgs::PointCloud2 &cloud) |
| void | refresh () |
| Refresh the cloud stored in this object. | |
| void | refresh (const std::string &topic) |
| void | updateCloud (sensor_msgs::PointCloud2 cloud, std::string name) |
| ~CloudHandler () | |
Private Types | |
| typedef interactive_markers::MenuHandler | MenuHandler |
Private Member Functions | |
| void | leftClickPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | makeMarker (float size) |
| void | makeMenu () |
| void | menuFocus (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | menuPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | pickup (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | saveCloudAndNormals () |
Private Attributes | |
| std::string | cloud_frame_ |
| pcl::PointCloud< pcl::Normal >::Ptr | cloud_normals_ |
| pcl::PointCloud< PointT >::Ptr | cloud_pts_ |
| actionlib::SimpleActionClient < point_cloud_server::StoreCloudAction > | cloud_server_client_ |
| bool | double_menu_ |
| std::string | head_pointing_frame_ |
| std::string | marker_name_ |
| interactive_markers::InteractiveMarkerServer | marker_server_ |
| object_manipulator::MechanismInterface & | mechanism_ |
| interactive_markers::MenuHandler | menu_handler_ |
| sensor_msgs::PointCloud2 | msg_cloud_ |
| ros::NodeHandle * | nh_ |
| ros::Publisher | pub_focus_ |
| ros::Publisher | pub_left_click_ |
| ros::Publisher | pub_refresh_flag_ |
| ros::Publisher | pub_right_click_ |
| tf::TransformListener * | tfl_ |
| std::string | topic_ |
| pcl::search::KdTree< PointT >::Ptr | tree_ |
| double | voxel_size_ |
Definition at line 50 of file cloud_handler.h.
typedef interactive_markers::MenuHandler CloudHandler::MenuHandler [private] |
Definition at line 76 of file cloud_handler.h.
| CloudHandler::CloudHandler | ( | ros::NodeHandle * | nh, |
| tf::TransformListener * | tfl, | ||
| std::string | marker_name, | ||
| std::string | topic_name, | ||
| std::string | server_name, | ||
| object_manipulator::MechanismInterface & | mechanism, | ||
| std::string | cloud_frame | ||
| ) |
Definition at line 57 of file cloud_handler.cpp.
Definition at line 85 of file cloud_handler.cpp.
| void CloudHandler::clear | ( | void | ) |
Clear the cloud stored in this object.
Definition at line 358 of file cloud_handler.cpp.
| sensor_msgs::PointCloud2 CloudHandler::get | ( | ) |
Get the cloud stored in this object.
Definition at line 299 of file cloud_handler.cpp.
| void CloudHandler::get | ( | sensor_msgs::PointCloud2 & | cloud | ) |
Definition at line 294 of file cloud_handler.cpp.
| void CloudHandler::leftClickPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 99 of file cloud_handler.cpp.
| void CloudHandler::makeMarker | ( | float | size | ) | [private] |
Definition at line 365 of file cloud_handler.cpp.
| void CloudHandler::makeMenu | ( | ) | [private] |
Definition at line 90 of file cloud_handler.cpp.
| void CloudHandler::menuFocus | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 125 of file cloud_handler.cpp.
| void CloudHandler::menuPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 153 of file cloud_handler.cpp.
| void CloudHandler::pickup | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
| void CloudHandler::refresh | ( | ) |
Refresh the cloud stored in this object.
Definition at line 328 of file cloud_handler.cpp.
| void CloudHandler::refresh | ( | const std::string & | topic | ) |
Definition at line 334 of file cloud_handler.cpp.
| void CloudHandler::saveCloudAndNormals | ( | ) | [private] |
Definition at line 244 of file cloud_handler.cpp.
| void CloudHandler::updateCloud | ( | sensor_msgs::PointCloud2 | cloud, |
| std::string | name | ||
| ) |
Definition at line 304 of file cloud_handler.cpp.
std::string CloudHandler::cloud_frame_ [private] |
Definition at line 108 of file cloud_handler.h.
pcl::PointCloud<pcl::Normal>::Ptr CloudHandler::cloud_normals_ [private] |
Definition at line 100 of file cloud_handler.h.
pcl::PointCloud<PointT>::Ptr CloudHandler::cloud_pts_ [private] |
Definition at line 99 of file cloud_handler.h.
actionlib::SimpleActionClient<point_cloud_server::StoreCloudAction> CloudHandler::cloud_server_client_ [private] |
Definition at line 106 of file cloud_handler.h.
bool CloudHandler::double_menu_ [private] |
Definition at line 103 of file cloud_handler.h.
std::string CloudHandler::head_pointing_frame_ [private] |
Definition at line 107 of file cloud_handler.h.
std::string CloudHandler::marker_name_ [private] |
Definition at line 90 of file cloud_handler.h.
Definition at line 95 of file cloud_handler.h.
Definition at line 105 of file cloud_handler.h.
Definition at line 96 of file cloud_handler.h.
sensor_msgs::PointCloud2 CloudHandler::msg_cloud_ [private] |
Definition at line 98 of file cloud_handler.h.
ros::NodeHandle* CloudHandler::nh_ [private] |
Definition at line 91 of file cloud_handler.h.
ros::Publisher CloudHandler::pub_focus_ [private] |
Definition at line 92 of file cloud_handler.h.
ros::Publisher CloudHandler::pub_left_click_ [private] |
Definition at line 92 of file cloud_handler.h.
Definition at line 92 of file cloud_handler.h.
ros::Publisher CloudHandler::pub_right_click_ [private] |
Definition at line 92 of file cloud_handler.h.
tf::TransformListener* CloudHandler::tfl_ [private] |
Definition at line 93 of file cloud_handler.h.
std::string CloudHandler::topic_ [private] |
Definition at line 90 of file cloud_handler.h.
pcl::search::KdTree<PointT>::Ptr CloudHandler::tree_ [private] |
Definition at line 101 of file cloud_handler.h.
double CloudHandler::voxel_size_ [private] |
Definition at line 102 of file cloud_handler.h.