Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
karto::Mapper Class Reference

#include <Mapper.h>

Inheritance diagram for karto::Mapper:
Inheritance graph
[legend]

Public Member Functions

void AddListener (MapperListener *pListener)
 
void FireBeginLoopClosure (const std::string &rInfo) const
 
void FireDebug (const std::string &rInfo) const
 
void FireEndLoopClosure (const std::string &rInfo) const
 
void FireInfo (const std::string &rInfo) const
 
void FireLoopClosureCheck (const std::string &rInfo) const
 
virtual const LocalizedRangeScanVector GetAllProcessedScans () const
 
virtual MapperGraphGetGraph () const
 
virtual ScanMatcherGetLoopScanMatcher () const
 
MapperSensorManagerGetMapperSensorManager () const
 
double getParamAngleVariancePenalty ()
 
double getParamCoarseAngleResolution ()
 
double getParamCoarseSearchAngleOffset ()
 
double getParamCorrelationSearchSpaceDimension ()
 
double getParamCorrelationSearchSpaceResolution ()
 
double getParamCorrelationSearchSpaceSmearDeviation ()
 
double getParamDistanceVariancePenalty ()
 
bool getParamDoLoopClosing ()
 
double getParamFineSearchAngleOffset ()
 
double getParamLinkMatchMinimumResponseFine ()
 
double getParamLinkScanMaximumDistance ()
 
double getParamLoopMatchMaximumVarianceCoarse ()
 
int getParamLoopMatchMinimumChainSize ()
 
double getParamLoopMatchMinimumResponseCoarse ()
 
double getParamLoopMatchMinimumResponseFine ()
 
double getParamLoopSearchMaximumDistance ()
 
double getParamLoopSearchSpaceDimension ()
 
double getParamLoopSearchSpaceResolution ()
 
double getParamLoopSearchSpaceSmearDeviation ()
 
double getParamMinimumAnglePenalty ()
 
double getParamMinimumDistancePenalty ()
 
double getParamMinimumTimeInterval ()
 
double getParamMinimumTravelDistance ()
 
double getParamMinimumTravelHeading ()
 
double getParamScanBufferMaximumScanDistance ()
 
int getParamScanBufferSize ()
 
bool getParamUseResponseExpansion ()
 
bool getParamUseScanBarycenter ()
 
bool getParamUseScanMatching ()
 
virtual ScanMatcherGetSequentialScanMatcher () const
 
void Initialize (kt_double rangeThreshold)
 
 Mapper ()
 
 Mapper (const std::string &rName)
 
virtual kt_bool Process (LocalizedRangeScan *pScan)
 
virtual kt_bool Process (Object *pObject)
 
void RemoveListener (MapperListener *pListener)
 
void Reset ()
 
void setParamAngleVariancePenalty (double d)
 
void setParamCoarseAngleResolution (double d)
 
void setParamCoarseSearchAngleOffset (double d)
 
void setParamCorrelationSearchSpaceDimension (double d)
 
void setParamCorrelationSearchSpaceResolution (double d)
 
void setParamCorrelationSearchSpaceSmearDeviation (double d)
 
void setParamDistanceVariancePenalty (double d)
 
void setParamDoLoopClosing (bool b)
 
void setParamFineSearchAngleOffset (double d)
 
void setParamLinkMatchMinimumResponseFine (double d)
 
void setParamLinkScanMaximumDistance (double d)
 
void setParamLoopMatchMaximumVarianceCoarse (double d)
 
void setParamLoopMatchMinimumChainSize (int i)
 
void setParamLoopMatchMinimumResponseCoarse (double d)
 
void setParamLoopMatchMinimumResponseFine (double d)
 
void setParamLoopSearchMaximumDistance (double d)
 
void setParamLoopSearchSpaceDimension (double d)
 
void setParamLoopSearchSpaceResolution (double d)
 
void setParamLoopSearchSpaceSmearDeviation (double d)
 
void setParamMinimumAnglePenalty (double d)
 
void setParamMinimumDistancePenalty (double d)
 
void setParamMinimumTimeInterval (double d)
 
void setParamMinimumTravelDistance (double d)
 
void setParamMinimumTravelHeading (double d)
 
void setParamScanBufferMaximumScanDistance (double d)
 
void setParamScanBufferSize (int i)
 
void setParamUseResponseExpansion (bool b)
 
void setParamUseScanBarycenter (bool b)
 
void setParamUseScanMatching (bool b)
 
void SetScanSolver (ScanSolver *pSolver)
 
void SetUseScanMatching (kt_bool val)
 
kt_bool TryCloseLoop (LocalizedRangeScan *pScan, const Name &rSensorName)
 
virtual ~Mapper ()
 
- Public Member Functions inherited from karto::Module
 Module (const std::string &rName)
 
virtual ~Module ()
 
