karto::OccupancyGrid Class Reference

#include <Karto.h>

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

List of all members.

Public Member Functions

OccupancyGridClone () const
virtual Grid< kt_int32u > * GetCellHitsCounts ()
virtual Grid< kt_int32u > * GetCellPassCounts ()
virtual kt_bool IsFree (const Vector2< kt_int32s > &rPose) const
 OccupancyGrid (kt_int32s width, kt_int32s height, const Vector2< kt_double > &rOffset, kt_double resolution)
virtual kt_double RayCast (const Pose2 &rPose2, kt_double maxRange) const
virtual ~OccupancyGrid ()

Static Public Member Functions

static OccupancyGridCreateFromScans (const LocalizedRangeScanVector &rScans, kt_double resolution)

Protected Member Functions

virtual kt_bool AddScan (LocalizedRangeScan *pScan, kt_bool doUpdate=false)
virtual void CreateFromScans (const LocalizedRangeScanVector &rScans)
virtual kt_bool RayTrace (const Vector2< kt_double > &rWorldFrom, const Vector2< kt_double > &rWorldTo, kt_bool isEndPointValid, kt_bool doUpdate=false)
virtual void Resize (kt_int32s width, kt_int32s height)
virtual void Update ()
virtual void UpdateCell (kt_int8u *pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)

Static Protected Member Functions

static void ComputeDimensions (const LocalizedRangeScanVector &rScans, kt_double resolution, kt_int32s &rWidth, kt_int32s &rHeight, Vector2< kt_double > &rOffset)

Protected Attributes

Grid< kt_int32u > * m_pCellHitsCnt
Grid< kt_int32u > * m_pCellPassCnt

Private Member Functions

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

Private Attributes

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

Friends

class CellUpdater

Detailed Description

Occupancy grid definition. See GridStates for possible grid values.

Definition at line 5238 of file Karto.h.


Constructor & Destructor Documentation

virtual karto::OccupancyGrid::~OccupancyGrid (  )  [inline, virtual]

Destructor

Definition at line 5246 of file Karto.h.

karto::OccupancyGrid::OccupancyGrid ( kt_int32s  width,
kt_int32s  height,
const Vector2< kt_double > &  rOffset,
kt_double  resolution 
) [inline]

Constructs an occupancy grid of given size

Parameters:
width 
height 
rOffset 
resolution 

Definition at line 5265 of file Karto.h.

karto::OccupancyGrid::OccupancyGrid ( const OccupancyGrid  )  [private]

Restrict the copy constructor


Member Function Documentation

virtual kt_bool karto::OccupancyGrid::AddScan ( LocalizedRangeScan pScan,
kt_bool  doUpdate = false 
) [inline, protected, virtual]

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

Parameters:
pScan 
doUpdate whether to update the grid's cell's occupancy status
Returns:
returns false if an endpoint fell off the grid, otherwise true

Definition at line 5440 of file Karto.h.

OccupancyGrid* karto::OccupancyGrid::Clone (  )  const [inline]

Make a clone

Returns:
occupancy grid clone

Definition at line 5310 of file Karto.h.

static void karto::OccupancyGrid::ComputeDimensions ( const LocalizedRangeScanVector rScans,
kt_double  resolution,
kt_int32s rWidth,
kt_int32s rHeight,
Vector2< kt_double > &  rOffset 
) [inline, static, protected]

Definition at line 5396 of file Karto.h.

virtual void karto::OccupancyGrid::CreateFromScans ( const LocalizedRangeScanVector rScans  )  [inline, protected, virtual]

Create grid using scans

Parameters:
scans 

Definition at line 5416 of file Karto.h.

static OccupancyGrid* karto::OccupancyGrid::CreateFromScans ( const LocalizedRangeScanVector rScans,
kt_double  resolution 
) [inline, static]

Create an occupancy grid from the given scans using the given resolution

Parameters:
scans 
resolution 

Definition at line 5290 of file Karto.h.

virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellHitsCounts (  )  [inline, virtual]

Definition at line 5385 of file Karto.h.

virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellPassCounts (  )  [inline, virtual]

Definition at line 5390 of file Karto.h.

virtual kt_bool karto::OccupancyGrid::IsFree ( const Vector2< kt_int32s > &  rPose  )  const [inline, virtual]

Check if grid point is free

Parameters:
rPose 
Returns:
whether the cell at the given point is free space

Definition at line 5327 of file Karto.h.

const OccupancyGrid& karto::OccupancyGrid::operator= ( const OccupancyGrid  )  [private]

Restrict the assignment operator

virtual kt_double karto::OccupancyGrid::RayCast ( const Pose2 rPose2,
kt_double  maxRange 
) const [inline, virtual]

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

Parameters:
rPose2 
maxRange 
Returns:
distance to closest obstacle

Definition at line 5345 of file Karto.h.

virtual kt_bool karto::OccupancyGrid::RayTrace ( const Vector2< kt_double > &  rWorldFrom,
const Vector2< kt_double > &  rWorldTo,
kt_bool  isEndPointValid,
kt_bool  doUpdate = false 
) [inline, protected, virtual]

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

Parameters:
rWorldFrom start position of beam
rWorldTo end position of beam
isEndPointValid is the reading within the range threshold?
pCoordinatorConverter converter from world to grid coordinates
whether to update the cells' occupancy status immediately
Returns:
returns false if an endpoint fell off the grid, otherwise true

Definition at line 5498 of file Karto.h.

virtual void karto::OccupancyGrid::Resize ( kt_int32s  width,
kt_int32s  height 
) [inline, protected, virtual]

Resizes the grid (deletes all old data)

Parameters:
width 
height 

Reimplemented from karto::Grid< kt_int8u >.

Definition at line 5582 of file Karto.h.

virtual void karto::OccupancyGrid::Update (  )  [inline, protected, virtual]

Update the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt

Definition at line 5558 of file Karto.h.

virtual void karto::OccupancyGrid::UpdateCell ( kt_int8u pCell,
kt_int32u  cellPassCnt,
kt_int32u  cellHitCnt 
) [inline, protected, virtual]

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

Parameters:
pCell 
cellPassCnt 
cellHitCnt 

Definition at line 5538 of file Karto.h.


Friends And Related Function Documentation

friend class CellUpdater [friend]

Definition at line 5240 of file Karto.h.


Member Data Documentation

Definition at line 5594 of file Karto.h.

Definition at line 5591 of file Karto.h.

Definition at line 5608 of file Karto.h.

Definition at line 5616 of file Karto.h.

Definition at line 5619 of file Karto.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


karto
Author(s): SRI International (package maintained by Brian Gerkey)
autogenerated on Fri Jan 11 10:07:06 2013