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
00033
00034
00035
00036
00037
00038 #ifndef PCL_ROS_SEGMENT_DIFFERENCES_H_
00039 #define PCL_ROS_SEGMENT_DIFFERENCES_H_
00040
00041 #include <pcl/segmentation/segment_differences.h>
00042 #include "pcl_ros/pcl_nodelet.h"
00043
00044
00045 #include <dynamic_reconfigure/server.h>
00046 #include "pcl_ros/SegmentDifferencesConfig.h"
00047
00048
00049 namespace pcl_ros
00050 {
00051 namespace sync_policies = message_filters::sync_policies;
00052
00056
00060 class SegmentDifferences : public PCLNodelet
00061 {
00062 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00063 typedef PointCloud::Ptr PointCloudPtr;
00064 typedef PointCloud::ConstPtr PointCloudConstPtr;
00065
00066 public:
00068 SegmentDifferences () {};
00069
00070 protected:
00072 message_filters::Subscriber<PointCloud> sub_target_filter_;
00073
00075 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud> > > sync_input_target_e_;
00076 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud> > > sync_input_target_a_;
00077
00079 boost::shared_ptr<dynamic_reconfigure::Server<SegmentDifferencesConfig> > srv_;
00080
00082 void onInit ();
00083
00088 void config_callback (SegmentDifferencesConfig &config, uint32_t level);
00089
00094 void input_target_callback (const PointCloudConstPtr &cloud,
00095 const PointCloudConstPtr &cloud_target);
00096
00097 private:
00099 pcl::SegmentDifferences<pcl::PointXYZ> impl_;
00100
00101 public:
00102 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00103 };
00104 }
00105
00106 #endif //#ifndef PCL_ROS_SEGMENT_DIFFERENCES_H_