- Public Member Functions inherited from karto::Object
virtual const char * GetClassName () const =0
 
const NameGetName () const
 
virtual kt_objecttype GetObjectType () const =0
 
AbstractParameterGetParameter (const std::string &rName) const
 
virtual ParameterManagerGetParameterManager ()
 
const ParameterVectorGetParameters () const
 
 Object ()
 
 Object (const Name &rName)
 
template<typename T >
void SetParameter (const std::string &rName, T value)
 
virtual ~Object ()
 

Private Member Functions

kt_bool HasMovedEnough (LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
 
void InitializeParameters ()
 
 Mapper (const Mapper &)
 
const Mapperoperator= (const Mapper &)
 

Private Attributes

kt_bool m_Initialized
 
std::vector< MapperListener * > m_Listeners
 
Parameter< kt_double > * m_pAngleVariancePenalty
 
Parameter< kt_double > * m_pCoarseAngleResolution
 
Parameter< kt_double > * m_pCoarseSearchAngleOffset
 
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
 
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
 
Parameter< kt_double > * m_pCorrelationSearchSpaceSmearDeviation
 
Parameter< kt_double > * m_pDistanceVariancePenalty
 
Parameter< kt_bool > * m_pDoLoopClosing
 
Parameter< kt_double > * m_pFineSearchAngleOffset
 
MapperGraphm_pGraph
 
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
 
Parameter< kt_double > * m_pLinkScanMaximumDistance
 
Parameter< kt_double > * m_pLoopMatchMaximumVarianceCoarse
 
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
 
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
 
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
 
Parameter< kt_double > * m_pLoopSearchMaximumDistance
 
Parameter< kt_double > * m_pLoopSearchSpaceDimension
 
Parameter< kt_double > * m_pLoopSearchSpaceResolution
 
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
 
MapperSensorManagerm_pMapperSensorManager
 
Parameter< kt_double > * m_pMinimumAnglePenalty
 
Parameter< kt_double > * m_pMinimumDistancePenalty
 
Parameter< kt_double > * m_pMinimumTimeInterval
 
Parameter< kt_double > * m_pMinimumTravelDistance
 
Parameter< kt_double > * m_pMinimumTravelHeading
 
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
 
Parameter< kt_int32u > * m_pScanBufferSize
 
ScanSolverm_pScanOptimizer
 
ScanMatcherm_pSequentialScanMatcher
 
Parameter< kt_bool > * m_pUseResponseExpansion
 
Parameter< kt_bool > * m_pUseScanBarycenter
 
Parameter< kt_bool > * m_pUseScanMatching
 

Friends

class MapperGraph
 
class ScanMatcher
 

Additional Inherited Members

- Protected Member Functions inherited from karto::NonCopyable
 NonCopyable ()
 
virtual ~NonCopyable ()
 

Detailed Description

Graph SLAM mapper. Creates a map given a set of LocalizedRangeScans The current Karto implementation is a proprietary, high-performance scan-matching algorithm that constructs a map from individual range scans and corrects for errors in the range and odometry data.

The following parameters can be set on the Mapper.

UseScanMatching (ParameterBool)
When set to true, the mapper will use a scan matching algorithm. In most real-world situations this should be set to true so that the mapper algorithm can correct for noise and errors in odometry and scan data. In some simulator environments where the simulated scan and odometry data are very accurate, the scan matching algorithm can produce worse results. In those cases set to false to improve results. Default value is true.

UseScanBarycenter (ParameterBool)
UseResponseExpansion (ParameterBool)
RangeThreshold (ParameterDouble - meters)
The range threshold is used to truncate range scan distance measurement readings. The threshold should be set such that adjacent range readings in a scan will generally give "solid" coverage of objects.

Having solid coverage depends on the map resolution and the angular resolution of the range scan device. The following are the recommended threshold values for the corresponding map resolution and range finder resolution values:

Map Resolution Laser Angular Resolution
1.0 degree 0.5 degree 0.25 degree
0.1 5.7m 11.4m 22.9m
0.05 2.8m 5.7m 11.4m
0.01 0.5m 1.1m 2.3m

Note that the value of RangeThreshold should be adjusted taking into account the values of MinimumTravelDistance and MinimumTravelHeading (see also below). By incorporating scans into the map more frequently, the RangeThreshold value can be increased as the additional scans will "fill in" the gaps of objects at greater distances where there is less solid coverage.

Default value is 12.0 (meters).

MinimumTravelDistance (ParameterDouble - meters)
Sets the minimum travel between scans. If a new scan's position is more than minimumDistance from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum change in heading requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.3 (meters).

MinimumTravelHeading (ParameterDouble - radians)
Sets the minimum heading change between scans. If a new scan's heading is more than minimumHeading from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.08726646259971647 (radians) - 5 degrees.

ScanBufferSize (ParameterIn32u - size)
Scan buffer size is the length of the scan chain stored for scan matching. "ScanBufferSize" should be set to approximately "ScanBufferMaximumScanDistance" / "MinimumTravelDistance". The idea is to get an area approximately 20 meters long for scan matching. For example, if we add scans every MinimumTravelDistance = 0.3 meters, then "ScanBufferSize" should be 20 / 0.3 = 67.) Default value is 67.

