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

#include <laser_scan_observer.h>

Inheritance diagram for LaserScanObserver:
Inheritance graph
[legend]

Public Member Functions

virtual void handle_transformed_msg (const ScanPtr msg, const tf::StampedTransform &t)
 
 LaserScanObserver (DstPtr slam, bool skip_max_vals, bool use_cached_trig)
 
const RobotPoseodometry_pose () const
 
void set_odometry_pose (const RobotPose &pose)
 
- 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 DstPtr = std::shared_ptr< SensorDataObserver< TransformedLaserScan >>
 
using ScanPtr = boost::shared_ptr< sensor_msgs::LaserScan >
 

Private Member Functions

std::shared_ptr< TrigonometryProvidertrig_provider (const ScanPtr msg)
 

Private Attributes

RobotPose _prev_pose
 
bool _skip_max_vals
 
DstPtr _slam
 
bool _use_cached_trig_provider
 

Detailed Description

Definition at line 17 of file laser_scan_observer.h.

Member Typedef Documentation

Definition at line 19 of file laser_scan_observer.h.

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

Definition at line 18 of file laser_scan_observer.h.

Constructor & Destructor Documentation

LaserScanObserver::LaserScanObserver ( DstPtr  slam,
bool  skip_max_vals,
bool  use_cached_trig 
)
inline

Definition at line 22 of file laser_scan_observer.h.

Member Function Documentation

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

Definition at line 28 of file laser_scan_observer.h.

const RobotPose& LaserScanObserver::odometry_pose ( ) const
inline

Definition at line 69 of file laser_scan_observer.h.

void LaserScanObserver::set_odometry_pose ( const RobotPose pose)
inline

Definition at line 70 of file laser_scan_observer.h.

std::shared_ptr<TrigonometryProvider> LaserScanObserver::trig_provider ( const ScanPtr  msg)
inlineprivate

Definition at line 74 of file laser_scan_observer.h.

Member Data Documentation

RobotPose LaserScanObserver::_prev_pose
private

Definition at line 89 of file laser_scan_observer.h.

bool LaserScanObserver::_skip_max_vals
private

Definition at line 87 of file laser_scan_observer.h.

DstPtr LaserScanObserver::_slam
private

Definition at line 86 of file laser_scan_observer.h.

bool LaserScanObserver::_use_cached_trig_provider
private

Definition at line 88 of file laser_scan_observer.h.


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


slam_constructor
Author(s): JetBrains Research, OSLL team
autogenerated on Mon Jun 10 2019 15:08:26