Public Member Functions | Private Attributes
TinySlamFascade Class Reference

The TinySLAM access point. SLAM users are supposed to work with it. More...

#include <tiny_fascade.h>

Inheritance diagram for TinySlamFascade:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void add_scan_matcher_observer (ScanMatcherObsPtr obs)
virtual void handle_laser_scan (TransformedLaserScan &scan)
void remove_scan_matcher_observer (ScanMatcherObsPtr obs)
void set_viewer (std::shared_ptr< RvizGridViewer > viewer)
 TinySlamFascade (std::shared_ptr< GridCellStrategy > gcs, const TinyWorldParams &params, const GridMapParams &init_map_params, bool skip_max_vals)

Private Attributes

std::shared_ptr< RvizGridViewer_viewer
std::unique_ptr< TinyWorld_world

Detailed Description

The TinySLAM access point. SLAM users are supposed to work with it.

Responsibilities:
  Handles data came from a scanner and locates a viewer.
  Connects internal frameworks components to a single tinySLAM method (the fascade pattern is applied).

Definition at line 21 of file tiny_fascade.h.


Constructor & Destructor Documentation

TinySlamFascade::TinySlamFascade ( std::shared_ptr< GridCellStrategy gcs,
const TinyWorldParams params,
const GridMapParams init_map_params,
bool  skip_max_vals 
) [inline]

Initializes the tinySLAM method.

Parameters:
[in]gcs- a configuration of cells in a map (a cell strategy).
[in]params- the tinySLAM parameters (see TinyWorldParams).
[in]skip_max_vals- whether the values that exceed the max one specific to the laser scanner should be skipped.

Definition at line 34 of file tiny_fascade.h.


Member Function Documentation

void TinySlamFascade::add_scan_matcher_observer ( ScanMatcherObsPtr  obs) [inline]

Registers a scan matcher observer.

Parameters:
[in]obs- a new scanner matcher observer.

Definition at line 69 of file tiny_fascade.h.

virtual void TinySlamFascade::handle_laser_scan ( TransformedLaserScan scan) [inline, virtual]

Updates the map and the robot pose with scan data.
The update is done according to a prediction-correction approach. (the odometry is used for a prediction, the laser scan - for a correction).

Parameters:
[in]scan- data from the robot's scanners (odnometry + laser scan).

Implements LaserScanObserver.

Definition at line 55 of file tiny_fascade.h.

void TinySlamFascade::remove_scan_matcher_observer ( ScanMatcherObsPtr  obs) [inline]

Unregisters a scan matcher observer.

Parameters:
[in]obs- the scanner matcher observer to be removed.

Definition at line 77 of file tiny_fascade.h.

void TinySlamFascade::set_viewer ( std::shared_ptr< RvizGridViewer viewer) [inline]

Sets a viewer component that is notified by a pose and map updates.

Parameters:
[in]viewer- a new value of the data member viewer.

Definition at line 45 of file tiny_fascade.h.


Member Data Documentation

std::shared_ptr<RvizGridViewer> TinySlamFascade::_viewer [private]

Definition at line 84 of file tiny_fascade.h.

std::unique_ptr<TinyWorld> TinySlamFascade::_world [private]

Definition at line 83 of file tiny_fascade.h.


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


tiny_slam
Author(s):
autogenerated on Mon Jul 17 2017 02:33:43