Public Member Functions | Static 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 <Karto.h>

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

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 ()
 
- 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 ()
 
virtual kt_int32s GridIndex (const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
 
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
 
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 OccupancyGridCreateFromScans (const LocalizedRangeScanVector &rScans, kt_double resolution)
 
- 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 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)
 
- Protected Member Functions inherited from karto::Grid< kt_int8u >
 Grid (kt_int32s width, kt_int32s height)
 

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

Constructor & Destructor Documentation

◆ OccupancyGrid() [1/2]

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

◆ ~OccupancyGrid()

virtual karto::OccupancyGrid::~OccupancyGrid ( )
inlinevirtual

Destructor

Definition at line 6042 of file Karto.h.

◆ OccupancyGrid() [2/2]

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

Restrict the copy constructor

Member Function Documentation

◆ AddScan()

virtual kt_bool karto::OccupancyGrid::AddScan ( LocalizedRangeScan pScan,
kt_bool  doUpdate = false 
)
inlineprotectedvirtual

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

◆ Clone()

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

Make a clone

Returns
occupancy grid clone

Definition at line 6079 of file Karto.h.

◆ ComputeDimensions()

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

Calculate grid dimensions from localized range scans

Parameters
rScans
resolution
rWidth
rHeight
rOffset

Definition at line 6204 of file Karto.h.

◆ CreateFromScans() [1/2]

static OccupancyGrid* karto::OccupancyGrid::CreateFromScans ( const LocalizedRangeScanVector rScans,
kt_double  resolution 
)
inlinestatic

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

Parameters
rScans
resolution

Definition at line 6059 of file Karto.h.

◆ CreateFromScans() [2/2]

virtual void karto::OccupancyGrid::CreateFromScans ( const LocalizedRangeScanVector rScans)
inlineprotectedvirtual

Create grid using scans

Parameters
rScans

Definition at line 6234 of file Karto.h.

◆ GetCellHitsCounts()

virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellHitsCounts ( )
inlineprotectedvirtual

Get cell hit grid

Returns
Grid<kt_int32u>*

Definition at line 6181 of file Karto.h.

◆ GetCellPassCounts()

virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellPassCounts ( )
inlineprotectedvirtual

Get cell pass grid

Returns
Grid<kt_int32u>*

Definition at line 6190 of file Karto.h.

◆ IsFree()

virtual kt_bool karto::OccupancyGrid::IsFree ( const Vector2< kt_int32s > &  rPose) const
inlinevirtual

Check if grid point is free

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

Definition at line 6099 of file Karto.h.

◆ operator=()

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

Restrict the assignment operator

◆ RayCast()

virtual kt_double karto::OccupancyGrid::RayCast ( const Pose2 rPose2,
kt_double  maxRange 
) const
inlinevirtual

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

◆ RayTrace()

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

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

◆ Resize()

virtual void karto::OccupancyGrid::Resize ( kt_int32s  width,
kt_int32s  height 
)
inlineprotectedvirtual

Resizes the grid (deletes all old data)

Parameters
width
height

Reimplemented from karto::Grid< kt_int8u >.

Definition at line 6408 of file Karto.h.

◆ SetMinPassThrough()

void karto::OccupancyGrid::SetMinPassThrough ( kt_int32u  count)
inline

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

◆ SetOccupancyThreshold()

void karto::OccupancyGrid::SetOccupancyThreshold ( kt_double  thresh)
inline

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

Definition at line 6171 of file Karto.h.

◆ Update()

virtual void karto::OccupancyGrid::Update ( )
inlineprotectedvirtual

Update the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt

Definition at line 6384 of file Karto.h.

◆ UpdateCell()

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

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

Parameters
pCell
cellPassCnt
cellHitCnt

Definition at line 6364 of file Karto.h.

Friends And Related Function Documentation

◆ CellUpdater

friend class CellUpdater
friend

Definition at line 6008 of file Karto.h.

◆ IncrementalOccupancyGrid

friend class IncrementalOccupancyGrid
friend

Definition at line 6009 of file Karto.h.

Member Data Documentation

◆ m_pCellHitsCnt

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

Counters of number of times a beam ended at a cell

Definition at line 6424 of file Karto.h.

◆ m_pCellPassCnt

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

Counters of number of times a beam passed through a cell

Definition at line 6419 of file Karto.h.

◆ m_pCellUpdater

CellUpdater* karto::OccupancyGrid::m_pCellUpdater
private

Definition at line 6438 of file Karto.h.

◆ m_pMinPassThrough

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

Definition at line 6446 of file Karto.h.

◆ m_pOccupancyThreshold

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

Definition at line 6449 of file Karto.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