#include <OpenMapper.h>

Public Member Functions | |
| const Rectangle2< kt_int32s > & | GetROI () const |
| virtual kt_int32s | GridIndex (const Vector2i &rGrid, kt_bool boundaryCheck=true) const |
| void | SetROI (const Rectangle2< kt_int32s > &roi) |
| void | SmearPoint (const Vector2i &rGridPoint) |
Static Public Member Functions | |
| static CorrelationGrid * | CreateGrid (kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation) |
Protected Member Functions | |
| virtual void | CalculateKernel () |
| CorrelationGrid (kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation) | |
Static Protected Member Functions | |
| static kt_int32s | GetHalfKernelSize (kt_double smearDeviation, kt_double resolution) |
Private Member Functions | |
| void | SmearInternal (kt_int32s halfKernel, kt_int32s kernelConstant, kt_int8u *pGridAdr) |
Private Attributes | |
| kt_int32s | m_KernelSize |
| kt_int8u * | m_pKernel |
| Rectangle2< kt_int32s > | m_Roi |
| kt_double | m_SmearDeviation |
Correlation grid used for scan matching
Definition at line 816 of file OpenMapper.h.
| karto::CorrelationGrid::CorrelationGrid | ( | kt_int32u | width, |
| kt_int32u | height, | ||
| kt_int32u | borderSize, | ||
| kt_double | resolution, | ||
| kt_double | smearDeviation | ||
| ) | [inline, protected] |
Constructs a correlation grid of given size and parameters
| width | width |
| height | height |
| borderSize | size of border |
| resolution | resolution |
| smearDeviation | amount to smear when adding scans to grid |
Definition at line 921 of file OpenMapper.h.
| virtual void karto::CorrelationGrid::CalculateKernel | ( | ) | [inline, protected, virtual] |
Sets up the kernel for grid smearing
Definition at line 938 of file OpenMapper.h.
| static CorrelationGrid* karto::CorrelationGrid::CreateGrid | ( | kt_int32s | width, |
| kt_int32s | height, | ||
| kt_double | resolution, | ||
| kt_double | smearDeviation | ||
| ) | [inline, static] |
Creates a correlation grid of given size and parameters
| width | width |
| height | height |
| resolution | resolution |
| smearDeviation | amount to smear when adding scans to grid |
Definition at line 838 of file OpenMapper.h.
| static kt_int32s karto::CorrelationGrid::GetHalfKernelSize | ( | kt_double | smearDeviation, |
| kt_double | resolution | ||
| ) | [inline, static, protected] |
Computes the kernel half-size based on the smear distance and the grid resolution. Computes to two standard deviations to get 95% region and to reduce aliasing.
| smearDeviation | amount to smear when adding scans to grid |
| resolution | resolution |
Definition at line 999 of file OpenMapper.h.
| const Rectangle2<kt_int32s>& karto::CorrelationGrid::GetROI | ( | ) | const [inline] |
Get the region of interest (ROI)
Definition at line 868 of file OpenMapper.h.
| virtual kt_int32s karto::CorrelationGrid::GridIndex | ( | const Vector2i & | rGrid, |
| kt_bool | boundaryCheck = true |
||
| ) | const [inline, virtual] |
Gets the index into the data pointer of the given grid coordinate
| rGrid | grid coordinate |
| boundaryCheck | whether to check the boundary of the grid |
Reimplemented from karto::Grid< kt_int8u >.
Definition at line 856 of file OpenMapper.h.
| void karto::CorrelationGrid::SetROI | ( | const Rectangle2< kt_int32s > & | roi | ) | [inline] |
Sets the region of interest (ROI)
| roi | location of the ROI |
Definition at line 877 of file OpenMapper.h.
| void karto::CorrelationGrid::SmearInternal | ( | kt_int32s | halfKernel, |
| kt_int32s | kernelConstant, | ||
| kt_int8u * | pGridAdr | ||
| ) | [inline, private] |
Definition at line 1008 of file OpenMapper.h.
| void karto::CorrelationGrid::SmearPoint | ( | const Vector2i & | rGridPoint | ) | [inline] |
Smears cell if the cell at the given point is marked as "occupied"
| rGridPoint | grid coordinate |
Definition at line 886 of file OpenMapper.h.
Definition at line 1034 of file OpenMapper.h.
kt_int8u* karto::CorrelationGrid::m_pKernel [private] |
Definition at line 1037 of file OpenMapper.h.
Rectangle2<kt_int32s> karto::CorrelationGrid::m_Roi [private] |
Definition at line 1040 of file OpenMapper.h.
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 1031 of file OpenMapper.h.