Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
DynamicEDTOctomap Class Reference

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

#include <dynamicEDTOctomap.h>

Inheritance diagram for DynamicEDTOctomap:
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...
 
 DynamicEDTOctomap (float maxdist, octomap::OcTree *_octree, octomap::point3d bbxMin, octomap::point3d bbxMax, bool treatUnknownAsOccupied)
 
float getDistance (const octomap::point3d &p) const
 retrieves distance at point. Returns DynamicEDTOctomap::distanceValue_Error if point is outside the map. More...
 
float getDistance (const octomap::OcTreeKey &k) const
 retrieves distance at key. Returns DynamicEDTOctomap::distanceValue_Error if key is outside the map. More...
 
float getDistance_unsafe (const octomap::point3d &p) const
 
float getDistance_unsafe (const octomap::OcTreeKey &k) 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 DynamicEDTOctomap::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 ~DynamicEDTOctomap ()
 

Static Public Attributes

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...
 

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::point3d &p) const
 
void mapToWorld (int x, int y, int z, octomap::OcTreeKey &key) 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
 
octomap::OcTreeoctree
 
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

A DynamicEDTOctomap 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 45 of file dynamicEDTOctomap.h.

Constructor & Destructor Documentation

DynamicEDTOctomap::DynamicEDTOctomap ( float  maxdist,
octomap::OcTree _octree,
octomap::point3d  bbxMin,
octomap::point3d  bbxMax,
bool  treatUnknownAsOccupied 
)

Create a DynamicEDTOctomap 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!

Definition at line 43 of file dynamicEDTOctomap.cpp.

DynamicEDTOctomap::~DynamicEDTOctomap ( )
virtual

Definition at line 52 of file dynamicEDTOctomap.cpp.

Member Function Documentation

bool DynamicEDTOctomap::checkConsistency ( ) const

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

Definition at line 291 of file dynamicEDTOctomap.cpp.

float DynamicEDTOctomap::getDistance ( const octomap::point3d p) const

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

Definition at line 235 of file dynamicEDTOctomap.cpp.

float DynamicEDTOctomap::getDistance ( const octomap::OcTreeKey k) const

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

Definition at line 252 of file dynamicEDTOctomap.cpp.

float DynamicEDTOctomap::getDistance_unsafe ( const octomap::point3d p) const

Definition at line 245 of file dynamicEDTOctomap.cpp.

float DynamicEDTOctomap::getDistance_unsafe ( const octomap::OcTreeKey k) const

Definition at line 265 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::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 DynamicEDTOctomap::distanceValue_Error if point is outside the map.

Definition at line 202 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::getDistanceAndClosestObstacle_unsafe ( const octomap::point3d p,
float &  distance,
octomap::point3d closestObstacle 
) const

Definition at line 220 of file dynamicEDTOctomap.cpp.

float DynamicEDTOctomap::getMaxDist ( ) const
inline

retrieve maximum distance value

Definition at line 88 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::getSquaredDistanceInCells ( const octomap::point3d p) const

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

Definition at line 274 of file dynamicEDTOctomap.cpp.

int DynamicEDTOctomap::getSquaredDistanceInCells_unsafe ( const octomap::point3d p) const

Definition at line 284 of file dynamicEDTOctomap.cpp.

int DynamicEDTOctomap::getSquaredMaxDistCells ( ) const
inline

retrieve squared maximum distance value in grid cells

Definition at line 93 of file dynamicEDTOctomap.h.

void DynamicEDTOctomap::initializeOcTree ( octomap::point3d  bbxMin,
octomap::point3d  bbxMax 
)
private

Definition at line 82 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::insertMaxDepthLeafAtInitialize ( octomap::OcTreeKey  key)
private

Definition at line 143 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::mapToWorld ( int  x,
int  y,
int  z,
octomap::point3d p 
) const
private

Definition at line 193 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::mapToWorld ( int  x,
int  y,
int  z,
octomap::OcTreeKey key 
) const
private

Definition at line 197 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::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.

Definition at line 57 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::updateMaxDepthLeaf ( octomap::OcTreeKey key,
bool  occupied 
)
private

Definition at line 179 of file dynamicEDTOctomap.cpp.

void DynamicEDTOctomap::worldToMap ( const octomap::point3d p,
int &  x,
int &  y,
int &  z 
) const
private

Definition at line 186 of file dynamicEDTOctomap.cpp.

Member Data Documentation

octomap::OcTreeKey DynamicEDTOctomap::boundingBoxMaxKey
private

Definition at line 119 of file dynamicEDTOctomap.h.

octomap::OcTreeKey DynamicEDTOctomap::boundingBoxMinKey
private

Definition at line 118 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::distanceInCellsValue_Error = -1
static

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

Definition at line 103 of file dynamicEDTOctomap.h.

float DynamicEDTOctomap::distanceValue_Error = -1.0
static

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

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 101 of file dynamicEDTOctomap.h.

octomap::OcTree* DynamicEDTOctomap::octree
private

Definition at line 114 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::offsetX
private

Definition at line 120 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::offsetY
private

Definition at line 120 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::offsetZ
private

Definition at line 120 of file dynamicEDTOctomap.h.

int DynamicEDTOctomap::treeDepth
private

Definition at line 116 of file dynamicEDTOctomap.h.

double DynamicEDTOctomap::treeResolution
private

Definition at line 117 of file dynamicEDTOctomap.h.

bool DynamicEDTOctomap::unknownOccupied
private

Definition at line 115 of file dynamicEDTOctomap.h.


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


dynamicEDT3D
Author(s): Christoph Sprunk
autogenerated on Mon Jun 10 2019 14:00:23