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

#include <OccupancyGrid.h>

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

Public Member Functions

OccupancyGridClone () const
 
kt_bool IsFree (const Vector2i &rGridIndex) const
 
 OccupancyGrid (kt_int32s width, kt_int32s height, const Vector2d &rOffset, kt_double resolution)
 
kt_double RayCast (const Pose2 &rPose2, kt_double maxRange) const
 
- Public Member Functions inherited from karto::Object
 Object ()
 
 Object (const Identifier &rIdentifier)
 
- Public Member Functions inherited from karto::Referenced
 Referenced ()
 

Protected Member Functions

kt_bool AddScan (LocalizedLaserScan *pScan, kt_bool doUpdate=false)
 
virtual void CreateFromScans (const LocalizedLaserScanList &rScans)
 
Grid< kt_int32u > * GetCellHitsCounts ()
 
Grid< kt_int32u > * GetCellPassCounts ()
 
kt_bool RayTrace (const Vector2d &rWorldFrom, const Vector2d &rWorldTo, kt_bool isEndPointValid, kt_bool doUpdate=false)
 
virtual void Resize (kt_int32s width, kt_int32s height)
 
void UpdateCell (kt_int8u *pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
 
void UpdateGrid ()
 
- 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)
 
virtual kt_int32s GridIndex (const Vector2i &rGrid, kt_bool boundaryCheck=true) const
 
Vector2d GridToWorld (const Vector2i &rGrid, kt_bool flipY=false) const
 
Vector2i IndexToGrid (kt_int32s index) const
 
kt_bool IsValidGridIndex (const Vector2i &rGrid) const
 
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 void ComputeDimensions (const LocalizedLaserScanList &rScans, kt_double resolution, kt_int32s &rWidth, kt_int32s &rHeight, Vector2d &rOffset)
 
static OccupancyGridCreateFromMapper (OpenMapper *pMapper, kt_double resolution)
 
static OccupancyGridCreateFromScans (const LocalizedLaserScanList &rScans, kt_double resolution)
 
static KARTO_DEPRECATED OccupancyGridCreateFromScans (const std::vector< SmartPointer< LocalizedRangeScan > > &rScans, kt_double resolution)
 

Protected Attributes

SmartPointer< Grid< kt_int32u > > m_pCellHitsCnt
 
SmartPointer< Grid< kt_int32u > > m_pCellPassCnt
 

Private Member Functions

 KARTO_RTTI ()
 
 OccupancyGrid (const OccupancyGrid &)
 
const OccupancyGridoperator= (const OccupancyGrid &)
 

Private Attributes

CellUpdaterm_pCellUpdater
 
SmartPointer< Parameter< kt_int32u > > m_pMinPassThrough
 
SmartPointer< Parameter< kt_double > > m_pOccupancyThreshold
 

Friends

class CellUpdater
 
class IncrementalOccupancyGrid
 

Additional Inherited Members

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

Detailed Description

Occupancy grid definition. See GridStates for possible grid values.

Definition at line 56 of file OccupancyGrid.h.

Constructor & Destructor Documentation

karto::OccupancyGrid::OccupancyGrid ( kt_int32s  width,
kt_int32s  height,
const Vector2d rOffset,
kt_double  resolution 
)

Occupancy grid of given size

Parameters
widthwidth
heightheight
rOffsetoffset
resolutionresolution

Definition at line 28 of file OccupancyGrid.cpp.

karto::OccupancyGrid::OccupancyGrid ( const OccupancyGrid )
private

Member Function Documentation

kt_bool karto::OccupancyGrid::AddScan ( LocalizedLaserScan pScan,
kt_bool  doUpdate = false 
)
protected

Adds the scan's information to this grid's counters (optionally update the grid's cells' occupancy status)

Parameters
pScanlaser scan
doUpdatewhether to update the grid's cell's occupancy status
Returns
returns false if an endpoint fell off the grid, otherwise true

Definition at line 142 of file OccupancyGrid.cpp.

OccupancyGrid * karto::OccupancyGrid::Clone ( ) const

Makes a clone

Returns
occupancy grid clone

Definition at line 53 of file OccupancyGrid.cpp.

void karto::OccupancyGrid::ComputeDimensions ( const LocalizedLaserScanList rScans,
kt_double  resolution,
kt_int32s rWidth,
kt_int32s rHeight,
Vector2d rOffset 
)
staticprotected

Calculates grid dimensions from localized laser scans and resolution

Parameters
rScansscans
resolutionresolution
rWidth(output parameter) width
rHeight(output parameter) height
rOffset(output parameter) offset

Definition at line 105 of file OccupancyGrid.cpp.

OccupancyGrid * karto::OccupancyGrid::CreateFromMapper ( OpenMapper pMapper,
kt_double  resolution 
)
staticprotected

Occupancy grid from the scans in the given mapper using the given resolution

Note
Please assign the returned occupancy grid to an OccupancyGridPtr to avoid memory leaks.
Parameters
pMappermapper
resolutionresolution
Returns
occupancy grid from the given scans using the given resolution

Definition at line 100 of file OccupancyGrid.cpp.

