00001 00063 #ifndef __SEGMENTATION_VISUALIZER_H__ 00064 #define __SEGMENTATION_VISUALIZER_H__ 00065 00066 #include <ros/ros.h> 00067 #include <sensor_msgs/PointCloud2.h> 00068 00069 #include <pcl/point_types.h> 00070 #include <pcl/visualization/pcl_visualizer.h> 00071 00072 namespace cob_3d_segmentation 00073 { 00074 class SegmentationVisualizer 00075 { 00076 public: 00077 SegmentationVisualizer() : nh_(), v_(), v1_(0), v2_(0) 00078 { } 00079 00080 ~SegmentationVisualizer() 00081 { } 00082 00083 00084 inline void 00085 spinOnce() { v_.spinOnce(100); } 00086 00087 inline bool 00088 isRunning() { return !v_.wasStopped(); } 00089 00090 void 00091 init(); 00092 00093 00094 00095 protected: 00096 00097 void 00098 update_v1_cb(const sensor_msgs::PointCloud2::ConstPtr& cloud_in); 00099 00100 void 00101 update_v2_cb(const sensor_msgs::PointCloud2::ConstPtr& cloud_in); 00102 00103 ros::NodeHandle nh_; 00104 ros::Subscriber sub_v1_; 00105 ros::Subscriber sub_v2_; 00106 00107 pcl::visualization::PCLVisualizer v_; 00108 int v1_; 00109 int v2_; 00110 }; 00111 } 00112 00113 00114 #endif