ScanBufferMaximumScanDistance (ParameterDouble - meters)
Scan buffer maximum scan distance is the maximum distance between the first and last scans in the scan chain stored for matching. Default value is 20.0.

CorrelationSearchSpaceDimension (ParameterDouble - meters)
The size of the correlation grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

CorrelationSearchSpaceResolution (ParameterDouble - meters)
The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

CorrelationSearchSpaceSmearDeviation (ParameterDouble - meters)
The robot position is smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

LinkMatchMinimumResponseFine (ParameterDouble - probability (>= 0.0, <= 1.0))
Scans are linked only if the correlation response value is greater than this value. Default value is 0.4

LinkScanMaximumDistance (ParameterDouble - meters)
Maximum distance between linked scans. Scans that are farther apart will not be linked regardless of the correlation response value. Default value is 6.0 meters.

LoopSearchSpaceDimension (ParameterDouble - meters)
Dimension of the correlation grid used by the loop closure detection algorithm Default value is 4.0 meters.

LoopSearchSpaceResolution (ParameterDouble - meters)
Coarse resolution of the correlation grid used by the matcher to determine a possible loop closure. Default value is 0.05 meters.

LoopSearchSpaceSmearDeviation (ParameterDouble - meters)
Smearing distance in the correlation grid used by the matcher to determine a possible loop closure match. Default value is 0.03 meters.

LoopSearchMaximumDistance (ParameterDouble - meters)
Scans less than this distance from the current position will be considered for a match in loop closure. Default value is 4.0 meters.

LoopMatchMinimumChainSize (ParameterIn32s)
When the loop closure detection finds a candidate it must be part of a large set of linked scans. If the chain of scans is less than this value we do not attempt to close the loop. Default value is 10.

LoopMatchMaximumVarianceCoarse (ParameterDouble)
The co-variance values for a possible loop closure have to be less than this value to consider a viable solution. This applies to the coarse search. Default value is 0.16.

LoopMatchMinimumResponseCoarse (ParameterDouble - probability (>= 0.0, <= 1.0))
If response is larger then this then initiate loop closure search at the coarse resolution. Default value is 0.7.

LoopMatchMinimumResponseFine (ParameterDouble - probability (>= 0.0, <= 1.0))
If response is larger then this then initiate loop closure search at the fine resolution. Default value is 0.5.

Definition at line 1750 of file Mapper.h.

Constructor & Destructor Documentation

◆ Mapper() [1/3]

karto::Mapper::Mapper ( )

Default constructor

Definition at line 1342 of file Mapper.cpp.

◆ Mapper() [2/3]

karto::Mapper::Mapper ( const std::string &  rName)

Constructor a mapper with a name

Parameters
rNamemapper name

Default constructor

Definition at line 1356 of file Mapper.cpp.

◆ ~Mapper()

karto::Mapper::~Mapper ( )
virtual

Destructor

Definition at line 1370 of file Mapper.cpp.

◆ Mapper() [3/3]

karto::Mapper::Mapper ( const Mapper )
private

Restrict the copy constructor

Member Function Documentation

◆ AddListener()

void karto::Mapper::AddListener ( MapperListener pListener)

Add a listener to mapper

Parameters
pListenerAdds a listener
pListener

Definition at line 2071 of file Mapper.cpp.

◆ FireBeginLoopClosure()

void karto::Mapper::FireBeginLoopClosure ( const std::string &  rInfo) const

Fire a message before loop closure to listeners

Parameters
rInfo

Definition at line 2123 of file Mapper.cpp.

◆ FireDebug()

void karto::Mapper::FireDebug ( const std::string &  rInfo) const

Fire a debug message to listeners

Parameters
rInfo

Definition at line 2097 of file Mapper.cpp.

◆ FireEndLoopClosure()

void karto::Mapper::FireEndLoopClosure ( const std::string &  rInfo) const

Fire a message after loop closure to listeners

Parameters
rInfo

Definition at line 2136 of file Mapper.cpp.

◆ FireInfo()

void karto::Mapper::FireInfo ( const std::string &  rInfo) const

Fire a general message to listeners

Parameters
rInfo

Definition at line 2089 of file Mapper.cpp.

◆ FireLoopClosureCheck()

void karto::Mapper::FireLoopClosureCheck ( const std::string &  rInfo) const

