#include <dense_laser_assembler.h>
|
bool | flattenScanVec (const std::vector< sensor_msgs::LaserScanConstPtr > &scans, calibration_msgs::DenseLaserSnapshot &snapshot) |
| Takes a vector of LaserScan messages, and composes them into one larger snapshot. More...
|
|
bool | verifyMetadata (const calibration_msgs::DenseLaserSnapshot &snapshot, const sensor_msgs::LaserScan &scan) |
| Internal data consistency check. More...
|
|
Definition at line 49 of file dense_laser_assembler.h.
DenseLaserAssembler::DenseLaserAssembler |
( |
const unsigned int |
cache_size = 100 | ) |
|
void DenseLaserAssembler::add |
( |
const sensor_msgs::LaserScanConstPtr & |
laser_scan | ) |
|
bool DenseLaserAssembler::assembleSnapshot |
( |
const ros::Time & |
start, |
|
|
const ros::Time & |
end, |
|
|
calibration_msgs::DenseLaserSnapshot & |
snapshot |
|
) |
| |
Takes a vector of LaserScan messages, and composes them into one larger snapshot.
- Parameters
-
start | The earliest scan time to be included in the snapshot |
end | The latest scan time to be included in the snapshot |
output | A populated snapshot message |
- Returns
- True on success
Definition at line 56 of file dense_laser_assembler.cpp.
bool DenseLaserAssembler::flattenScanVec |
( |
const std::vector< sensor_msgs::LaserScanConstPtr > & |
scans, |
|
|
calibration_msgs::DenseLaserSnapshot & |
snapshot |
|
) |
| |
|
private |
Takes a vector of LaserScan messages, and composes them into one larger snapshot.
- Parameters
-
scans | Vector of laser scans |
snapshot | Output: A populated snapshot message |
- Returns
- True on success. Could fail if all the scans don't have the same metadata
Definition at line 69 of file dense_laser_assembler.cpp.
void DenseLaserAssembler::setCacheSize |
( |
const unsigned int |
cache_size | ) |
|
bool DenseLaserAssembler::verifyMetadata |
( |
const calibration_msgs::DenseLaserSnapshot & |
snapshot, |
|
|
const sensor_msgs::LaserScan & |
scan |
|
) |
| |
|
private |
Internal data consistency check.
A check to make sure that a scan's metadata matches the metadata of the snapshot.
- Parameters
-
snapshot | The snapshot to compare against |
scan | the scan to compare against |
- Returns
- True on success. False if metadata doesn't match
Definition at line 153 of file dense_laser_assembler.cpp.
The documentation for this class was generated from the following files: