|
void | ConvertToCloud (const string &fixed_frame_id, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out) |
|
unsigned int | GetPointsInScan (const sensor_msgs::LaserScan &scan) |
| Returns the number of points in the current scan. More...
|
|
| LaserScanAssemblerSrv () |
|
| ~LaserScanAssemblerSrv () |
|
| BaseAssemblerSrv () |
|
virtual void | ConvertToCloud (const std::string &fixed_frame_id, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out)=0 |
| Converts the current scan into a cloud in the specified fixed frame. More...
|
|
void | start () |
| 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...
|
|
| ~BaseAssemblerSrv () |
|
Maintains a history of laser scans and generates a point cloud upon request.
ROS Parameters
- (Several params are inherited from laser_assembler::BaseAssemblerSrv)
- "~ignore_laser_skew" (bool) - Specifies the method to project laser data
- true -> Account for laser skew, and compute the transform for each laser point (This is currently really slow!)
- false-> Don't account for laser skew, and use 1 transform per scanline. (This might have a little error when moving fast)
ROS Service Calls
Definition at line 57 of file laser_scan_assembler_srv.cpp.