Fire a message upon checking for loop closure to listeners

Parameters
rInfo

Definition at line 2110 of file Mapper.cpp.

◆ GetAllProcessedScans()

const LocalizedRangeScanVector karto::Mapper::GetAllProcessedScans ( ) const
virtual

Returns all processed scans added to the mapper. NOTE: The returned scans have their corrected pose updated.

Returns
list of scans received and processed by the mapper. If no scans have been processed, return an empty list.

Gets all the processed scans

Returns
all scans

Definition at line 2055 of file Mapper.cpp.

◆ GetGraph()

MapperGraph * karto::Mapper::GetGraph ( ) const
virtual

Get scan link graph

Returns
graph

Definition at line 2154 of file Mapper.cpp.

◆ GetLoopScanMatcher()

ScanMatcher * karto::Mapper::GetLoopScanMatcher ( ) const
virtual

Gets the loop scan matcher

Returns
loop scan matcher

Definition at line 2164 of file Mapper.cpp.

◆ GetMapperSensorManager()

MapperSensorManager* karto::Mapper::GetMapperSensorManager ( ) const
inline

Gets the device manager

Returns
device manager

Definition at line 1851 of file Mapper.h.

◆ getParamAngleVariancePenalty()

double karto::Mapper::getParamAngleVariancePenalty ( )

Definition at line 1704 of file Mapper.cpp.

◆ getParamCoarseAngleResolution()

double karto::Mapper::getParamCoarseAngleResolution ( )

Definition at line 1719 of file Mapper.cpp.

◆ getParamCoarseSearchAngleOffset()

double karto::Mapper::getParamCoarseSearchAngleOffset ( )

Definition at line 1714 of file Mapper.cpp.

◆ getParamCorrelationSearchSpaceDimension()

double karto::Mapper::getParamCorrelationSearchSpaceDimension ( )

Definition at line 1665 of file Mapper.cpp.

◆ getParamCorrelationSearchSpaceResolution()

double karto::Mapper::getParamCorrelationSearchSpaceResolution ( )

Definition at line 1670 of file Mapper.cpp.

◆ getParamCorrelationSearchSpaceSmearDeviation()

double karto::Mapper::getParamCorrelationSearchSpaceSmearDeviation ( )

Definition at line 1675 of file Mapper.cpp.

◆ getParamDistanceVariancePenalty()

double karto::Mapper::getParamDistanceVariancePenalty ( )

Definition at line 1699 of file Mapper.cpp.

◆ getParamDoLoopClosing()

bool karto::Mapper::getParamDoLoopClosing ( )

Definition at line 1638 of file Mapper.cpp.

◆ getParamFineSearchAngleOffset()

double karto::Mapper::getParamFineSearchAngleOffset ( )

Definition at line 1709 of file Mapper.cpp.

◆ getParamLinkMatchMinimumResponseFine()

double karto::Mapper::getParamLinkMatchMinimumResponseFine ( )

Definition at line 1623 of file Mapper.cpp.

◆ getParamLinkScanMaximumDistance()

double karto::Mapper::getParamLinkScanMaximumDistance ( )

Definition at line 1628 of file Mapper.cpp.

◆ getParamLoopMatchMaximumVarianceCoarse()

double karto::Mapper::getParamLoopMatchMaximumVarianceCoarse ( )

Definition at line 1648 of file Mapper.cpp.

◆ getParamLoopMatchMinimumChainSize()

int karto::Mapper::getParamLoopMatchMinimumChainSize ( )

Definition at line 1643 of file Mapper.cpp.

◆ getParamLoopMatchMinimumResponseCoarse()

double karto::Mapper::getParamLoopMatchMinimumResponseCoarse ( )

Definition at line 1653 of file Mapper.cpp.

◆ getParamLoopMatchMinimumResponseFine()

double karto::Mapper::getParamLoopMatchMinimumResponseFine ( )

Definition at line 1658 of file Mapper.cpp.

◆ getParamLoopSearchMaximumDistance()

double karto::Mapper::getParamLoopSearchMaximumDistance ( )

Definition at line 1633 of file Mapper.cpp.

◆ getParamLoopSearchSpaceDimension()

double karto::Mapper::getParamLoopSearchSpaceDimension ( )

Definition at line 1682 of file Mapper.cpp.

◆ getParamLoopSearchSpaceResolution()

double karto::Mapper::getParamLoopSearchSpaceResolution ( )

Definition at line 1687 of file Mapper.cpp.

◆ getParamLoopSearchSpaceSmearDeviation()

double karto::Mapper::getParamLoopSearchSpaceSmearDeviation ( )

Definition at line 1692 of file Mapper.cpp.

◆ getParamMinimumAnglePenalty()

double karto::Mapper::getParamMinimumAnglePenalty ( )

Definition at line 1724 of file Mapper.cpp.

