Public Member Functions | Private Types | Private Attributes | List of all members
LaserScanObserver Class Referenceabstract

Class responsibilities: observes laser scans and odometry; converts ROS structures to internal representation. More...

#include <laser_scan_observer.h>

Inheritance diagram for LaserScanObserver:
Inheritance graph
[legend]

Public Member Functions

virtual void handle_laser_scan (TransformedLaserScan &)=0
 
virtual void handle_transformed_msg (const ScanPtr msg, const tf::StampedTransform &t)
 Converts ROS-specific structures that hold sensor data to internal framework's structures; Laser scan filtering is performed as part of the conversion. More...
 
 LaserScanObserver (bool skip_max_vals=false)
 
- Public Member Functions inherited from TopicObserver< sensor_msgs::LaserScan >
virtual void handle_transformed_msg (const boost::shared_ptr< sensor_msgs::LaserScan >, const tf::StampedTransform &)=0
 

Private Types

using ScanPtr = boost::shared_ptr< sensor_msgs::LaserScan >
 

Private Attributes

double _prev_x
 
double _prev_y
 
double _prev_yaw
 
bool _skip_max_vals
 

Detailed Description

Class responsibilities: observes laser scans and odometry; converts ROS structures to internal representation.

Definition at line 15 of file laser_scan_observer.h.

Member Typedef Documentation

using LaserScanObserver::ScanPtr = boost::shared_ptr<sensor_msgs::LaserScan>
private

Definition at line 16 of file laser_scan_observer.h.

Constructor & Destructor Documentation

LaserScanObserver::LaserScanObserver ( bool  skip_max_vals = false)
inline

Initializes the base laser scan observer.

Parameters
skip_max_valsWhether scan points that exceed the max reliable scan-specific distance be skipped.

Definition at line 22 of file laser_scan_observer.h.

Member Function Documentation

virtual void LaserScanObserver::handle_laser_scan ( TransformedLaserScan )
pure virtual

Implemented in TinySlamFascade.

virtual void LaserScanObserver::handle_transformed_msg ( const ScanPtr  msg,
const tf::StampedTransform t 
)
inlinevirtual

Converts ROS-specific structures that hold sensor data to internal framework's structures; Laser scan filtering is performed as part of the conversion.

Parameters
msgA ROS specific laser scan message.
tA TF specific transform.

Definition at line 31 of file laser_scan_observer.h.

Member Data Documentation

double LaserScanObserver::_prev_x
private

Definition at line 70 of file laser_scan_observer.h.

double LaserScanObserver::_prev_y
private

Definition at line 70 of file laser_scan_observer.h.

double LaserScanObserver::_prev_yaw
private

Definition at line 70 of file laser_scan_observer.h.

bool LaserScanObserver::_skip_max_vals
private

Definition at line 69 of file laser_scan_observer.h.


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


tiny_slam
Author(s):
autogenerated on Mon Jun 10 2019 15:30:57