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

#include <Mapper.h>

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

Public Member Functions

 CorrelationGrid ()
 
const Rectangle2< kt_int32s > & GetROI () const
 
virtual kt_int32s GridIndex (const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
 
void SetROI (const Rectangle2< kt_int32s > &roi)
 
void SmearPoint (const Vector2< kt_int32s > &rGridPoint)
 
virtual ~CorrelationGrid ()
 
- Public Member Functions inherited from karto::Grid< kt_int8u >
void Clear ()
 
GridClone ()
 
BoundingBox2 GetBoundingBox () const
 
CoordinateConverterGetCoordinateConverter () const
 
kt_int8uGetDataPointer (const Vector2< kt_int32s > &rGrid)
 
kt_int8uGetDataPointer (const Vector2< kt_int32s > &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 Vector2< kt_int32s > &rGrid) const
 
kt_int32s GetWidth () const
 
kt_int32s GetWidthStep () const
 
 Grid ()
 
Vector2< kt_doubleGridToWorld (const Vector2< kt_int32s > &rGrid, kt_bool flipY=false) const
 
Vector2< kt_int32sIndexToGrid (kt_int32s index) const
 
kt_bool IsValidGridIndex (const Vector2< kt_int32s > &rGrid) const
 
virtual void Resize (kt_int32s width, kt_int32s height)
 
void TraceLine (kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor *f=NULL)
 
Vector2< kt_int32sWorldToGrid (const Vector2< kt_double > &rWorld, kt_bool flipY=false) const
 
virtual ~Grid ()
 

Static Public Member Functions

static CorrelationGridCreateGrid (kt_int32s width, kt_int32s height, kt_double resolution, kt_double smearDeviation)
 
- Static Public Member Functions inherited from karto::Grid< kt_int8u >
static GridCreateGrid (kt_int32s width, kt_int32s height, kt_double resolution)
 

Protected Member Functions

virtual void CalculateKernel ()
 
 CorrelationGrid (kt_int32u width, kt_int32u height, kt_int32u borderSize, kt_double resolution, kt_double smearDeviation)
 
- Protected Member Functions inherited from karto::Grid< kt_int8u >
 Grid (kt_int32s width, kt_int32s height)
 

Static Protected Member Functions

static kt_int32s GetHalfKernelSize (kt_double smearDeviation, kt_double resolution)
 

Private Member Functions

template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 

Private Attributes

kt_int32s m_KernelSize
 
kt_int8um_pKernel
 
Rectangle2< kt_int32sm_Roi
 
kt_double m_SmearDeviation
 

Friends

class boost::serialization::access
 

Detailed Description

Implementation of a correlation grid used for scan matching

Definition at line 1060 of file Mapper.h.

Constructor & Destructor Documentation

◆ ~CorrelationGrid()

virtual karto::CorrelationGrid::~CorrelationGrid ( )
inlinevirtual

Destructor

Definition at line 1066 of file Mapper.h.

◆ CorrelationGrid() [1/2]

karto::CorrelationGrid::CorrelationGrid ( )
inline

Create a correlation grid of given size and parameters

Parameters
width
height
resolution
smearDeviation
Returns
correlation grid

Definition at line 1084 of file Mapper.h.

◆ CorrelationGrid() [2/2]

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
width
height
borderSize
resolution
smearDeviation

Definition at line 1183 of file Mapper.h.

Member Function Documentation

◆ CalculateKernel()

virtual void karto::CorrelationGrid::CalculateKernel ( )
inlineprotectedvirtual

Sets up the kernel for grid smearing.

Definition at line 1201 of file Mapper.h.

◆ CreateGrid()

static CorrelationGrid* karto::CorrelationGrid::CreateGrid ( kt_int32s  width,
kt_int32s  height,
kt_double  resolution,
kt_double  smearDeviation 
)
inlinestatic

Definition at line 1087 of file Mapper.h.

◆ GetHalfKernelSize()

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
smearDeviation
resolution
Returns
kernel half-size based on the parameters

Definition at line 1265 of file Mapper.h.

◆ GetROI()

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

Get the Region Of Interest (ROI)

Returns
region of interest

Definition at line 1120 of file Mapper.h.

◆ GridIndex()

virtual kt_int32s karto::CorrelationGrid::GridIndex ( const Vector2< kt_int32s > &  rGrid,
kt_bool  boundaryCheck = true 
) const
inlinevirtual

Gets the index into the data pointer of the given grid coordinate

Parameters
rGrid
boundaryCheck
Returns
grid index

Reimplemented from karto::Grid< kt_int8u >.

Definition at line 1108 of file Mapper.h.

◆ serialize()

template<class Archive >
void karto::CorrelationGrid::serialize ( Archive &  ar,
const unsigned int  version 
)
inlineprivate

Definition at line 1292 of file Mapper.h.

◆ SetROI()

void karto::CorrelationGrid::SetROI ( const Rectangle2< kt_int32s > &  roi)
inline

Sets the Region Of Interest (ROI)

Parameters
roi

Definition at line 1129 of file Mapper.h.

◆ SmearPoint()

void karto::CorrelationGrid::SmearPoint ( const Vector2< kt_int32s > &  rGridPoint)
inline

Smear cell if the cell at the given point is marked as "occupied"

Parameters
rGridPoint

Definition at line 1138 of file Mapper.h.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Serialization: class CorrelationGrid

Definition at line 1290 of file Mapper.h.

Member Data Documentation

◆ m_KernelSize

kt_int32s karto::CorrelationGrid::m_KernelSize
private

Definition at line 1280 of file Mapper.h.

◆ m_pKernel

kt_int8u* karto::CorrelationGrid::m_pKernel
private

Definition at line 1283 of file Mapper.h.

◆ m_Roi

Rectangle2<kt_int32s> karto::CorrelationGrid::m_Roi
private

Definition at line 1286 of file Mapper.h.

◆ m_SmearDeviation

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 1277 of file Mapper.h.


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


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:49