Maintains a history of laser scans and generates a point cloud upon request. More...
Public Member Functions | |
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. | |
LaserScanAssembler () | |
void | scanCallback (const sensor_msgs::LaserScanConstPtr &laser_scan) |
~LaserScanAssembler () | |
Private Attributes | |
filters::FilterChain < sensor_msgs::LaserScan > | filter_chain_ |
bool | ignore_laser_skew_ |
ros::Duration | max_tolerance_ |
laser_geometry::LaserProjection | projector_ |
sensor_msgs::LaserScan | scan_filtered_ |
ros::Subscriber | skew_scan_sub_ |
Maintains a history of laser scans and generates a point cloud upon request.
Definition at line 50 of file laser_scan_assembler.cpp.
laser_assembler::LaserScanAssembler::LaserScanAssembler | ( | ) | [inline] |
Definition at line 53 of file laser_scan_assembler.cpp.
laser_assembler::LaserScanAssembler::~LaserScanAssembler | ( | ) | [inline] |
Definition at line 71 of file laser_scan_assembler.cpp.
void laser_assembler::LaserScanAssembler::ConvertToCloud | ( | const string & | fixed_frame_id, | |
const sensor_msgs::LaserScan & | scan_in, | |||
sensor_msgs::PointCloud & | cloud_out | |||
) | [inline] |
Definition at line 81 of file laser_scan_assembler.cpp.
unsigned int laser_assembler::LaserScanAssembler::GetPointsInScan | ( | const sensor_msgs::LaserScan & | 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::BaseAssembler< sensor_msgs::LaserScan >.
Definition at line 76 of file laser_scan_assembler.cpp.
void laser_assembler::LaserScanAssembler::scanCallback | ( | const sensor_msgs::LaserScanConstPtr & | laser_scan | ) | [inline] |
Definition at line 104 of file laser_scan_assembler.cpp.
filters::FilterChain<sensor_msgs::LaserScan> laser_assembler::LaserScanAssembler::filter_chain_ [private] |
Definition at line 127 of file laser_scan_assembler.cpp.
bool laser_assembler::LaserScanAssembler::ignore_laser_skew_ [private] |
Definition at line 121 of file laser_scan_assembler.cpp.
ros::Duration laser_assembler::LaserScanAssembler::max_tolerance_ [private] |
Definition at line 125 of file laser_scan_assembler.cpp.
laser_geometry::LaserProjection laser_assembler::LaserScanAssembler::projector_ [private] |
Definition at line 122 of file laser_scan_assembler.cpp.
sensor_msgs::LaserScan laser_assembler::LaserScanAssembler::scan_filtered_ [mutable, private] |
Definition at line 128 of file laser_scan_assembler.cpp.
ros::Subscriber laser_assembler::LaserScanAssembler::skew_scan_sub_ [private] |
Definition at line 124 of file laser_scan_assembler.cpp.