#include <dense_laser_assembler.h>
Public Member Functions | |
| void | add (const sensor_msgs::LaserScanConstPtr &laser_scan) | 
| bool | 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.   | |
| DenseLaserAssembler (const unsigned int cache_size=100) | |
| void | setCacheSize (const unsigned int cache_size) | 
Private Member Functions | |
| 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.   | |
| bool | verifyMetadata (const calibration_msgs::DenseLaserSnapshot &snapshot, const sensor_msgs::LaserScan &scan) | 
| Internal data consistency check.   | |
Private Attributes | |
| settlerlib::SortedDeque < sensor_msgs::LaserScanConstPtr >  | cache_ | 
| Stores the history of laser scans.   | |
Definition at line 49 of file dense_laser_assembler.h.
| DenseLaserAssembler::DenseLaserAssembler | ( | const unsigned int | cache_size = 100 | ) | 
Definition at line 40 of file dense_laser_assembler.cpp.
| void DenseLaserAssembler::add | ( | const sensor_msgs::LaserScanConstPtr & | laser_scan | ) | 
Definition at line 51 of file dense_laser_assembler.cpp.
| 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.
| 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 | 
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.
| scans | Vector of laser scans | 
| snapshot | Output: A populated snapshot message | 
Definition at line 69 of file dense_laser_assembler.cpp.
| void DenseLaserAssembler::setCacheSize | ( | const unsigned int | cache_size | ) | 
Definition at line 46 of file dense_laser_assembler.cpp.
| 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.
| snapshot | The snapshot to compare against | 
| scan | the scan to compare against | 
Definition at line 153 of file dense_laser_assembler.cpp.
settlerlib::SortedDeque<sensor_msgs::LaserScanConstPtr> dense_laser_assembler::DenseLaserAssembler::cache_ [private] | 
        
Stores the history of laser scans.
Definition at line 70 of file dense_laser_assembler.h.