◆ getParamMinimumDistancePenalty()

double karto::Mapper::getParamMinimumDistancePenalty ( )

Definition at line 1729 of file Mapper.cpp.

◆ getParamMinimumTimeInterval()

double karto::Mapper::getParamMinimumTimeInterval ( )

Definition at line 1598 of file Mapper.cpp.

◆ getParamMinimumTravelDistance()

double karto::Mapper::getParamMinimumTravelDistance ( )

Definition at line 1603 of file Mapper.cpp.

◆ getParamMinimumTravelHeading()

double karto::Mapper::getParamMinimumTravelHeading ( )

Definition at line 1608 of file Mapper.cpp.

◆ getParamScanBufferMaximumScanDistance()

double karto::Mapper::getParamScanBufferMaximumScanDistance ( )

Definition at line 1618 of file Mapper.cpp.

◆ getParamScanBufferSize()

int karto::Mapper::getParamScanBufferSize ( )

Definition at line 1613 of file Mapper.cpp.

◆ getParamUseResponseExpansion()

bool karto::Mapper::getParamUseResponseExpansion ( )

Definition at line 1734 of file Mapper.cpp.

◆ getParamUseScanBarycenter()

bool karto::Mapper::getParamUseScanBarycenter ( )

Definition at line 1593 of file Mapper.cpp.

◆ getParamUseScanMatching()

bool karto::Mapper::getParamUseScanMatching ( )

Definition at line 1588 of file Mapper.cpp.

◆ GetSequentialScanMatcher()

ScanMatcher * karto::Mapper::GetSequentialScanMatcher ( ) const
virtual

Gets the sequential scan matcher

Returns
sequential scan matcher

Definition at line 2159 of file Mapper.cpp.

◆ HasMovedEnough()

kt_bool karto::Mapper::HasMovedEnough ( LocalizedRangeScan pScan,
LocalizedRangeScan pLastScan 
) const
private

Test if the scan is "sufficiently far" from the last scan added.

Parameters
pScanscan to be checked
pLastScanlast scan added to mapper
Returns
true if the scan is "sufficiently far" from the last scan added or the scan is the first scan to be added

Is the scan sufficiently far from the last scan?

Parameters
pScan
pLastScan
Returns
true if the scans are sufficiently far

Definition at line 2016 of file Mapper.cpp.

◆ Initialize()

void karto::Mapper::Initialize ( kt_double  rangeThreshold)

Allocate memory needed for mapping

Parameters
rangeThreshold

Definition at line 1893 of file Mapper.cpp.

◆ InitializeParameters()

void karto::Mapper::InitializeParameters ( )
private

Definition at line 1377 of file Mapper.cpp.

◆ operator=()

const Mapper& karto::Mapper::operator= ( const Mapper )
private

Restrict the assignment operator

◆ Process() [1/2]

kt_bool karto::Mapper::Process ( LocalizedRangeScan pScan)
virtual

Process a localized range scan for incorporation into the map. The scan must be identified with a range finder device. Once added to a map, the corrected pose information in the localized scan will be updated to the correct pose as determined by the mapper.

Parameters
pScanA localized range scan that has pose information associated directly with the scan data. The pose is that of the range device originating the scan. Note that the mapper will set corrected pose information in the scan object.
Returns
true if the scan was added successfully, false otherwise

Definition at line 1933 of file Mapper.cpp.

◆ Process() [2/2]

kt_bool karto::Mapper::Process ( Object pObject)
virtual

Process an Object

Reimplemented from karto::Module.

Definition at line 1928 of file Mapper.cpp.

◆ RemoveListener()

void karto::Mapper::RemoveListener ( MapperListener pListener)

Remove a listener to mapper

Parameters
pListenerRemoves a listener
pListener

Definition at line 2080 of file Mapper.cpp.

◆ Reset()

void karto::Mapper::Reset ( )
virtual

Resets the mapper. Deallocate memory allocated in Initialize()

Implements karto::Module.

Definition at line 1914 of file Mapper.cpp.

◆ setParamAngleVariancePenalty()

void karto::Mapper::setParamAngleVariancePenalty ( double  d)

Definition at line 1856 of file Mapper.cpp.

◆ setParamCoarseAngleResolution()

void karto::Mapper::setParamCoarseAngleResolution ( double  d)

Definition at line 1871 of file Mapper.cpp.

◆ setParamCoarseSearchAngleOffset()

void karto::Mapper::setParamCoarseSearchAngleOffset ( double  d)

Definition at line 1866 of file Mapper.cpp.

◆ setParamCorrelationSearchSpaceDimension()

void karto::Mapper::setParamCorrelationSearchSpaceDimension ( double  d)

Definition at line 1817 of file Mapper.cpp.

◆ setParamCorrelationSearchSpaceResolution()

