37 #ifndef DENSE_LASER_ASSEMBLER_DENSE_LASER_ASSEMBLER_H_ 38 #define DENSE_LASER_ASSEMBLER_DENSE_LASER_ASSEMBLER_H_ 43 #include <sensor_msgs/LaserScan.h> 44 #include <calibration_msgs/DenseLaserSnapshot.h> 56 void add(
const sensor_msgs::LaserScanConstPtr& laser_scan);
79 bool flattenScanVec(
const std::vector< sensor_msgs::LaserScanConstPtr >& scans,
80 calibration_msgs::DenseLaserSnapshot& snapshot);
90 bool verifyMetadata(
const calibration_msgs::DenseLaserSnapshot& snapshot,
const sensor_msgs::LaserScan& scan);
DenseLaserAssembler(const unsigned int cache_size=100)
void add(const sensor_msgs::LaserScanConstPtr &laser_scan)
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.
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. ...
void setCacheSize(const unsigned int cache_size)
settlerlib::SortedDeque< sensor_msgs::LaserScanConstPtr > cache_
Stores the history of laser scans.