Class that matches scans. Performes a scan adjustment by altering a robot pose in order to maximize the correspondence between a scan and a grid map; the rule of correspondence computation is defined in ScanCostEstimator subclasses. More...
#include <grid_scan_matcher.h>

Public Member Functions | |
| GridScanMatcher (std::shared_ptr< ScanCostEstimator > estimator) | |
| virtual double | process_scan (const RobotState &init_pose, const TransformedLaserScan &scan, const GridMap &map, RobotState &pose_delta)=0 |
| virtual void | reset_state () |
| Invoked to reset the scan matcher's state. | |
| void | subscribe (std::shared_ptr< GridScanMatcherObserver > obs) |
| void | unsubscribe (std::shared_ptr< GridScanMatcherObserver > obs) |
Protected Member Functions | |
| std::shared_ptr < ScanCostEstimator > | cost_estimator () |
| Returns a pointer to the cost estimator. | |
| std::vector< std::weak_ptr < GridScanMatcherObserver > > & | observers () |
| Returns a reference to the vector of pointers on observers. | |
Private Attributes | |
| std::shared_ptr < ScanCostEstimator > | _cost_estimator |
| std::vector< std::weak_ptr < GridScanMatcherObserver > > | _observers |
Class that matches scans. Performes a scan adjustment by altering a robot pose in order to maximize the correspondence between a scan and a grid map; the rule of correspondence computation is defined in ScanCostEstimator subclasses.
Definition at line 84 of file grid_scan_matcher.h.
| GridScanMatcher::GridScanMatcher | ( | std::shared_ptr< ScanCostEstimator > | estimator | ) | [inline] |
Definition at line 86 of file grid_scan_matcher.h.
| std::shared_ptr<ScanCostEstimator> GridScanMatcher::cost_estimator | ( | ) | [inline, protected] |
Returns a pointer to the cost estimator.
Definition at line 131 of file grid_scan_matcher.h.
| std::vector<std::weak_ptr<GridScanMatcherObserver> >& GridScanMatcher::observers | ( | ) | [inline, protected] |
Returns a reference to the vector of pointers on observers.
Definition at line 136 of file grid_scan_matcher.h.
| virtual double GridScanMatcher::process_scan | ( | const RobotState & | init_pose, |
| const TransformedLaserScan & | scan, | ||
| const GridMap & | map, | ||
| RobotState & | pose_delta | ||
| ) | [pure virtual] |
A callback invoked on scan processing.
| init_pose | A pose of a robot. |
| scan | A laser scan with a transformation. |
| map | A grid map that is used by the matcher. |
| pose_delta | The difference between the real robot pose and its estimation. |
Implemented in MonteCarloScanMatcher.
| virtual void GridScanMatcher::reset_state | ( | ) | [inline, virtual] |
Invoked to reset the scan matcher's state.
Reimplemented in TinyScanMatcher.
Definition at line 103 of file grid_scan_matcher.h.
| void GridScanMatcher::subscribe | ( | std::shared_ptr< GridScanMatcherObserver > | obs | ) | [inline] |
Adds an observer.
| obs | A shared pointer to an observer to be added. |
Definition at line 109 of file grid_scan_matcher.h.
| void GridScanMatcher::unsubscribe | ( | std::shared_ptr< GridScanMatcherObserver > | obs | ) | [inline] |
Removes an observer.
| obs | A shared pointer to an observer to be removed |
Definition at line 117 of file grid_scan_matcher.h.
std::shared_ptr<ScanCostEstimator> GridScanMatcher::_cost_estimator [private] |
Definition at line 141 of file grid_scan_matcher.h.
std::vector<std::weak_ptr<GridScanMatcherObserver> > GridScanMatcher::_observers [private] |
Definition at line 140 of file grid_scan_matcher.h.