Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
DynamicEDTOctomapBase< TREE > Class Template Reference

A DynamicEDTOctomapBase object connects a DynamicEDT3D object to an octomap. More...

#include <dynamicEDTOctomap.h>

Inheritance diagram for DynamicEDTOctomapBase< TREE >:
Inheritance graph
[legend]

Public Member Functions

bool checkConsistency () const
 Brute force method used for debug purposes. Checks occupancy state consistency between octomap and internal representation. More...
 
 DynamicEDTOctomapBase (float maxdist, TREE *_octree, octomap::point3d bbxMin, octomap::point3d bbxMax, bool treatUnknownAsOccupied)
 
float getDistance (const octomap::OcTreeKey &k) const
 retrieves distance at key. Returns DynamicEDTOctomapBase::distanceValue_Error if key is outside the map. More...
 
float getDistance (const octomap::point3d &p) const
 retrieves distance at point. Returns DynamicEDTOctomapBase::distanceValue_Error if point is outside the map. More...
 
float getDistance_unsafe (const octomap::OcTreeKey &k) const
 
float getDistance_unsafe (const octomap::point3d &p) const
 
void getDistanceAndClosestObstacle (const octomap::point3d &p, float &distance, octomap::point3d &closestObstacle) const
 
void getDistanceAndClosestObstacle_unsafe (const octomap::point3d &p, float &distance, octomap::point3d &closestObstacle) const
 
float getMaxDist () const
 retrieve maximum distance value More...
 
int getSquaredDistanceInCells (const octomap::point3d &p) const
 retrieves squared distance in cells at point. Returns DynamicEDTOctomapBase::distanceInCellsValue_Error if point is outside the map. More...
 
int getSquaredDistanceInCells_unsafe (const octomap::point3d &p) const
 
int getSquaredMaxDistCells () const
 retrieve squared maximum distance value in grid cells More...
 
virtual void update (bool updateRealDist=true)
 
virtual ~DynamicEDTOctomapBase ()
 

Static Public Attributes

static int distanceInCellsValue_Error
 distance value returned when requesting distance in cell units for a cell outside the map More...
 
static float distanceValue_Error
 distance value returned when requesting distance for a cell outside the map More...
 

Private Member Functions

void initializeOcTree (octomap::point3d bbxMin, octomap::point3d bbxMax)
 
void insertMaxDepthLeafAtInitialize (octomap::OcTreeKey key)
 
void mapToWorld (int x, int y, int z, octomap::OcTreeKey &key) const
 
void mapToWorld (int x, int y, int z, octomap::point3d &p) const
 
void updateMaxDepthLeaf (octomap::OcTreeKey &key, bool occupied)
 
void worldToMap (const octomap::point3d &p, int &x, int &y, int &z) const
 
- Private Member Functions inherited from DynamicEDT3D
void clearCell (int x, int y, int z)
 remove an obstacle at the specified cell coordinate More...
 
 DynamicEDT3D (int _maxdist_squared)
 
void exchangeObstacles (std::vector< INTPOINT3D > newObstacles)
 remove old dynamic obstacles and add the new ones More...
 
INTPOINT3D getClosestObstacle (int x, int y, int z) const
 gets the closest occupied cell for that location More...
 
float getDistance (int x, int y, int z) const
 returns the obstacle distance at the specified location More...
 
unsigned int getSizeX () const
 returns the x size of the workspace/map More...
 
unsigned int getSizeY () const
 returns the y size of the workspace/map More...
 
unsigned int getSizeZ () const
 returns the z size of the workspace/map More...
 
int getSQCellDistance (int x, int y, int z) const
 returns the squared obstacle distance in cell units at the specified location More...
 
void initializeEmpty (int _sizeX, int _sizeY, int sizeZ, bool initGridMap=true)
 Initialization with an empty map. More...
 
void initializeMap (int _sizeX, int _sizeY, int sizeZ, bool ***_gridMap)
 Initialization with a given binary map (false==free, true==occupied) More...
 
bool isOccupied (int x, int y, int z) const
 checks whether the specficied location is occupied More...
 
void occupyCell (int x, int y, int z)
 add an obstacle at the specified cell coordinate More...
 
 ~DynamicEDT3D ()
 
void inspectCellPropagate (int &nx, int &ny, int &nz, dataCell &c, bool updateRealDist)
 
void inspectCellRaise (int &nx, int &ny, int &nz, bool updateRealDist)
 
void propagateCell (INTPOINT3D &p, dataCell &c, bool updateRealDist)
 
void raiseCell (INTPOINT3D &p, dataCell &c, bool updateRealDist)
 
void removeObstacle (int x, int y, int z)
 
void setObstacle (int x, int y, int z)
 

Private Attributes

octomap::OcTreeKey boundingBoxMaxKey
 
octomap::OcTreeKey boundingBoxMinKey
 
TREE * octree
 
int offsetX
 
int offsetY
 
int offsetZ
 
int treeDepth
 
double treeResolution
 
bool unknownOccupied
 
- Private Attributes inherited from DynamicEDT3D
dataCell *** data
 
double doubleThreshold
 
bool *** gridMap
 
double maxDist
 
int maxDist_squared
 
int padding
 
int sizeX
 
int sizeXm1
 
int sizeY
 
int sizeYm1
 
int sizeZ
 
int sizeZm1
 
double sqrt2
 

Additional Inherited Members

- Private Types inherited from DynamicEDT3D
enum  ObstDataState { invalidObstData = INT_MAX }
 
enum  QueueingState {
  fwNotQueued =1, fwQueued =2, fwProcessed =3, bwQueued =4,
  bwProcessed =1
}
 
enum  State { free =0, occupied =1 }
 
- Static Private Attributes inherited from DynamicEDT3D
static int distanceInCellsValue_Error = -1
 distance value returned when requesting distance in cell units for a cell outside the map More...
 
static float distanceValue_Error = -1.0
 distance value returned when requesting distance for a cell outside the map More...
 

Detailed Description

template<class TREE>
class DynamicEDTOctomapBase< TREE >

A DynamicEDTOctomapBase object connects a DynamicEDT3D object to an octomap.

dynamicEDT3D: A library for incrementally updatable Euclidean distance transforms in 3D.

Author
C. Sprunk, B. Lau, W. Burgard, University of Freiburg, Copyright (C) 2011.
See also
http://octomap.sourceforge.net/ License: New BSD License

Definition at line 47 of file dynamicEDTOctomap.h.

Constructor & Destructor Documentation

◆ DynamicEDTOctomapBase()

template<class TREE >
DynamicEDTOctomapBase< TREE >::DynamicEDTOctomapBase ( float  maxdist,
TREE *  _octree,
octomap::point3d  bbxMin,
octomap::point3d  bbxMax,
bool  treatUnknownAsOccupied 
)

Create a DynamicEDTOctomapBase object that maintains a distance transform in the bounding box given by bbxMin, bbxMax and clamps distances at maxdist. treatUnknownAsOccupied configures the treatment of unknown cells in the distance computation.

The constructor copies occupancy data but does not yet compute the distance map. You need to call udpate to do this.

The distance map is maintained in a full three-dimensional array, i.e., there exists a float field in memory for every voxel inside the bounding box given by bbxMin and bbxMax. Consider this when computing distance maps for large octomaps, they will use much more memory than the octomap itself!

◆ ~DynamicEDTOctomapBase()

template<class TREE >
virtual DynamicEDTOctomapBase< TREE >::~DynamicEDTOctomapBase ( )
virtual

Member Function Documentation

◆ checkConsistency()

template<class TREE >
bool DynamicEDTOctomapBase< TREE >::checkConsistency ( ) const

Brute force method used for debug purposes. Checks occupancy state consistency between octomap and internal representation.

◆ getDistance() [1/2]

template<class TREE >
float DynamicEDTOctomapBase< TREE >::getDistance ( const octomap::OcTreeKey k) const

retrieves distance at key. Returns DynamicEDTOctomapBase::distanceValue_Error if key is outside the map.

◆ getDistance() [2/2]

template<class TREE >
float DynamicEDTOctomapBase< TREE >::getDistance ( const octomap::point3d p) const

retrieves distance at point. Returns DynamicEDTOctomapBase::distanceValue_Error if point is outside the map.

◆ getDistance_unsafe() [1/2]

template<class TREE >
float DynamicEDTOctomapBase< TREE >::getDistance_unsafe ( const octomap::OcTreeKey k) const

◆ getDistance_unsafe() [2/2]

template<class TREE >
float DynamicEDTOctomapBase< TREE >::getDistance_unsafe ( const octomap::point3d p) const

◆ getDistanceAndClosestObstacle()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::getDistanceAndClosestObstacle ( const octomap::point3d p,
float &  distance,
octomap::point3d closestObstacle 
) const

retrieves distance and closestObstacle (closestObstacle is to be discarded if distance is maximum distance, the method does not write closestObstacle in this case). Returns DynamicEDTOctomapBase::distanceValue_Error if point is outside the map.

◆ getDistanceAndClosestObstacle_unsafe()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::getDistanceAndClosestObstacle_unsafe ( const octomap::point3d p,
float &  distance,
octomap::point3d closestObstacle 
) const

◆ getMaxDist()

template<class TREE >
float DynamicEDTOctomapBase< TREE >::getMaxDist ( ) const
inline