void karto::Mapper::setParamCorrelationSearchSpaceResolution ( double  d)

Definition at line 1822 of file Mapper.cpp.

◆ setParamCorrelationSearchSpaceSmearDeviation()

void karto::Mapper::setParamCorrelationSearchSpaceSmearDeviation ( double  d)

Definition at line 1827 of file Mapper.cpp.

◆ setParamDistanceVariancePenalty()

void karto::Mapper::setParamDistanceVariancePenalty ( double  d)

Definition at line 1851 of file Mapper.cpp.

◆ setParamDoLoopClosing()

void karto::Mapper::setParamDoLoopClosing ( bool  b)

Definition at line 1791 of file Mapper.cpp.

◆ setParamFineSearchAngleOffset()

void karto::Mapper::setParamFineSearchAngleOffset ( double  d)

Definition at line 1861 of file Mapper.cpp.

◆ setParamLinkMatchMinimumResponseFine()

void karto::Mapper::setParamLinkMatchMinimumResponseFine ( double  d)

Definition at line 1776 of file Mapper.cpp.

◆ setParamLinkScanMaximumDistance()

void karto::Mapper::setParamLinkScanMaximumDistance ( double  d)

Definition at line 1781 of file Mapper.cpp.

◆ setParamLoopMatchMaximumVarianceCoarse()

void karto::Mapper::setParamLoopMatchMaximumVarianceCoarse ( double  d)

Definition at line 1801 of file Mapper.cpp.

◆ setParamLoopMatchMinimumChainSize()

void karto::Mapper::setParamLoopMatchMinimumChainSize ( int  i)

Definition at line 1796 of file Mapper.cpp.

◆ setParamLoopMatchMinimumResponseCoarse()

void karto::Mapper::setParamLoopMatchMinimumResponseCoarse ( double  d)

Definition at line 1806 of file Mapper.cpp.

◆ setParamLoopMatchMinimumResponseFine()

void karto::Mapper::setParamLoopMatchMinimumResponseFine ( double  d)

Definition at line 1811 of file Mapper.cpp.

◆ setParamLoopSearchMaximumDistance()

void karto::Mapper::setParamLoopSearchMaximumDistance ( double  d)

Definition at line 1786 of file Mapper.cpp.

◆ setParamLoopSearchSpaceDimension()

void karto::Mapper::setParamLoopSearchSpaceDimension ( double  d)

Definition at line 1834 of file Mapper.cpp.

◆ setParamLoopSearchSpaceResolution()

void karto::Mapper::setParamLoopSearchSpaceResolution ( double  d)

Definition at line 1839 of file Mapper.cpp.

◆ setParamLoopSearchSpaceSmearDeviation()

void karto::Mapper::setParamLoopSearchSpaceSmearDeviation ( double  d)

Definition at line 1844 of file Mapper.cpp.

◆ setParamMinimumAnglePenalty()

void karto::Mapper::setParamMinimumAnglePenalty ( double  d)

Definition at line 1876 of file Mapper.cpp.

◆ setParamMinimumDistancePenalty()

void karto::Mapper::setParamMinimumDistancePenalty ( double  d)

Definition at line 1881 of file Mapper.cpp.

◆ setParamMinimumTimeInterval()

void karto::Mapper::setParamMinimumTimeInterval ( double  d)

Definition at line 1751 of file Mapper.cpp.

◆ setParamMinimumTravelDistance()

void karto::Mapper::setParamMinimumTravelDistance ( double  d)

Definition at line 1756 of file Mapper.cpp.

◆ setParamMinimumTravelHeading()

void karto::Mapper::setParamMinimumTravelHeading ( double  d)

Definition at line 1761 of file Mapper.cpp.

◆ setParamScanBufferMaximumScanDistance()

void karto::Mapper::setParamScanBufferMaximumScanDistance ( double  d)

Definition at line 1771 of file Mapper.cpp.

◆ setParamScanBufferSize()

void karto::Mapper::setParamScanBufferSize ( int  i)

Definition at line 1766 of file Mapper.cpp.

◆ setParamUseResponseExpansion()

void karto::Mapper::setParamUseResponseExpansion ( bool  b)

Definition at line 1886 of file Mapper.cpp.

◆ setParamUseScanBarycenter()

void karto::Mapper::setParamUseScanBarycenter ( bool  b)

Definition at line 1746 of file Mapper.cpp.

◆ setParamUseScanMatching()

void karto::Mapper::setParamUseScanMatching ( bool  b)

Definition at line 1741 of file Mapper.cpp.

◆ SetScanSolver()

void karto::Mapper::SetScanSolver ( ScanSolver pSolver)

Set scan optimizer used by mapper when closing the loop

Parameters
pSolver

Definition at line 2149 of file Mapper.cpp.

◆ SetUseScanMatching()

