Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request.
More...
|
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. More...
|
|
| PointCloudAssembler () |
|
| ~PointCloudAssembler () |
|
| BaseAssembler (const std::string &max_size_param_name) |
|
virtual void | ConvertToCloud (const std::string &fixed_frame_id, const sensor_msgs::PointCloud &scan_in, sensor_msgs::PointCloud &cloud_out)=0 |
| Converts the current scan into a cloud in the specified fixed frame. More...
|
|
void | start (const std::string &in_topic_name) |
| Tells the assembler to start listening to input data It is possible that a derived class needs to initialize and configure various things before actually beginning to process scans. Calling start create subcribes to the input stream, thus allowing the scanCallback and ConvertToCloud to be called. Start should be called only once. More...
|
|
void | start () |
|
| ~BaseAssembler () |
|
Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request.
- Todo:
- Clean up the doxygen part of this header params
Definition at line 50 of file point_cloud_assembler.cpp.
laser_assembler::PointCloudAssembler::PointCloudAssembler |
( |
| ) |
|
|
inline |
laser_assembler::PointCloudAssembler::~PointCloudAssembler |
( |
| ) |
|
|
inline |
void laser_assembler::PointCloudAssembler::ConvertToCloud |
( |
const string & |
fixed_frame_id, |
|
|
const sensor_msgs::PointCloud & |
scan_in, |
|
|
sensor_msgs::PointCloud & |
cloud_out |
|
) |
| |
|
inline |
unsigned int laser_assembler::PointCloudAssembler::GetPointsInScan |
( |
const sensor_msgs::PointCloud & |
scan | ) |
|
|
inlinevirtual |
The documentation for this class was generated from the following file: