38 #ifndef PCL_ROS_SEGMENT_DIFFERENCES_H_ 39 #define PCL_ROS_SEGMENT_DIFFERENCES_H_ 41 #include <pcl/segmentation/segment_differences.h> 45 #include <dynamic_reconfigure/server.h> 46 #include "pcl_ros/SegmentDifferencesConfig.h" 92 void config_callback (SegmentDifferencesConfig &config, uint32_t level);
99 const PointCloudConstPtr &cloud_target);
103 pcl::SegmentDifferences<pcl::PointXYZ>
impl_;
106 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
110 #endif //#ifndef PCL_ROS_SEGMENT_DIFFERENCES_H_ void config_callback(SegmentDifferencesConfig &config, uint32_t level)
Dynamic reconfigure callback.
SegmentDifferences()
Empty constructor.
void onInit()
Nodelet initialization routine.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud > > > sync_input_target_a_
PointCloud::ConstPtr PointCloudConstPtr
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud > > > sync_input_target_e_
Synchronized input, and planar hull.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
void input_target_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &cloud_target)
Input point cloud callback.
pcl::SegmentDifferences< pcl::PointXYZ > impl_
The PCL implementation used.
boost::shared_ptr< dynamic_reconfigure::Server< SegmentDifferencesConfig > > srv_
Pointer to a dynamic reconfigure service.
message_filters::Subscriber< PointCloud > sub_target_filter_
The message filter subscriber for PointCloud2.
void subscribe()
LazyNodelet connection routine.
pcl::PointCloud< pcl::PointXYZ > PointCloud
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the ...
PointCloud::Ptr PointCloudPtr