retrieve maximum distance value

Definition at line 90 of file dynamicEDTOctomap.h.

◆ getSquaredDistanceInCells()

template<class TREE >
int DynamicEDTOctomapBase< TREE >::getSquaredDistanceInCells ( const octomap::point3d p) const

retrieves squared distance in cells at point. Returns DynamicEDTOctomapBase::distanceInCellsValue_Error if point is outside the map.

◆ getSquaredDistanceInCells_unsafe()

template<class TREE >
int DynamicEDTOctomapBase< TREE >::getSquaredDistanceInCells_unsafe ( const octomap::point3d p) const

◆ getSquaredMaxDistCells()

template<class TREE >
int DynamicEDTOctomapBase< TREE >::getSquaredMaxDistCells ( ) const
inline

retrieve squared maximum distance value in grid cells

Definition at line 95 of file dynamicEDTOctomap.h.

◆ initializeOcTree()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::initializeOcTree ( octomap::point3d  bbxMin,
octomap::point3d  bbxMax 
)
private

◆ insertMaxDepthLeafAtInitialize()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::insertMaxDepthLeafAtInitialize ( octomap::OcTreeKey  key)
private

◆ mapToWorld() [1/2]

template<class TREE >
void DynamicEDTOctomapBase< TREE >::mapToWorld ( int  x,
int  y,
int  z,
octomap::OcTreeKey key 
) const
private

◆ mapToWorld() [2/2]

template<class TREE >
void DynamicEDTOctomapBase< TREE >::mapToWorld ( int  x,
int  y,
int  z,
octomap::point3d p 
) const
private

◆ update()

template<class TREE >
virtual void DynamicEDTOctomapBase< TREE >::update ( bool  updateRealDist = true)
virtual

trigger updating of the distance map. This will query the octomap for the set of changes since the last update. If you set updateRealDist to false, computations will be faster (square root will be omitted), but you can only retrieve squared distances

Reimplemented from DynamicEDT3D.

◆ updateMaxDepthLeaf()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::updateMaxDepthLeaf ( octomap::OcTreeKey key,
bool  occupied 
)
private

◆ worldToMap()

template<class TREE >
void DynamicEDTOctomapBase< TREE >::worldToMap ( const octomap::point3d p,
int &  x,
int &  y,
int &  z 
) const
private

Member Data Documentation

◆ boundingBoxMaxKey

template<class TREE >
octomap::OcTreeKey DynamicEDTOctomapBase< TREE >::boundingBoxMaxKey
private

Definition at line 121 of file dynamicEDTOctomap.h.

◆ boundingBoxMinKey

template<class TREE >
octomap::OcTreeKey DynamicEDTOctomapBase< TREE >::boundingBoxMinKey
private

Definition at line 120 of file dynamicEDTOctomap.h.

◆ distanceInCellsValue_Error

template<class TREE >
int DynamicEDTOctomapBase< TREE >::distanceInCellsValue_Error
static

distance value returned when requesting distance in cell units for a cell outside the map

Definition at line 105 of file dynamicEDTOctomap.h.

◆ distanceValue_Error

template<class TREE >
float DynamicEDTOctomapBase< TREE >::distanceValue_Error
static

distance value returned when requesting distance for a cell outside the map

Definition at line 103 of file dynamicEDTOctomap.h.

◆ octree

template<class TREE >
TREE* DynamicEDTOctomapBase< TREE >::octree
private

Definition at line 116 of file dynamicEDTOctomap.h.

◆ offsetX

template<class TREE >
int DynamicEDTOctomapBase< TREE >::offsetX
private

Definition at line 122 of file dynamicEDTOctomap.h.

◆ offsetY

template<class TREE >
int DynamicEDTOctomapBase< TREE >::offsetY
private

Definition at line 122 of file dynamicEDTOctomap.h.

◆ offsetZ

template<class TREE >
int DynamicEDTOctomapBase< TREE >::offsetZ
private

Definition at line 122 of file dynamicEDTOctomap.h.

◆ treeDepth

template<class TREE >
int DynamicEDTOctomapBase< TREE >::treeDepth
private

Definition at line 118 of file dynamicEDTOctomap.h.

◆ treeResolution

template<class TREE >
double DynamicEDTOctomapBase< TREE >::treeResolution
private

Definition at line 119 of file dynamicEDTOctomap.h.

◆ unknownOccupied

template<class TREE >
bool DynamicEDTOctomapBase< TREE >::unknownOccupied
private

Definition at line 117 of file dynamicEDTOctomap.h.


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


dynamicEDT3D
Author(s): Christoph Sprunk
autogenerated on Tue Dec 12 2023 03:39:46