#include <Mapper.h>

Definition at line 491 of file Mapper.h.
Graph for graph SLAM
| pMapper | ||
| rParameters | ||
| pSensorManager |
Definition at line 1094 of file Mapper.cpp.
| karto::MapperGraph::~MapperGraph | ( | ) | [virtual] |
Destructor
Definition at line 1103 of file Mapper.cpp.
| Edge< LocalizedRangeScan > * karto::MapperGraph::AddEdge | ( | LocalizedRangeScan * | pSourceScan, | |
| LocalizedRangeScan * | pTargetScan, | |||
| kt_bool & | rIsNewEdge | |||
| ) |
Creates an edge between the source scan vertex and the target scan vertex if it does not already exist; otherwise return the existing edge
| pSourceScan | ||
| pTargetScan | ||
| rIsNewEdge | set to true if the edge is new |
Definition at line 1271 of file Mapper.cpp.
| void karto::MapperGraph::AddEdges | ( | LocalizedRangeScan * | pScan, | |
| const Matrix3 & | rCovariance | |||
| ) |
Link scan to last scan and nearby chains of scans
| pScan | ||
| rCovariance | uncertainty of match |
Definition at line 1127 of file Mapper.cpp.
| void karto::MapperGraph::AddVertex | ( | LocalizedRangeScan * | pScan | ) |
Adds a vertex representing the given scan to the graph
| pScan |
Definition at line 1112 of file Mapper.cpp.
| Pose2 karto::MapperGraph::ComputeWeightedMean | ( | const Pose2Vector & | rMeans, | |
| const std::vector< Matrix3 > & | rCovariances | |||
| ) | const [private] |
Compute mean of poses weighted by covariances
| rMeans | ||
| rCovariances |
Definition at line 1458 of file Mapper.cpp.
| void karto::MapperGraph::CorrectPoses | ( | ) | [private] |
Optimizes scan poses
Definition at line 1549 of file Mapper.cpp.
| std::vector< LocalizedRangeScanVector > karto::MapperGraph::FindNearChains | ( | LocalizedRangeScan * | pScan | ) | [private] |
Find chains of scans that are close to given scan
| pScan |
Definition at line 1353 of file Mapper.cpp.
| LocalizedRangeScanVector karto::MapperGraph::FindNearLinkedScans | ( | LocalizedRangeScan * | pScan, | |
| kt_double | maxDistance | |||
| ) |
Find "nearby" (no further than given distance away) scans through graph links
| pScan | ||
| maxDistance |
Definition at line 1449 of file Mapper.cpp.
| LocalizedRangeScanVector karto::MapperGraph::FindPossibleLoopClosure | ( | LocalizedRangeScan * | pScan, | |
| const Name & | rSensorName, | |||
| kt_int32u & | rStartNum | |||
| ) | [private] |
Tries to find a chain of scan from the given device starting at the given scan index that could possibly close a loop with the given scan
| pScan | ||
| rSensorName | ||
| rStartNum |
Definition at line 1502 of file Mapper.cpp.
| LocalizedRangeScan * karto::MapperGraph::GetClosestScanToPose | ( | const LocalizedRangeScanVector & | rScans, | |
| const Pose2 & | rPose | |||
| ) | const [private] |
Finds the closest scan in the vector to the given pose
| rScans | ||
| rPose |
Definition at line 1251 of file Mapper.cpp.
| ScanMatcher* karto::MapperGraph::GetLoopScanMatcher | ( | ) | const [inline] |
| Vertex<LocalizedRangeScan>* karto::MapperGraph::GetVertex | ( | LocalizedRangeScan * | pScan | ) | [inline, private] |
| void karto::MapperGraph::LinkChainToScan | ( | const LocalizedRangeScanVector & | rChain, | |
| LocalizedRangeScan * | pScan, | |||
| const Pose2 & | rMean, | |||
| const Matrix3 & | rCovariance | |||
| ) | [private] |
Link the chain of scans to the given scan by finding the closest scan in the chain to the given scan
| rChain | ||
| pScan | ||
| rMean | ||
| rCovariance |
Definition at line 1337 of file Mapper.cpp.
| void karto::MapperGraph::LinkNearChains | ( | LocalizedRangeScan * | pScan, | |
| Pose2Vector & | rMeans, | |||
| std::vector< Matrix3 > & | rCovariances | |||
| ) | [private] |
Find nearby chains of scans and link them to scan if response is high enough
| pScan | ||
| rMeans | ||
| rCovariances |
Definition at line 1314 of file Mapper.cpp.
| void karto::MapperGraph::LinkScans | ( | LocalizedRangeScan * | pFromScan, | |
| LocalizedRangeScan * | pToScan, | |||
| const Pose2 & | rMean, | |||
| const Matrix3 & | rCovariance | |||
| ) | [private] |
Adds an edge between the two scans and labels the edge with the given mean and covariance
| pFromScan | ||
| pToScan | ||
| rMean | ||
| rCovariance |
Definition at line 1298 of file Mapper.cpp.
| kt_bool karto::MapperGraph::TryCloseLoop | ( | LocalizedRangeScan * | pScan, | |
| const Name & | rSensorName | |||
| ) |
Tries to close a loop using the given scan with the scans from the given device
| pScan | ||
| rSensorName |
Definition at line 1191 of file Mapper.cpp.
Mapper* karto::MapperGraph::m_pMapper [private] |