Public Member Functions | Private Member Functions | Private Attributes
dense_laser_assembler::DenseLaserAssembler Class Reference

#include <dense_laser_assembler.h>

List of all members.

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.

Detailed Description

Definition at line 49 of file dense_laser_assembler.h.


Constructor & Destructor Documentation

DenseLaserAssembler::DenseLaserAssembler ( const unsigned int  cache_size = 100)

Definition at line 40 of file dense_laser_assembler.cpp.


Member Function Documentation

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.

Parameters:
startThe earliest scan time to be included in the snapshot
endThe 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:
scansVector of laser scans
snapshotOutput: 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)

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.

Parameters:
snapshotThe snapshot to compare against
scanthe scan to compare against
Returns:
True on success. False if metadata doesn't match

Definition at line 153 of file dense_laser_assembler.cpp.


Member Data Documentation

Stores the history of laser scans.

Definition at line 70 of file dense_laser_assembler.h.


The documentation for this class was generated from the following files:


dense_laser_assembler
Author(s): Vijay Pradeep
autogenerated on Wed Apr 3 2019 02:59:29