Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef PR2_MARKER_CONTROL_CLOUD_HANDLER
00033 #define PR2_MARKER_CONTROL_CLOUD_HANDLER
00034
00035 #include <ros/ros.h>
00036
00037 #include <interactive_markers/interactive_marker_server.h>
00038 #include <interactive_markers/menu_handler.h>
00039 #include <sensor_msgs/PointCloud2.h>
00040
00041 #include <actionlib/client/simple_action_client.h>
00042 #include <point_cloud_server/StoreCloudAction.h>
00043 #include <pcl/search/kdtree.h>
00044 #include <tf/transform_listener.h>
00045 #include <object_manipulator/tools/mechanism_interface.h>
00046
00047 typedef pcl::PointXYZRGB PointT;
00048
00049
00050 class CloudHandler
00051 {
00052 public:
00053
00054 CloudHandler( ros::NodeHandle *nh, tf::TransformListener *tfl,
00055 std::string marker_name,
00056 std::string topic_name, std::string server_name,
00057 object_manipulator::MechanismInterface &mechanism,
00058 std::string cloud_frame);
00059
00060 ~CloudHandler();
00061
00063 void clear();
00064
00066 void refresh();
00067 void refresh(const std::string &topic);
00068 void updateCloud(sensor_msgs::PointCloud2 cloud, std::string name);
00069
00071 sensor_msgs::PointCloud2 get();
00072 void get(sensor_msgs::PointCloud2 &cloud);
00073
00074 private:
00075
00076 typedef interactive_markers::MenuHandler MenuHandler;
00077
00078 void makeMenu();
00079
00080 void pickup( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00081
00082 void makeMarker(float size);
00083
00084 void saveCloudAndNormals();
00085
00086 void menuPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00087 void menuFocus( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00088 void leftClickPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00089
00090 std::string marker_name_, topic_;
00091 ros::NodeHandle *nh_;
00092 ros::Publisher pub_left_click_, pub_right_click_, pub_refresh_flag_, pub_focus_;
00093 tf::TransformListener *tfl_;
00094
00095 interactive_markers::InteractiveMarkerServer marker_server_;
00096 interactive_markers::MenuHandler menu_handler_;
00097
00098 sensor_msgs::PointCloud2 msg_cloud_;
00099 pcl::PointCloud<PointT>::Ptr cloud_pts_;
00100 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_;
00101 pcl::search::KdTree<PointT>::Ptr tree_;
00102 double voxel_size_;
00103 bool double_menu_;
00104
00105 object_manipulator::MechanismInterface &mechanism_;
00106 actionlib::SimpleActionClient<point_cloud_server::StoreCloudAction> cloud_server_client_;
00107 std::string head_pointing_frame_;
00108 std::string cloud_frame_;
00109 };
00110
00111
00112
00113 #endif