void karto::Mapper::SetUseScanMatching ( kt_bool  val)
inline

Definition at line 1930 of file Mapper.h.

◆ TryCloseLoop()

kt_bool karto::Mapper::TryCloseLoop ( LocalizedRangeScan pScan,
const Name rSensorName 
)
inline

Tries to close a loop using the given scan with the scans from the given sensor

Parameters
pScan
rSensorName

Definition at line 1861 of file Mapper.h.

Friends And Related Function Documentation

◆ MapperGraph

friend class MapperGraph
friend

Definition at line 1752 of file Mapper.h.

◆ ScanMatcher

friend class ScanMatcher
friend

Definition at line 1753 of file Mapper.h.

Member Data Documentation

◆ m_Initialized

kt_bool karto::Mapper::m_Initialized
private

Definition at line 1933 of file Mapper.h.

◆ m_Listeners

std::vector<MapperListener*> karto::Mapper::m_Listeners
private

Definition at line 1942 of file Mapper.h.

◆ m_pAngleVariancePenalty

Parameter<kt_double>* karto::Mapper::m_pAngleVariancePenalty
private

Definition at line 2113 of file Mapper.h.

◆ m_pCoarseAngleResolution

Parameter<kt_double>* karto::Mapper::m_pCoarseAngleResolution
private

Definition at line 2120 of file Mapper.h.

◆ m_pCoarseSearchAngleOffset

Parameter<kt_double>* karto::Mapper::m_pCoarseSearchAngleOffset
private

Definition at line 2117 of file Mapper.h.

◆ m_pCorrelationSearchSpaceDimension

Parameter<kt_double>* karto::Mapper::m_pCorrelationSearchSpaceDimension
private

The size of the search grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

Definition at line 2070 of file Mapper.h.

◆ m_pCorrelationSearchSpaceResolution

Parameter<kt_double>* karto::Mapper::m_pCorrelationSearchSpaceResolution
private

The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

Definition at line 2076 of file Mapper.h.

◆ m_pCorrelationSearchSpaceSmearDeviation

Parameter<kt_double>* karto::Mapper::m_pCorrelationSearchSpaceSmearDeviation
private

The point readings are smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

Definition at line 2082 of file Mapper.h.

◆ m_pDistanceVariancePenalty

Parameter<kt_double>* karto::Mapper::m_pDistanceVariancePenalty
private

Definition at line 2112 of file Mapper.h.

◆ m_pDoLoopClosing

Parameter<kt_bool>* karto::Mapper::m_pDoLoopClosing
private

Enable/disable loop closure. Default is enabled.

Definition at line 2027 of file Mapper.h.

◆ m_pFineSearchAngleOffset

Parameter<kt_double>* karto::Mapper::m_pFineSearchAngleOffset
private

Definition at line 2116 of file Mapper.h.

◆ m_pGraph

MapperGraph* karto::Mapper::m_pGraph
private

Definition at line 1939 of file Mapper.h.

◆ m_pLinkMatchMinimumResponseFine

Parameter<kt_double>* karto::Mapper::m_pLinkMatchMinimumResponseFine
private

Scans are linked only if the correlation response value is greater than this value. Default value is 0.4

Definition at line 2014 of file Mapper.h.

◆ m_pLinkScanMaximumDistance

Parameter<kt_double>* karto::Mapper::m_pLinkScanMaximumDistance
private

Maximum distance between linked scans. Scans that are farther apart will not be linked regardless of the correlation response value. Default value is 6.0 meters.

Definition at line 2021 of file Mapper.h.

◆ m_pLoopMatchMaximumVarianceCoarse

Parameter<kt_double>* karto::Mapper::m_pLoopMatchMaximumVarianceCoarse
private

The co-variance values for a possible loop closure have to be less than this value to consider a viable solution. This applies to the coarse search. Default value is 0.16.

Definition at line 2049 of file Mapper.h.

◆ m_pLoopMatchMinimumChainSize

Parameter<kt_int32u>* karto::Mapper::m_pLoopMatchMinimumChainSize
private

When the loop closure detection finds a candidate it must be part of a large set of linked scans. If the chain of scans is less than this value we do not attempt to close the loop. Default value is 10.

Definition at line 2042 of file Mapper.h.

◆ m_pLoopMatchMinimumResponseCoarse

Parameter<kt_double>* karto::Mapper::m_pLoopMatchMinimumResponseCoarse
private

If response is larger then this, then initiate loop closure search at the coarse resolution. Default value is 0.7.

Definition at line 2055 of file Mapper.h.

◆ m_pLoopMatchMinimumResponseFine

Parameter<kt_double>* karto::Mapper::m_pLoopMatchMinimumResponseFine
private

If response is larger then this, then initiate loop closure search at the fine resolution. Default value is 0.7.