OccupancyGrid * karto::OccupancyGrid::CreateFromScans ( const LocalizedLaserScanList rScans,
kt_double  resolution 
)
staticprotected

public: /** Occupancy grid from the given scans using the given resolution

Note
Please assign the returned occupancy grid to an OccupancyGridPtr to avoid memory leaks.
Parameters
rScanslist of scans
resolutionresolution
Returns
occupancy grid from the given scans using the given resolution

Definition at line 84 of file OccupancyGrid.cpp.

OccupancyGrid * karto::OccupancyGrid::CreateFromScans ( const std::vector< SmartPointer< LocalizedRangeScan > > &  rScans,
kt_double  resolution 
)
staticprotected

Occupancy grid from the given scans using the given resolution

Note
Please assign the returned occupancy grid to an OccupancyGridPtr to avoid memory leaks.
Parameters
rScansscans
resolutionresolution
Deprecated:
Please use CreateFromScans(const LocalizedLaserScanList& rScans, kt_double resolution)
Warning
Throws exception in Windows
Returns
occupancy grid from the given scans using the given resolution

Definition at line 72 of file OccupancyGrid.cpp.

void karto::OccupancyGrid::CreateFromScans ( const LocalizedLaserScanList rScans)
protectedvirtual

Creates grid using scans

Parameters
rScansscans

Definition at line 126 of file OccupancyGrid.cpp.

Grid<kt_int32u>* karto::OccupancyGrid::GetCellHitsCounts ( )
inlineprotected

Gets grid of cell hit counts

Returns
grid of cell hit counts

Definition at line 144 of file OccupancyGrid.h.

Grid<kt_int32u>* karto::OccupancyGrid::GetCellPassCounts ( )
inlineprotected

Get grid of cell pass counts

Returns
grid of cell pass counts

Definition at line 153 of file OccupancyGrid.h.

kt_bool karto::OccupancyGrid::IsFree ( const Vector2i rGridIndex) const
inline

Checks if the given grid index is free

Parameters
rGridIndexgrid index
Returns
whether the cell at the given grid index is free space

Definition at line 124 of file OccupancyGrid.h.

karto::OccupancyGrid::KARTO_RTTI ( )
private
const OccupancyGrid& karto::OccupancyGrid::operator= ( const OccupancyGrid )
private
kt_double karto::OccupancyGrid::RayCast ( const Pose2 rPose2,
kt_double  maxRange 
) const

Casts a ray from the given point (up to the given max range) and returns the distance to the closest obstacle

Parameters
rPose2starting point
maxRangemaximum range
Returns
distance to closest obstacle

Definition at line 186 of file OccupancyGrid.cpp.

kt_bool karto::OccupancyGrid::RayTrace ( const Vector2d rWorldFrom,
const Vector2d rWorldTo,
kt_bool  isEndPointValid,
kt_bool  doUpdate = false 
)
protected

Traces a beam from the start position to the end position marking the bookkeeping arrays accordingly.

Parameters
rWorldFromstart position of beam
rWorldToend position of beam
isEndPointValidis the reading within the range threshold?
doUpdatewhether to update the cells' occupancy status immediately
Returns
returns false if an endpoint fell off the grid, otherwise true

Definition at line 226 of file OccupancyGrid.cpp.

void karto::OccupancyGrid::Resize ( kt_int32s  width,
kt_int32s  height 
)
protectedvirtual

Resizes the grid (deletes all old data)

Parameters
widthnew width
heightnew height

Reimplemented from karto::Grid< kt_int8u >.

Definition at line 296 of file OccupancyGrid.cpp.

void karto::OccupancyGrid::UpdateCell ( kt_int8u pCell,
kt_int32u  cellPassCnt,
kt_int32u  cellHitCnt 
)
protected

Updates a single cell's value based on the given counters

Parameters
pCellcell
cellPassCntcell pass count
cellHitCntcell hit count

Definition at line 260 of file OccupancyGrid.cpp.

void karto::OccupancyGrid::UpdateGrid ( )
protected

Updates the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt

Definition at line 277 of file OccupancyGrid.cpp.

Friends And Related Function Documentation

friend class CellUpdater
friend

Definition at line 61 of file OccupancyGrid.h.

friend class IncrementalOccupancyGrid
friend

Definition at line 62 of file OccupancyGrid.h.

Member Data Documentation

SmartPointer< Grid<kt_int32u> > karto::OccupancyGrid::m_pCellHitsCnt
protected

Counters of number of times a beam ended at a cell

Definition at line 223 of file OccupancyGrid.h.

SmartPointer< Grid<kt_int32u> > karto::OccupancyGrid::m_pCellPassCnt
protected

Counters of number of times a beam passed through a cell

Definition at line 218 of file OccupancyGrid.h.

CellUpdater* karto::OccupancyGrid::m_pCellUpdater
private

Definition at line 226 of file OccupancyGrid.h.

SmartPointer<Parameter<kt_int32u> > karto::OccupancyGrid::m_pMinPassThrough
private

Definition at line 234 of file OccupancyGrid.h.

SmartPointer<Parameter<kt_double> > karto::OccupancyGrid::m_pOccupancyThreshold
private

Definition at line 237 of file OccupancyGrid.h.


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


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:36