Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends
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 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
void SetMinPassThrough (kt_int32u count)
void SetOccupancyThreshold (kt_double thresh)
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 Grid< kt_int32u > * GetCellHitsCounts ()
virtual Grid< kt_int32u > * GetCellPassCounts ()
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
class IncrementalOccupancyGrid

Detailed Description

Occupancy grid definition. See GridStates for possible grid values.

Definition at line 5591 of file Karto.h.


Constructor & Destructor Documentation

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 5604 of file Karto.h.

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

Destructor

Definition at line 5627 of file Karto.h.

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
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 5837 of file Karto.h.

Make a clone

Returns:
occupancy grid clone

Definition at line 5664 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]

Calculate grid dimensions from localized range scans

Parameters:
rScans
resolution
rWidth
rHeight
rOffset

Definition at line 5789 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:
rScans
resolution

Definition at line 5644 of file Karto.h.

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

Create grid using scans

Parameters:
rScans

Definition at line 5813 of file Karto.h.

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

Get cell hit grid

Returns:
Grid<kt_int32u>*

Definition at line 5766 of file Karto.h.

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

Get cell pass grid

Returns:
Grid<kt_int32u>*

Definition at line 5775 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 5684 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 5702 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:
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 5895 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 5982 of file Karto.h.

Sets the minimum number of beams that must pass through a cell before it will be considered to be occupied or unoccupied. This prevents stray beams from messing up the map.

Definition at line 5747 of file Karto.h.

Sets the minimum ratio of beams hitting cell to beams passing through cell for cell to be marked as occupied.

Definition at line 5756 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 5958 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 5938 of file Karto.h.


Friends And Related Function Documentation

friend class CellUpdater [friend]

Definition at line 5593 of file Karto.h.

friend class IncrementalOccupancyGrid [friend]

Definition at line 5594 of file Karto.h.


Member Data Documentation

Counters of number of times a beam ended at a cell

Definition at line 5998 of file Karto.h.

Counters of number of times a beam passed through a cell

Definition at line 5993 of file Karto.h.

Definition at line 6012 of file Karto.h.

Definition at line 6020 of file Karto.h.

Definition at line 6023 of file Karto.h.


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


open_karto
Author(s):
autogenerated on Thu Jun 6 2019 21:02:57