Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes
karto::CorrelationGrid Class Reference

#include <OpenMapper.h>

Inheritance diagram for karto::CorrelationGrid:
Inheritance graph
[legend]

List of all members.

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 CorrelationGridCreateGrid (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_int8um_pKernel
Rectangle2< kt_int32sm_Roi
kt_double m_SmearDeviation

Detailed Description

Correlation grid used for scan matching

Definition at line 816 of file OpenMapper.h.


Constructor & Destructor Documentation

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

Parameters:
widthwidth
heightheight
borderSizesize of border
resolutionresolution
smearDeviationamount to smear when adding scans to grid

Definition at line 921 of file OpenMapper.h.


Member Function Documentation

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

Parameters:
widthwidth
heightheight
resolutionresolution
smearDeviationamount to smear when adding scans to grid
Returns:
correlation 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.

Parameters:
smearDeviationamount to smear when adding scans to grid
resolutionresolution
Returns:
kernel half-size based on the parameters

Definition at line 999 of file OpenMapper.h.

Get the region of interest (ROI)

Returns:
region of interest

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

Parameters:
rGridgrid coordinate
boundaryCheckwhether to check the boundary of the grid
Returns:
grid index

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)

Parameters:
roilocation 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"

Parameters:
rGridPointgrid coordinate

Definition at line 886 of file OpenMapper.h.


Member Data Documentation

Definition at line 1034 of file OpenMapper.h.

Definition at line 1037 of file OpenMapper.h.

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.


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


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Mon Oct 6 2014 02:44:18