The class implements the tinySLAM-specific map update logic. More...
#include <tiny_world.h>

Public Member Functions | |
| virtual void | handle_observation (TransformedLaserScan &scan) override |
| virtual void | handle_scan_point (GridMap &map, double laser_x, double laser_y, double beam_end_x, double beam_end_y, bool is_occ, double quality) override |
| std::shared_ptr< GridScanMatcher > | scan_matcher () |
| TinyWorld (std::shared_ptr< GridCellStrategy > gcs, const TinyWorldParams ¶ms, const GridMapParams &init_map_params) | |
Private Attributes | |
| std::shared_ptr< GridCellStrategy > | _gcs |
| const TinyWorldParams | _params |
| std::shared_ptr< TinyScanMatcher > | _scan_matcher |
The class implements the tinySLAM-specific map update logic.
There is an robot state correction based on used scan matcher rules and the map update based on the algorithm from the paper with a wall blur.
Definition at line 40 of file tiny_world.h.
| TinyWorld::TinyWorld | ( | std::shared_ptr< GridCellStrategy > | gcs, |
| const TinyWorldParams & | params, | ||
| const GridMapParams & | init_map_params | ||
| ) | [inline] |
Initializes the world to produce tiny SLAM.
| [in] | gcs | - a shared pointer to a cell-specific strategy. |
| [in] | params | - the initial values for tinySLAM (see TinyWorldParams). |
Definition at line 50 of file tiny_world.h.
| virtual void TinyWorld::handle_observation | ( | TransformedLaserScan & | scan | ) | [inline, override, virtual] |
Updates the robot pose and the map by a prediction-correction scheme.
Updates the map depends on whether the robot pose have been changed during a correction step.
| [in] | scan | - data from a laser scanner. |
Reimplemented from LaserScanGridWorld.
Definition at line 64 of file tiny_world.h.
| virtual void TinyWorld::handle_scan_point | ( | GridMap & | map, |
| double | laser_x, | ||
| double | laser_y, | ||
| double | beam_end_x, | ||
| double | beam_end_y, | ||
| bool | is_occ, | ||
| double | quality | ||
| ) | [inline, override, virtual] |
Updates the map with a given laser scan point.
Estimates the occupancy of the cell with an obstacle (beam_end_x, beam_end_y).
And after that there is a "wall blur".
| [in] | map | - the map of the environment. |
| [in] | laser_x,laser_y | - the beginning coordinates of the laser ray. |
| [in] | beam_end_x,beam_end_y | - the ending coordinates of the laser ray |
| [in] | is_occ | - the parameter which shows whether this cell is occupied or not. |
| [in] | quality | - the quality of the laser scanner. |
Definition at line 88 of file tiny_world.h.
| std::shared_ptr<GridScanMatcher> TinyWorld::scan_matcher | ( | ) | [inline] |
Returns a pointer to the scan matcher used for the robot pose correction.
Definition at line 123 of file tiny_world.h.
std::shared_ptr<GridCellStrategy> TinyWorld::_gcs [private] |
Definition at line 127 of file tiny_world.h.
const TinyWorldParams TinyWorld::_params [private] |
Definition at line 128 of file tiny_world.h.
std::shared_ptr<TinyScanMatcher> TinyWorld::_scan_matcher [private] |
Definition at line 129 of file tiny_world.h.