#include <Mapper.h>
|
void | ComputeAngularCovariance (const Pose2 &rBestPose, kt_double bestResponse, const Pose2 &rSearchCenter, kt_double searchAngleOffset, kt_double searchAngleResolution, Matrix3 &rCovariance) |
|
void | ComputePositionalCovariance (const Pose2 &rBestPose, kt_double bestResponse, const Pose2 &rSearchCenter, const Vector2< kt_double > &rSearchSpaceOffset, const Vector2< kt_double > &rSearchSpaceResolution, kt_double searchAngleResolution, Matrix3 &rCovariance) |
|
kt_double | CorrelateScan (LocalizedRangeScan *pScan, const Pose2 &rSearchCenter, const Vector2< kt_double > &rSearchSpaceOffset, const Vector2< kt_double > &rSearchSpaceResolution, kt_double searchAngleOffset, kt_double searchAngleResolution, kt_bool doPenalize, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doingFineMatch) |
|
CorrelationGrid * | GetCorrelationGrid () const |
|
template<class T = LocalizedRangeScanVector> |
kt_double | MatchScan (LocalizedRangeScan *pScan, const T &rBaseScans, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doPenalize=true, kt_bool doRefineMatch=true) |
|
void | operator() (const kt_double &y) const |
|
| ScanMatcher () |
|
virtual | ~ScanMatcher () |
|
Scan matcher
Definition at line 1314 of file Mapper.h.
◆ ScanMatcher() [1/2]
karto::ScanMatcher::ScanMatcher |
( |
| ) |
|
|
inline |
◆ ~ScanMatcher()
karto::ScanMatcher::~ScanMatcher |
( |
| ) |
|
|
virtual |
◆ ScanMatcher() [2/2]
karto::ScanMatcher::ScanMatcher |
( |
Mapper * |
pMapper | ) |
|
|
inlineprotected |
Default constructor
Definition at line 1464 of file Mapper.h.
◆ AddScan()
Marks cells where scans' points hit as being occupied. Can smear points as they are added.
- Parameters
-
pScan | scan whose points will mark cells in grid as being occupied |
viewPoint | do not add points that belong to scans "opposite" the view point |
doSmear | whether the points will be smeared |
Definition at line 1100 of file Mapper.cpp.
◆ AddScans() [1/2]
Marks cells where scans' points hit as being occupied
- Parameters
-
rScans | scans whose points will mark cells in grid as being occupied |
viewPoint | do not add points that belong to scans "opposite" the view point |
Definition at line 1078 of file Mapper.cpp.
◆ AddScans() [2/2]
Marks cells where scans' points hit as being occupied
- Parameters
-
rScans | scans whose points will mark cells in grid as being occupied |
viewPoint | do not add points that belong to scans "opposite" the view point |
Definition at line 1057 of file Mapper.cpp.
◆ ComputeAngularCovariance()
Computes the angular covariance of the best pose
- Parameters
-
rBestPose | |
bestResponse | |
rSearchCenter | |
searchAngleOffset | |
searchAngleResolution | |
rCovariance | Computes the angular covariance of the best pose |
rBestPose | |
bestResponse | |
rSearchCenter | |
rSearchAngleOffset | |
searchAngleResolution | |
rCovariance | |
Definition at line 999 of file Mapper.cpp.
◆ ComputePositionalCovariance()
Computes the positional covariance of the best pose
- Parameters
-
rBestPose | |
bestResponse | |
rSearchCenter | |
rSearchSpaceOffset | |
rSearchSpaceResolution | |
searchAngleResolution | |
rCovariance | |
Definition at line 893 of file Mapper.cpp.
◆ CorrelateScan()
Finds the best pose for the scan centering the search in the correlation grid at the given pose and search in the space by the vector and angular offsets in increments of the given resolutions
- Parameters
-
pScan | scan to match against correlation grid |
rSearchCenter | the center of the search space |
rSearchSpaceOffset | searches poses in the area offset by this vector around search center |
rSearchSpaceResolution | how fine a granularity to search in the search space |
searchAngleOffset | searches poses in the angles offset by this angle around search center |
searchAngleResolution | how fine a granularity to search in the angular search space |
doPenalize | whether to penalize matches further from the search center |
rMean | output parameter of mean (best pose) of match |
rCovariance | output parameter of covariance of match |
doingFineMatch | whether to do a finer search after coarse search |
- Returns
- strength of response
Finds the best pose for the scan centering the search in the correlation grid at the given pose and search in the space by the vector and angular offsets in increments of the given resolutions
- Parameters
-
rScan | scan to match against correlation grid |
rSearchCenter | the center of the search space |
rSearchSpaceOffset | searches poses in the area offset by this vector around search center |
rSearchSpaceResolution | how fine a granularity to search in the search space |
searchAngleOffset | searches poses in the angles offset by this angle around search center |
searchAngleResolution | how fine a granularity to search in the angular search space |
doPenalize | whether to penalize matches further from the search center |
rMean | output parameter of mean (best pose) of match |
rCovariance | output parameter of covariance of match |
doingFineMatch | whether to do a finer search after coarse search |
- Returns
- strength of response
Definition at line 719 of file Mapper.cpp.
◆ Create()
Create a scan matcher with the given parameters
Definition at line 485 of file Mapper.cpp.
◆ FindValidPoints()
Compute which points in a scan are on the same side as the given viewpoint
- Parameters
-
- Returns
- points on the same side
Definition at line 1140 of file Mapper.cpp.
◆ GetCorrelationGrid()
Gets the correlation grid data (for debugging)
- Returns
- correlation grid
Definition at line 1422 of file Mapper.h.
◆ GetResponse()
Get response at given position for given rotation (only look up valid points)
- Parameters
-
angleIndex | |
gridPositionIndex | |
- Returns
- response
Definition at line 1203 of file Mapper.cpp.
◆ MatchScan()
Match given scan against set of scans
- Parameters
-
pScan | scan being scan-matched |
rBaseScans | set of scans whose points will mark cells in grid as being occupied |
rMean | output parameter of mean (best pose) of match |
rCovariance | output parameter of covariance of match |
doPenalize | whether to penalize matches further from the search center |
doRefineMatch | whether to do finer-grained matching if coarse match is good (default is true) |
- Returns
- strength of response
Definition at line 544 of file Mapper.cpp.
◆ operator()()
void karto::ScanMatcher::operator() |
( |
const kt_double & |
y | ) |
const |
Parallelize scan matching
Definition at line 649 of file Mapper.cpp.
◆ serialize()
template<class Archive >
void karto::ScanMatcher::serialize |
( |
Archive & |
ar, |
|
|
const unsigned int |
version |
|
) |
| |
|
inlineprivate |
◆ boost::serialization::access
friend class boost::serialization::access |
|
friend |
◆ m_doPenalize
kt_bool karto::ScanMatcher::m_doPenalize |
|
private |
◆ m_nAngles
◆ m_pCorrelationGrid
◆ m_pGridLookup
◆ m_pMapper
Mapper* karto::ScanMatcher::m_pMapper |
|
private |
◆ m_pPoseResponse
◆ m_pSearchSpaceProbs
◆ m_rSearchCenter
Pose2 karto::ScanMatcher::m_rSearchCenter |
|
private |
◆ m_searchAngleOffset
kt_double karto::ScanMatcher::m_searchAngleOffset |
|
private |
◆ m_searchAngleResolution
kt_double karto::ScanMatcher::m_searchAngleResolution |
|
private |
◆ m_xPoses
std::vector<kt_double> karto::ScanMatcher::m_xPoses |
|
private |
◆ m_yPoses
std::vector<kt_double> karto::ScanMatcher::m_yPoses |
|
private |
The documentation for this class was generated from the following files: