Segments the difference of two point clouds (e.g. a point map and new sensor data) and publishes the difference. More...

Public Member Functions | |
| DifferenceSegmentation () | |
| void | onInit () |
| initializes parameters | |
| void | pointCloudSubCallback (const sensor_msgs::PointCloud2::ConstPtr &map_msg, const sensor_msgs::PointCloud2::ConstPtr &pc_aligned_msg) |
| callback for point cloud subroutine | |
| ~DifferenceSegmentation () | |
Protected Attributes | |
| pcl::PointCloud< Point > | map_ |
| ros::Publisher | map_diff_pub_ |
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | map_sub_ |
| ros::NodeHandle | n_ |
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | pc_aligned_sub_ |
| pcl::SegmentDifferences< Point > | sd_ |
| boost::shared_ptr < message_filters::Synchronizer < MySyncPolicy > > | sync_ |
Private Types | |
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | MySyncPolicy |
| typedef pcl::PointXYZRGB | Point |
| typedef pcl::PointCloud< Point > | PointCloud |
Segments the difference of two point clouds (e.g. a point map and new sensor data) and publishes the difference.
Definition at line 91 of file difference_segmentation.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > DifferenceSegmentation::MySyncPolicy [private] |
Definition at line 95 of file difference_segmentation.cpp.
typedef pcl::PointXYZRGB DifferenceSegmentation::Point [private] |
Definition at line 93 of file difference_segmentation.cpp.
typedef pcl::PointCloud<Point> DifferenceSegmentation::PointCloud [private] |
Definition at line 94 of file difference_segmentation.cpp.
| DifferenceSegmentation::DifferenceSegmentation | ( | ) | [inline] |
Definition at line 99 of file difference_segmentation.cpp.
| DifferenceSegmentation::~DifferenceSegmentation | ( | ) | [inline] |
void
Definition at line 104 of file difference_segmentation.cpp.
| void DifferenceSegmentation::onInit | ( | ) | [inline, virtual] |
initializes parameters
initializes parameters
Implements nodelet::Nodelet.
Definition at line 117 of file difference_segmentation.cpp.
| void DifferenceSegmentation::pointCloudSubCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | map_msg, |
| const sensor_msgs::PointCloud2::ConstPtr & | pc_aligned_msg | ||
| ) | [inline] |
callback for point cloud subroutine
callback for point cloud subroutine which stores the point cloud for further calculation
| pc_in | new point cloud |
Definition at line 144 of file difference_segmentation.cpp.
pcl::PointCloud<Point> DifferenceSegmentation::map_ [protected] |
Definition at line 181 of file difference_segmentation.cpp.
ros::Publisher DifferenceSegmentation::map_diff_pub_ [protected] |
Definition at line 178 of file difference_segmentation.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2 > DifferenceSegmentation::map_sub_ [protected] |
Definition at line 176 of file difference_segmentation.cpp.
ros::NodeHandle DifferenceSegmentation::n_ [protected] |
Definition at line 175 of file difference_segmentation.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2 > DifferenceSegmentation::pc_aligned_sub_ [protected] |
Definition at line 177 of file difference_segmentation.cpp.
pcl::SegmentDifferences<Point> DifferenceSegmentation::sd_ [protected] |
Definition at line 182 of file difference_segmentation.cpp.
boost::shared_ptr<message_filters::Synchronizer<MySyncPolicy> > DifferenceSegmentation::sync_ [protected] |
Definition at line 179 of file difference_segmentation.cpp.