Public Member Functions | Public Attributes | List of all members
karto::LocalizationScanVertex Struct Reference

#include <Mapper.h>

Public Member Functions

 LocalizationScanVertex ()
 
 LocalizationScanVertex (const LocalizationScanVertex &obj)
 

Public Attributes

LocalizedRangeScanscan
 
Vertex< LocalizedRangeScan > * vertex
 

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 1918 of file Mapper.h.

Constructor & Destructor Documentation

◆ LocalizationScanVertex() [1/2]

karto::LocalizationScanVertex::LocalizationScanVertex ( )
inline

Definition at line 1920 of file Mapper.h.

◆ LocalizationScanVertex() [2/2]

karto::LocalizationScanVertex::LocalizationScanVertex ( const LocalizationScanVertex obj)
inline

Definition at line 1921 of file Mapper.h.

Member Data Documentation

◆ scan

LocalizedRangeScan* karto::LocalizationScanVertex::scan

Definition at line 1921 of file Mapper.h.

◆ vertex

Vertex<LocalizedRangeScan>* karto::LocalizationScanVertex::vertex

Definition at line 1923 of file Mapper.h.


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


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56