Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes | List of all members
karto::CorrelationGrid Class Reference

#include <OpenMapper.h>

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

Protected Member Functions

virtual void CalculateKernel ()
 
 CorrelationGrid (kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation)
 
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)
 
- Protected Member Functions inherited from karto::Grid< kt_int8u >
void Clear ()
 
GridClone ()
 
BoundingBox2 GetBoundingBox () const
 
CoordinateConverterGetCoordinateConverter () const
 
kt_int8uGetDataPointer (const Vector2i &rGrid)
 
kt_int8uGetDataPointer (const Vector2i &rGrid) const
 
kt_int8uGetDataPointer ()
 
kt_int8uGetDataPointer () const
 
kt_int32s GetDataSize () const
 
kt_int32s GetHeight () const
 
kt_double GetResolution () const
 
const Size2< kt_int32sGetSize () const
 
kt_int8u GetValue (const Vector2i &rGrid) const
 
kt_int32s GetWidth () const
 
kt_int32s GetWidthStep () const
 
 Grid (kt_int32s width, kt_int32s height)
 
Vector2d GridToWorld (const Vector2i &rGrid, kt_bool flipY=false) const
 
Vector2i IndexToGrid (kt_int32s index) const
 
kt_bool IsValidGridIndex (const Vector2i &rGrid) const
 
virtual void Resize (kt_int32s width, kt_int32s height)
 
void SetValue (const Vector2i &rGrid, kt_int8urValue) const
 
void TraceLine (kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor *f=NULL)
 
Vector2i WorldToGrid (const Vector2d &rWorld, kt_bool flipY=false) const
 
- Protected Member Functions inherited from karto::Object
const IdentifierGetIdentifier () const
 
AbstractParameterGetParameter (const String &rParameterName) const
 
template<typename T >
Parameter< T > * GetParameter (const String &rParameterName) const
 
ParameterList GetParameters ()
 
ParameterSetGetParameterSet ()
 
template<typename T >
void SetParameters (const karto::String &rParameterName, const T &rValue)
 
- Protected Member Functions inherited from karto::Referenced
kt_int32s GetReferenceCount ()
 
kt_int32s Reference () const
 
kt_int32s Unreference () const
 
kt_int32s UnreferenceNoDelete () const
 

Static Protected Member Functions

static CorrelationGridCreateGrid (kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
 
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
 

Additional Inherited Members

- Public Member Functions inherited from karto::Object
 Object ()
 
 Object (const Identifier &rIdentifier)
 
- Public Member Functions inherited from karto::Referenced
 Referenced ()
 
- Static Public Member Functions inherited from karto::Grid< kt_int8u >
static GridCreateGrid (kt_int32s width, kt_int32s height, kt_double resolution)
 

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 
)
inlineprotected

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 ( )
inlineprotectedvirtual

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 
)
inlinestaticprotected

public: /** 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 
)
inlinestaticprotected

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.

const Rectangle2<kt_int32s>& karto::CorrelationGrid::GetROI ( ) const
inlineprotected

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
inlineprotectedvirtual

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)
inlineprotected

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 
)
inlineprivate

Definition at line 1008 of file OpenMapper.h.

void karto::CorrelationGrid::SmearPoint ( const Vector2i rGridPoint)
inlineprotected

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

kt_int32s karto::CorrelationGrid::m_KernelSize
private

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.

kt_double karto::CorrelationGrid::m_SmearDeviation
private

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 Tue Nov 7 2017 06:02:36