Program Listing for File dynamicEDTOctomap.h
↰ Return to documentation for file (/tmp/ws/src/octomap/dynamicEDT3D/include/dynamicEDT3D/dynamicEDTOctomap.h
)
/*
* Copyright (c) 2011-2012, C. Sprunk, B. Lau, W. Burgard, University of Freiburg
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the University of Freiburg nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef DYNAMICEDTOCTOMAP_H_
#define DYNAMICEDTOCTOMAP_H_
#include "dynamicEDT3D.h"
#include <octomap/OcTree.h>
#include <octomap/OcTreeStamped.h>
template <class TREE>
class DynamicEDTOctomapBase: private DynamicEDT3D {
public:
DynamicEDTOctomapBase(float maxdist, TREE* _octree, octomap::point3d bbxMin, octomap::point3d bbxMax, bool treatUnknownAsOccupied);
virtual ~DynamicEDTOctomapBase();
virtual void update(bool updateRealDist=true);
void getDistanceAndClosestObstacle(const octomap::point3d& p, float &distance, octomap::point3d& closestObstacle) const;
float getDistance(const octomap::point3d& p) const;
float getDistance(const octomap::OcTreeKey& k) const;
int getSquaredDistanceInCells(const octomap::point3d& p) const;
//variant of getDistanceAndClosestObstacle that ommits the check whether p is inside the area of the distance map. Use only if you are certain that p is covered by the distance map and if you need to save the time of the check.
void getDistanceAndClosestObstacle_unsafe(const octomap::point3d& p, float &distance, octomap::point3d& closestObstacle) const;
//variant of getDistance that ommits the check whether p is inside the area of the distance map. Use only if you are certain that p is covered by the distance map and if you need to save the time of the check.
float getDistance_unsafe(const octomap::point3d& p) const;
//variant of getDistance that ommits the check whether p is inside the area of the distance map. Use only if you are certain that p is covered by the distance map and if you need to save the time of the check.
float getDistance_unsafe(const octomap::OcTreeKey& k) const;
//variant of getSquaredDistanceInCells that ommits the check whether p is inside the area of the distance map. Use only if you are certain that p is covered by the distance map and if you need to save the time of the check.
int getSquaredDistanceInCells_unsafe(const octomap::point3d& p) const;
float getMaxDist() const {
return maxDist*octree->getResolution();
}
int getSquaredMaxDistCells() const {
return maxDist_squared;
}
bool checkConsistency() const;
static float distanceValue_Error;
static int distanceInCellsValue_Error;
private:
void initializeOcTree(octomap::point3d bbxMin, octomap::point3d bbxMax);
void insertMaxDepthLeafAtInitialize(octomap::OcTreeKey key);
void updateMaxDepthLeaf(octomap::OcTreeKey& key, bool occupied);
void worldToMap(const octomap::point3d &p, int &x, int &y, int &z) const;
void mapToWorld(int x, int y, int z, octomap::point3d &p) const;
void mapToWorld(int x, int y, int z, octomap::OcTreeKey &key) const;
TREE* octree;
bool unknownOccupied;
int treeDepth;
double treeResolution;
octomap::OcTreeKey boundingBoxMinKey;
octomap::OcTreeKey boundingBoxMaxKey;
int offsetX, offsetY, offsetZ;
};
typedef DynamicEDTOctomapBase<octomap::OcTree> DynamicEDTOctomap;
typedef DynamicEDTOctomapBase<octomap::OcTreeStamped> DynamicEDTOctomapStamped;
#include "dynamicEDTOctomap.hxx"
#endif /* DYNAMICEDTOCTOMAP_H_ */