Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request. More...

Public Member Functions | |
| void | ConvertToCloud (const string &fixed_frame_id, const sensor_msgs::PointCloud &scan_in, sensor_msgs::PointCloud &cloud_out) |
| unsigned int | GetPointsInScan (const sensor_msgs::PointCloud &scan) |
| Returns the number of points in the current scan. | |
| PointCloudAssemblerSrv () | |
| ~PointCloudAssemblerSrv () | |
Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request.
Definition at line 50 of file point_cloud_assembler_srv.cpp.
Definition at line 53 of file point_cloud_assembler_srv.cpp.
Definition at line 58 of file point_cloud_assembler_srv.cpp.
| void laser_assembler::PointCloudAssemblerSrv::ConvertToCloud | ( | const string & | fixed_frame_id, |
| const sensor_msgs::PointCloud & | scan_in, | ||
| sensor_msgs::PointCloud & | cloud_out | ||
| ) | [inline] |
Definition at line 68 of file point_cloud_assembler_srv.cpp.
| unsigned int laser_assembler::PointCloudAssemblerSrv::GetPointsInScan | ( | const sensor_msgs::PointCloud & | scan | ) | [inline, virtual] |
Returns the number of points in the current scan.
| scan | The scan for for which we want to know the number of points |
Implements laser_assembler::BaseAssemblerSrv< sensor_msgs::PointCloud >.
Definition at line 63 of file point_cloud_assembler_srv.cpp.