Public Member Functions | Private Attributes | List of all members
laser_assembler::LaserScanAssembler Class Reference

Maintains a history of laser scans and generates a point cloud upon request. More...

Inheritance diagram for laser_assembler::LaserScanAssembler:
Inheritance graph
[legend]

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. More...
 
 LaserScanAssembler ()
 
void scanCallback (const sensor_msgs::LaserScanConstPtr &laser_scan)
 
 ~LaserScanAssembler ()
 
- Public Member Functions inherited from laser_assembler::BaseAssembler< sensor_msgs::LaserScan >
 BaseAssembler (const std::string &max_size_param_name)
 
virtual void ConvertToCloud (const std::string &fixed_frame_id, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out)=0
 Converts the current scan into a cloud in the specified fixed frame. More...
 
void start (const std::string &in_topic_name)
 Tells the assembler to start listening to input data It is possible that a derived class needs to initialize and configure various things before actually beginning to process scans. Calling start create subcribes to the input stream, thus allowing the scanCallback and ConvertToCloud to be called. Start should be called only once. More...
 
void start ()
 
 ~BaseAssembler ()
 

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_
 

Additional Inherited Members

- Protected Attributes inherited from laser_assembler::BaseAssembler< sensor_msgs::LaserScan >
ros::NodeHandle n_
 
ros::NodeHandle private_ns_
 
tf::TransformListenertf_
 
tf::MessageFilter< sensor_msgs::LaserScan > * tf_filter_
 

Detailed Description

Maintains a history of laser scans and generates a point cloud upon request.

Definition at line 50 of file laser_scan_assembler.cpp.

Constructor & Destructor Documentation

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.

Member Function Documentation

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)
inlinevirtual

Returns the number of points in the current scan.

Parameters
scanThe scan for for which we want to know the number of points
Returns
the number of points in scan

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.

Member Data Documentation

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_
mutableprivate

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.


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


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Thu Jun 27 2019 19:56:21