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

The class implements the tinySLAM-specific map update logic. More...

#include <tiny_world.h>

Inheritance diagram for TinyWorld:
Inheritance graph
[legend]

Public Types

using Point = DiscretePoint2D
 
- Public Types inherited from LaserScanGridWorld
using MapType = GridMap
 
using Point = DiscretePoint2D
 

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< GridScanMatcherscan_matcher ()
 
 TinyWorld (std::shared_ptr< GridCellStrategy > gcs, const TinyWorldParams &params, const GridMapParams &init_map_params)
 
- Public Member Functions inherited from LaserScanGridWorld
 LaserScanGridWorld (std::shared_ptr< GridCellStrategy > gcs, const GridMapParams &init_params)
 
virtual const MapTypemap () const
 Returns the map. More...
 
virtual MapTypemap ()
 
- Public Member Functions inherited from World< TransformedLaserScan, GridMap >
virtual const RobotStatepose () const
 Returns the robot pose. More...
 
virtual void update_robot_pose (double x, double y, double theta)
 
virtual const World< TransformedLaserScan, GridMap > & world () const
 Returns this world. More...
 

Private Attributes

std::shared_ptr< GridCellStrategy_gcs
 
const TinyWorldParams _params
 
std::shared_ptr< TinyScanMatcher_scan_matcher
 

Detailed Description

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.

Member Typedef Documentation

Definition at line 42 of file tiny_world.h.

Constructor & Destructor Documentation

TinyWorld::TinyWorld ( std::shared_ptr< GridCellStrategy gcs,
const TinyWorldParams params,
const GridMapParams init_map_params 
)
inline

Initializes the world to produce tiny SLAM.

Parameters
[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.

Member Function Documentation

virtual void TinyWorld::handle_observation ( TransformedLaserScan scan)
inlineoverridevirtual

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.

Parameters
[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 
)
inlineoverridevirtual

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".

Parameters
[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.

Reimplemented from LaserScanGridWorld.

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.

Member Data Documentation

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.


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


tiny_slam
Author(s):
autogenerated on Mon Jun 10 2019 15:30:57