#include <Mapper.h>
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.
Default constructor
Definition at line 1624 of file Mapper.cpp.
karto::Mapper::Mapper | ( | const std::string & | rName | ) |
Constructor a mapper with a name
rName | mapper name |
Default constructor
Definition at line 1638 of file Mapper.cpp.
karto::Mapper::~Mapper | ( | ) | [virtual] |
Destructor
Definition at line 1652 of file Mapper.cpp.
karto::Mapper::Mapper | ( | const Mapper & | ) | [private] |
Restrict the copy constructor
void karto::Mapper::AddListener | ( | MapperListener * | pListener | ) |
Add a listener to mapper
pListener | Adds a listener |
pListener |
Definition at line 2353 of file Mapper.cpp.
void karto::Mapper::FireBeginLoopClosure | ( | const std::string & | rInfo | ) | const |
Fire a message before loop closure to listeners
rInfo |
Definition at line 2405 of file Mapper.cpp.
void karto::Mapper::FireDebug | ( | const std::string & | rInfo | ) | const |
void karto::Mapper::FireEndLoopClosure | ( | const std::string & | rInfo | ) | const |
Fire a message after loop closure to listeners
rInfo |
Definition at line 2418 of file Mapper.cpp.
void karto::Mapper::FireInfo | ( | const std::string & | rInfo | ) | const |
void karto::Mapper::FireLoopClosureCheck | ( | const std::string & | rInfo | ) | const |
Fire a message upon checking for loop closure to listeners
rInfo |
Definition at line 2392 of file Mapper.cpp.
const LocalizedRangeScanVector karto::Mapper::GetAllProcessedScans | ( | ) | const [virtual] |
Returns all processed scans added to the mapper. NOTE: The returned scans have their corrected pose updated.
Gets all the processed scans
Definition at line 2337 of file Mapper.cpp.
MapperGraph * karto::Mapper::GetGraph | ( | ) | const [virtual] |
ScanMatcher * karto::Mapper::GetLoopScanMatcher | ( | ) | const [virtual] |
MapperSensorManager* karto::Mapper::GetMapperSensorManager | ( | ) | const [inline] |
double karto::Mapper::getParamAngleVariancePenalty | ( | ) |
Definition at line 1986 of file Mapper.cpp.
double karto::Mapper::getParamCoarseAngleResolution | ( | ) |
Definition at line 2001 of file Mapper.cpp.
Definition at line 1996 of file Mapper.cpp.
Definition at line 1947 of file Mapper.cpp.
Definition at line 1952 of file Mapper.cpp.
Definition at line 1957 of file Mapper.cpp.
Definition at line 1981 of file Mapper.cpp.
bool karto::Mapper::getParamDoLoopClosing | ( | ) |
Definition at line 1920 of file Mapper.cpp.
double karto::Mapper::getParamFineSearchAngleOffset | ( | ) |
Definition at line 1991 of file Mapper.cpp.
Definition at line 1905 of file Mapper.cpp.
Definition at line 1910 of file Mapper.cpp.
Definition at line 1930 of file Mapper.cpp.
Definition at line 1925 of file Mapper.cpp.
Definition at line 1935 of file Mapper.cpp.
Definition at line 1940 of file Mapper.cpp.
Definition at line 1915 of file Mapper.cpp.
Definition at line 1964 of file Mapper.cpp.
Definition at line 1969 of file Mapper.cpp.
Definition at line 1974 of file Mapper.cpp.
double karto::Mapper::getParamMinimumAnglePenalty | ( | ) |
Definition at line 2006 of file Mapper.cpp.
Definition at line 2011 of file Mapper.cpp.
double karto::Mapper::getParamMinimumTimeInterval | ( | ) |
Definition at line 1880 of file Mapper.cpp.
double karto::Mapper::getParamMinimumTravelDistance | ( | ) |
Definition at line 1885 of file Mapper.cpp.
double karto::Mapper::getParamMinimumTravelHeading | ( | ) |
Definition at line 1890 of file Mapper.cpp.
Definition at line 1900 of file Mapper.cpp.
Definition at line 1895 of file Mapper.cpp.
Definition at line 2016 of file Mapper.cpp.
Definition at line 1875 of file Mapper.cpp.
Definition at line 1870 of file Mapper.cpp.
ScanMatcher * karto::Mapper::GetSequentialScanMatcher | ( | ) | const [virtual] |
Gets the sequential scan matcher
Definition at line 2441 of file Mapper.cpp.
kt_bool karto::Mapper::HasMovedEnough | ( | LocalizedRangeScan * | pScan, |
LocalizedRangeScan * | pLastScan | ||
) | const [private] |
Test if the scan is "sufficiently far" from the last scan added.
pScan | scan to be checked |
pLastScan | last scan added to mapper |
Is the scan sufficiently far from the last scan?
pScan | |
pLastScan |
Definition at line 2298 of file Mapper.cpp.
void karto::Mapper::Initialize | ( | kt_double | rangeThreshold | ) |
Allocate memory needed for mapping
rangeThreshold |
Definition at line 2175 of file Mapper.cpp.
void karto::Mapper::InitializeParameters | ( | ) | [private] |
Definition at line 1659 of file Mapper.cpp.
Restrict the assignment operator
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.
pScan | A 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. |
Definition at line 2215 of file Mapper.cpp.
kt_bool karto::Mapper::Process | ( | Object * | pObject | ) | [virtual] |
void karto::Mapper::RemoveListener | ( | MapperListener * | pListener | ) |
Remove a listener to mapper
pListener | Removes a listener |
pListener |
Definition at line 2362 of file Mapper.cpp.
void karto::Mapper::Reset | ( | ) | [virtual] |
Resets the mapper. Deallocate memory allocated in Initialize()
Implements karto::Module.
Definition at line 2196 of file Mapper.cpp.
void karto::Mapper::setParamAngleVariancePenalty | ( | double | d | ) |
Definition at line 2138 of file Mapper.cpp.
void karto::Mapper::setParamCoarseAngleResolution | ( | double | d | ) |
Definition at line 2153 of file Mapper.cpp.
void karto::Mapper::setParamCoarseSearchAngleOffset | ( | double | d | ) |
Definition at line 2148 of file Mapper.cpp.
void karto::Mapper::setParamCorrelationSearchSpaceDimension | ( | double | d | ) |
Definition at line 2099 of file Mapper.cpp.
void karto::Mapper::setParamCorrelationSearchSpaceResolution | ( | double | d | ) |
Definition at line 2104 of file Mapper.cpp.
void karto::Mapper::setParamCorrelationSearchSpaceSmearDeviation | ( | double | d | ) |
Definition at line 2109 of file Mapper.cpp.
void karto::Mapper::setParamDistanceVariancePenalty | ( | double | d | ) |
Definition at line 2133 of file Mapper.cpp.
void karto::Mapper::setParamDoLoopClosing | ( | bool | b | ) |
Definition at line 2073 of file Mapper.cpp.
void karto::Mapper::setParamFineSearchAngleOffset | ( | double | d | ) |
Definition at line 2143 of file Mapper.cpp.
void karto::Mapper::setParamLinkMatchMinimumResponseFine | ( | double | d | ) |
Definition at line 2058 of file Mapper.cpp.
void karto::Mapper::setParamLinkScanMaximumDistance | ( | double | d | ) |
Definition at line 2063 of file Mapper.cpp.
void karto::Mapper::setParamLoopMatchMaximumVarianceCoarse | ( | double | d | ) |
Definition at line 2083 of file Mapper.cpp.
void karto::Mapper::setParamLoopMatchMinimumChainSize | ( | int | i | ) |
Definition at line 2078 of file Mapper.cpp.
void karto::Mapper::setParamLoopMatchMinimumResponseCoarse | ( | double | d | ) |
Definition at line 2088 of file Mapper.cpp.
void karto::Mapper::setParamLoopMatchMinimumResponseFine | ( | double | d | ) |
Definition at line 2093 of file Mapper.cpp.
void karto::Mapper::setParamLoopSearchMaximumDistance | ( | double | d | ) |
Definition at line 2068 of file Mapper.cpp.
void karto::Mapper::setParamLoopSearchSpaceDimension | ( | double | d | ) |
Definition at line 2116 of file Mapper.cpp.
void karto::Mapper::setParamLoopSearchSpaceResolution | ( | double | d | ) |
Definition at line 2121 of file Mapper.cpp.
void karto::Mapper::setParamLoopSearchSpaceSmearDeviation | ( | double | d | ) |
Definition at line 2126 of file Mapper.cpp.
void karto::Mapper::setParamMinimumAnglePenalty | ( | double | d | ) |
Definition at line 2158 of file Mapper.cpp.
void karto::Mapper::setParamMinimumDistancePenalty | ( | double | d | ) |
Definition at line 2163 of file Mapper.cpp.
void karto::Mapper::setParamMinimumTimeInterval | ( | double | d | ) |
Definition at line 2033 of file Mapper.cpp.
void karto::Mapper::setParamMinimumTravelDistance | ( | double | d | ) |
Definition at line 2038 of file Mapper.cpp.
void karto::Mapper::setParamMinimumTravelHeading | ( | double | d | ) |
Definition at line 2043 of file Mapper.cpp.
void karto::Mapper::setParamScanBufferMaximumScanDistance | ( | double | d | ) |
Definition at line 2053 of file Mapper.cpp.
void karto::Mapper::setParamScanBufferSize | ( | int | i | ) |
Definition at line 2048 of file Mapper.cpp.
void karto::Mapper::setParamUseResponseExpansion | ( | bool | b | ) |
Definition at line 2168 of file Mapper.cpp.
void karto::Mapper::setParamUseScanBarycenter | ( | bool | b | ) |
Definition at line 2028 of file Mapper.cpp.
void karto::Mapper::setParamUseScanMatching | ( | bool | b | ) |
Definition at line 2023 of file Mapper.cpp.
void karto::Mapper::SetScanSolver | ( | ScanSolver * | pSolver | ) |
Set scan optimizer used by mapper when closing the loop
pSolver |
Definition at line 2431 of file Mapper.cpp.
void karto::Mapper::SetUseScanMatching | ( | kt_bool | val | ) | [inline] |
kt_bool karto::Mapper::TryCloseLoop | ( | LocalizedRangeScan * | pScan, |
const Name & | rSensorName | ||
) | [inline] |
friend class MapperGraph [friend] |
friend class ScanMatcher [friend] |
kt_bool karto::Mapper::m_Initialized [private] |
std::vector<MapperListener*> karto::Mapper::m_Listeners [private] |
Parameter<kt_double>* karto::Mapper::m_pAngleVariancePenalty [private] |
Parameter<kt_bool>* karto::Mapper::m_pDoLoopClosing [private] |
MapperGraph* karto::Mapper::m_pGraph [private] |
Parameter<kt_double>* karto::Mapper::m_pMinimumAnglePenalty [private] |
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.
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).
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.
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.
ScanSolver* karto::Mapper::m_pScanOptimizer [private] |
Parameter<kt_bool>* karto::Mapper::m_pUseResponseExpansion [private] |
Parameter<kt_bool>* karto::Mapper::m_pUseScanBarycenter [private] |
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.