Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
DynamicEDTOctomap Class Reference

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

#include <dynamicEDTOctomap.h>

Inheritance diagram for DynamicEDTOctomap:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool checkConsistency () const
 Brute force method used for debug purposes. Checks occupancy state consistency between octomap and internal representation.
 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.
float getDistance (const octomap::OcTreeKey &k) const
 retrieves distance at key. Returns DynamicEDTOctomap::distanceValue_Error if key is outside the map.
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
int getSquaredDistanceInCells (const octomap::point3d &p) const
 retrieves squared distance in cells at point. Returns DynamicEDTOctomap::distanceInCellsValue_Error if point is outside the map.
int getSquaredDistanceInCells_unsafe (const octomap::point3d &p) const
int getSquaredMaxDistCells () const
 retrieve squared maximum distance value in grid cells
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
static float distanceValue_Error = -1.0
 distance value returned when requesting distance for a cell outside the map

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 Attributes

octomap::OcTreeKey boundingBoxMaxKey
octomap::OcTreeKey boundingBoxMinKey
octomap::OcTreeoctree
int offsetX
int offsetY
int offsetZ
int treeDepth
double treeResolution
bool unknownOccupied

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.

Definition at line 52 of file dynamicEDTOctomap.cpp.


Member Function Documentation

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

Definition at line 291 of file dynamicEDTOctomap.cpp.

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

Definition at line 235 of file dynamicEDTOctomap.cpp.

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

Definition at line 252 of file dynamicEDTOctomap.cpp.

Definition at line 245 of file dynamicEDTOctomap.cpp.

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.

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.

Definition at line 284 of file dynamicEDTOctomap.cpp.

retrieve squared maximum distance value in grid cells

Definition at line 93 of file dynamicEDTOctomap.h.

Definition at line 82 of file dynamicEDTOctomap.cpp.

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

Definition at line 119 of file dynamicEDTOctomap.h.

Definition at line 118 of file dynamicEDTOctomap.h.

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

Reimplemented from DynamicEDT3D.

Definition at line 103 of file dynamicEDTOctomap.h.

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

Reimplemented from DynamicEDT3D.

Definition at line 101 of file dynamicEDTOctomap.h.

Definition at line 114 of file dynamicEDTOctomap.h.

Definition at line 120 of file dynamicEDTOctomap.h.

Definition at line 120 of file dynamicEDTOctomap.h.

Definition at line 120 of file dynamicEDTOctomap.h.

Definition at line 116 of file dynamicEDTOctomap.h.

Definition at line 117 of file dynamicEDTOctomap.h.

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 Thu Feb 11 2016 23:51:18