Definition at line 2061 of file Mapper.h.

◆ m_pLoopSearchMaximumDistance

Parameter<kt_double>* karto::Mapper::m_pLoopSearchMaximumDistance
private

Scans less than this distance from the current position will be considered for a match in loop closure. Default value is 4.0 meters.

Definition at line 2034 of file Mapper.h.

◆ m_pLoopSearchSpaceDimension

Parameter<kt_double>* karto::Mapper::m_pLoopSearchSpaceDimension
private

The size of the search grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

Definition at line 2092 of file Mapper.h.

◆ m_pLoopSearchSpaceResolution

Parameter<kt_double>* karto::Mapper::m_pLoopSearchSpaceResolution
private

The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

Definition at line 2098 of file Mapper.h.

◆ m_pLoopSearchSpaceSmearDeviation

Parameter<kt_double>* karto::Mapper::m_pLoopSearchSpaceSmearDeviation
private

The point readings are smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

Definition at line 2104 of file Mapper.h.

◆ m_pMapperSensorManager

MapperSensorManager* karto::Mapper::m_pMapperSensorManager
private

Definition at line 1937 of file Mapper.h.

◆ m_pMinimumAnglePenalty

Parameter<kt_double>* karto::Mapper::m_pMinimumAnglePenalty
private

Definition at line 2124 of file Mapper.h.

◆ m_pMinimumDistancePenalty

Parameter<kt_double>* karto::Mapper::m_pMinimumDistancePenalty
private

Definition at line 2125 of file Mapper.h.

◆ m_pMinimumTimeInterval

Parameter<kt_double>* karto::Mapper::m_pMinimumTimeInterval
private

Sets the minimum time between scans. If a new scan's time stamp is longer than MinimumTimeInterval from the previously processed scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance and heading requirements. For performance reasons, it is generally it is a good idea to only process scans if a reasonable amount of time has passed. This parameter is particularly useful when there is a need to process scans while the robot is stationary. Default value is 3600 (seconds), effectively disabling this parameter.

Definition at line 1971 of file Mapper.h.

◆ m_pMinimumTravelDistance

Parameter<kt_double>* karto::Mapper::m_pMinimumTravelDistance
private

Sets the minimum travel between scans. If a new scan's position is more than minimumTravelDistance from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum change in heading requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.2 (meters).

Definition at line 1981 of file Mapper.h.

◆ m_pMinimumTravelHeading

Parameter<kt_double>* karto::Mapper::m_pMinimumTravelHeading
private

Sets the minimum heading change between scans. If a new scan's heading is more than minimumTravelHeading from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 10 degrees.

Definition at line 1991 of file Mapper.h.

◆ m_pScanBufferMaximumScanDistance

Parameter<kt_double>* karto::Mapper::m_pScanBufferMaximumScanDistance
private

Scan buffer maximum scan distance is the maximum distance between the first and last scans in the scan chain stored for matching. Default value is 20.0.

Definition at line 2008 of file Mapper.h.

◆ m_pScanBufferSize

Parameter<kt_int32u>* karto::Mapper::m_pScanBufferSize
private

Scan buffer size is the length of the scan chain stored for scan matching. "scanBufferSize" should be set to approximately "scanBufferMaximumScanDistance" / "minimumTravelDistance". The idea is to get an area approximately 20 meters long for scan matching. For example, if we add scans every minimumTravelDistance == 0.3 meters, then "scanBufferSize" should be 20 / 0.3 = 67.) Default value is 67.

Definition at line 2001 of file Mapper.h.

◆ m_pScanOptimizer

ScanSolver* karto::Mapper::m_pScanOptimizer
private

Definition at line 1940 of file Mapper.h.

◆ m_pSequentialScanMatcher

ScanMatcher* karto::Mapper::m_pSequentialScanMatcher
private

Definition at line 1935 of file Mapper.h.

◆ m_pUseResponseExpansion

Parameter<kt_bool>* karto::Mapper::m_pUseResponseExpansion
private

Definition at line 2128 of file Mapper.h.

◆ m_pUseScanBarycenter

Parameter<kt_bool>* karto::Mapper::m_pUseScanBarycenter
private

Default value is true.

Definition at line 1958 of file Mapper.h.

◆ m_pUseScanMatching

Parameter<kt_bool>* karto::Mapper::m_pUseScanMatching
private

When set to true, the mapper will use a scan matching algorithm. In most real-world situations this should be set to true so that the mapper algorithm can correct for noise and errors in odometry and scan data. In some simulator environments where the simulated scan and odometry data are very accurate, the scan matching algorithm can produce worse results. In those cases set this to false to improve results. Default value is true.

Definition at line 1953 of file Mapper.h.


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


open_karto
Author(s):
autogenerated on Tue Jul 23 2024 02:26:00