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

#include <grid_scan_matcher.h>

Inheritance diagram for GridScanMatcher:
Inheritance graph
[legend]

Public Types

using ObsPtr = std::shared_ptr< GridScanMatcherObserver >
 
using SPE = std::shared_ptr< ScanProbabilityEstimator >
 
using SPEParams = ScanProbabilityEstimator::SPEParams
 

Public Member Functions

LaserScan2D filter_scan (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map)
 
 GridScanMatcher (SPE estimator, double max_x_error=0, double max_y_error=0, double max_th_error=0)
 
virtual double process_scan (const TransformedLaserScan &scan, const RobotPose &init_pose, const GridMap &map, RobotPoseDelta &pose_delta)=0
 
virtual void reset_state ()
 
double scan_probability (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map) const
 
double scan_probability (const LaserScan2D &scan, const RobotPose &pose, const GridMap &map, const SPEParams &p) const
 
SPE scan_probability_estimator () const
 
void set_lookup_ranges (double x, double y=0, double th=0)
 
void set_scan_probability_estimator (SPE spe)
 
void subscribe (std::shared_ptr< GridScanMatcherObserver > obs)
 
void unsubscribe (std::shared_ptr< GridScanMatcherObserver > obs)
 
virtual ~GridScanMatcher ()=default
 

Protected Member Functions

void do_for_each_observer (std::function< void(ObsPtr)> op)
 
double max_th_error ()
 
double max_x_error ()
 
double max_y_error ()
 
std::vector< std::weak_ptr< GridScanMatcherObserver > > & observers ()
 

Private Attributes

double _max_th_error = 0
 
double _max_x_error = 0
 
double _max_y_error = 0
 
std::vector< std::weak_ptr< GridScanMatcherObserver > > _observers
 
SPE _scan_prob_estimator
 

Detailed Description

Definition at line 99 of file grid_scan_matcher.h.

Member Typedef Documentation

Definition at line 101 of file grid_scan_matcher.h.

Definition at line 102 of file grid_scan_matcher.h.

Definition at line 103 of file grid_scan_matcher.h.

Constructor & Destructor Documentation

GridScanMatcher::GridScanMatcher ( SPE  estimator,
double  max_x_error = 0,
double  max_y_error = 0,
double  max_th_error = 0 
)
inline

Definition at line 105 of file grid_scan_matcher.h.

virtual GridScanMatcher::~GridScanMatcher ( )
virtualdefault

Member Function Documentation

void GridScanMatcher::do_for_each_observer ( std::function< void(ObsPtr)>  op)
inlineprotected

Definition at line 172 of file grid_scan_matcher.h.

LaserScan2D GridScanMatcher::filter_scan ( const LaserScan2D scan,
const RobotPose pose,
const GridMap map 
)
inline

Definition at line 143 of file grid_scan_matcher.h.

double GridScanMatcher::max_th_error ( )
inlineprotected

Definition at line 182 of file grid_scan_matcher.h.

double GridScanMatcher::max_x_error ( )
inlineprotected

Definition at line 180 of file grid_scan_matcher.h.

double GridScanMatcher::max_y_error ( )
inlineprotected

Definition at line 181 of file grid_scan_matcher.h.

std::vector<std::weak_ptr<GridScanMatcherObserver> >& GridScanMatcher::observers ( )
inlineprotected

Definition at line 168 of file grid_scan_matcher.h.

virtual double GridScanMatcher::process_scan ( const TransformedLaserScan scan,
const RobotPose init_pose,
const GridMap map,
RobotPoseDelta pose_delta 
)
pure virtual
virtual void GridScanMatcher::reset_state ( )
inlinevirtual

Reimplemented in PoseEnumerationScanMatcher, and ConnectTheDotsAmbiguousDriftDetector.

Definition at line 119 of file grid_scan_matcher.h.

double GridScanMatcher::scan_probability ( const LaserScan2D scan,
const RobotPose pose,
const GridMap map 
) const
inline

Definition at line 148 of file grid_scan_matcher.h.

double GridScanMatcher::scan_probability ( const LaserScan2D scan,
const RobotPose pose,
const GridMap map,
const SPEParams p 
) const
inline

Definition at line 153 of file grid_scan_matcher.h.

SPE GridScanMatcher::scan_probability_estimator ( ) const
inline

Definition at line 158 of file grid_scan_matcher.h.

void GridScanMatcher::set_lookup_ranges ( double  x,
double  y = 0,
double  th = 0 
)
inline

Definition at line 137 of file grid_scan_matcher.h.

void GridScanMatcher::set_scan_probability_estimator ( SPE  spe)
inline

Definition at line 162 of file grid_scan_matcher.h.

void GridScanMatcher::subscribe ( std::shared_ptr< GridScanMatcherObserver obs)
inline

Definition at line 121 of file grid_scan_matcher.h.

void GridScanMatcher::unsubscribe ( std::shared_ptr< GridScanMatcherObserver obs)
inline

Definition at line 125 of file grid_scan_matcher.h.

Member Data Documentation

double GridScanMatcher::_max_th_error = 0
private

Definition at line 187 of file grid_scan_matcher.h.

double GridScanMatcher::_max_x_error = 0
private

Definition at line 187 of file grid_scan_matcher.h.

double GridScanMatcher::_max_y_error = 0
private

Definition at line 187 of file grid_scan_matcher.h.

std::vector<std::weak_ptr<GridScanMatcherObserver> > GridScanMatcher::_observers
private

Definition at line 185 of file grid_scan_matcher.h.

SPE GridScanMatcher::_scan_prob_estimator
private

Definition at line 186 of file grid_scan_matcher.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