Go to the documentation of this file.
34 #ifndef OCTOMAP_OCCUPANCY_OCTREE_BASE_H
35 #define OCTOMAP_OCCUPANCY_OCTREE_BASE_H
97 double maxrange=-1.,
bool lazy_eval =
false,
bool discretize =
false);
118 double maxrange=-1.,
bool lazy_eval =
false,
bool discretize =
false);
132 virtual void insertPointCloud(
const ScanNode& scan,
double maxrange=-1.,
bool lazy_eval =
false,
bool discretize =
false);
170 virtual NODE*
setNodeValue(
const point3d& value,
float log_odds_value,
bool lazy_eval =
false);
184 virtual NODE*
setNodeValue(
double x,
double y,
double z,
float log_odds_value,
bool lazy_eval =
false);
196 virtual NODE*
updateNode(
const OcTreeKey& key,
float log_odds_update,
bool lazy_eval =
false);
208 virtual NODE*
updateNode(
const point3d& value,
float log_odds_update,
bool lazy_eval =
false);
222 virtual NODE*
updateNode(
double x,
double y,
double z,
float log_odds_update,
bool lazy_eval =
false);
245 virtual NODE*
updateNode(
const point3d& value,
bool occupied,
bool lazy_eval =
false);
259 virtual NODE*
updateNode(
double x,
double y,
double z,
bool occupied,
bool lazy_eval =
false);
303 bool ignoreUnknownCells=
false,
double maxRange=-1.0)
const;
317 point3d& intersection,
double delta=0.0)
const;
329 bool getNormals(
const point3d& point, std::vector<point3d>& normals,
bool unknownStatus=
true)
const;
436 std::ostream&
writeBinaryNode(std::ostream &s,
const NODE* node)
const;
480 unsigned int depth,
const float& log_odds_update,
bool lazy_eval =
false);
483 unsigned int depth,
const float& log_odds_value,
bool lazy_eval =
false);
bool bbxSet() const
Definition: OccupancyOcTreeBase.h:335
virtual bool castRay(const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
Performs raycasting in 3d, similar to computeRay().
Definition: OccupancyOcTreeBase.hxx:639
virtual void toMaxLikelihood()
Creates the maximum likelihood map by calling toMaxLikelihood on all tree nodes, setting their occupa...
Definition: OccupancyOcTreeBase.hxx:518
void updateInnerOccupancy()
Updates the occupancy of all inner nodes to reflect their children's occupancy.
Definition: OccupancyOcTreeBase.hxx:494
OcTree base class, to be used with with any kind of OcTreeDataNode.
Definition: OcTreeBaseImpl.h:75
Base implementation for Occupancy Octrees (e.g.
Definition: OccupancyOcTreeBase.h:69
point3d getBBXMax() const
Definition: OccupancyOcTreeBase.h:343
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
KeyBoolMap::const_iterator changedKeysBegin() const
Iterator to traverse all keys of changed nodes.
Definition: OccupancyOcTreeBase.h:363
std::istream & readBinaryData(std::istream &s)
Reads only the data (=complete tree structure) from the input stream.
Definition: OccupancyOcTreeBase.hxx:931
const unsigned int tree_max_val
Definition: OcTreeBaseImpl.h:546
bool isChangeDetectionEnabled() const
Definition: OccupancyOcTreeBase.h:354
void toMaxLikelihoodRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
Definition: OccupancyOcTreeBase.hxx:532
unordered_ns::unordered_map< OcTreeKey, bool, OcTreeKey::KeyHash > KeyBoolMap
Data structrure to efficiently track changed nodes as a combination of OcTreeKeys and a bool flag (to...
Definition: OcTreeKey.h:136
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
Definition: OcTreeBaseImpl.h:545
virtual bool insertRay(const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false)
Insert one ray between origin and end into the tree.
Definition: OccupancyOcTreeBase.hxx:865
NODE * updateNodeRecurs(NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false)
Definition: OccupancyOcTreeBase.hxx:367
OccupancyOcTreeBase(double resolution)
Default constructor, sets resolution of leafs.
Definition: OccupancyOcTreeBase.hxx:42
void updateInnerOccupancyRecurs(NODE *node, unsigned int depth)
Definition: OccupancyOcTreeBase.hxx:500
point3d getBBXBounds() const
Definition: OccupancyOcTreeBase.hxx:915
virtual void insertPointCloud(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
Definition: OccupancyOcTreeBase.hxx:86
void resetChangeDetection()
Reset the set of changed keys. Call this after you obtained all changed nodes.
Definition: OccupancyOcTreeBase.h:356
point3d bbx_min
Definition: OccupancyOcTreeBase.h:492
This class represents a three-dimensional vector.
Definition: Vector3.h:50
OcTreeKey bbx_min_key
Definition: OccupancyOcTreeBase.h:494
virtual NODE * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).
Definition: OccupancyOcTreeBase.hxx:301
virtual void integrateMiss(NODE *occupancyNode) const
integrate a "miss" measurement according to the tree's sensor model
Definition: OccupancyOcTreeBase.hxx:1108
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
Data structure to efficiently compute the nodes to update from a scan insertion using a hash set.
Definition: OcTreeKey.h:129
void computeUpdate(const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
Helper for insertPointCloud().
Definition: OccupancyOcTreeBase.hxx:169
point3d getBBXMin() const
Definition: OccupancyOcTreeBase.h:341
std::ostream & writeBinaryData(std::ostream &s) const
Writes the data of the tree (without header) to the stream, recursively calling writeBinaryNode (star...
Definition: OccupancyOcTreeBase.hxx:946
A 3D scan as Pointcloud, performed from a Pose6D.
Definition: ScanGraph.h:52
virtual void nodeToMaxLikelihood(NODE *occupancyNode) const
converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"
Definition: OccupancyOcTreeBase.hxx:1113
virtual NODE * setNodeValue(const OcTreeKey &key, float log_odds_value, bool lazy_eval=false)
Set log_odds value of voxel to log_odds_value.
Definition: OccupancyOcTreeBase.hxx:267
virtual bool getRayIntersection(const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const
Retrieves the entry point of a ray into a voxel.
Definition: OccupancyOcTreeBase.hxx:762
bool integrateMissOnRay(const point3d &origin, const point3d &end, bool lazy_eval=false)
Traces a ray from origin to end and updates all voxels on the way as free.
Definition: OccupancyOcTreeBase.hxx:851
OcTreeKey bbx_max_key
Definition: OccupancyOcTreeBase.h:495
void setBBXMax(const point3d &max)
sets the maximum for a query bounding box to use
Definition: OccupancyOcTreeBase.hxx:893
OcTreeKey is a container class for internal key addressing.
Definition: OcTreeKey.h:70
virtual ~OccupancyOcTreeBase()
Definition: OccupancyOcTreeBase.hxx:56
bool use_change_detection
Definition: OccupancyOcTreeBase.h:497
virtual void updateNodeLogOdds(NODE *occupancyNode, const float &update) const
update logodds value of node by adding to the current value.
Definition: OccupancyOcTreeBase.hxx:1091
point3d getBBXCenter() const
Definition: OccupancyOcTreeBase.hxx:922
std::ostream & writeBinaryNode(std::ostream &s, const NODE *node) const
Write node to binary stream (max-likelihood value), recursively continue with all children.
Definition: OccupancyOcTreeBase.hxx:1025
KeyBoolMap::const_iterator changedKeysEnd() const
Iterator to traverse all keys of changed nodes.
Definition: OccupancyOcTreeBase.h:366
void enableChangeDetection(bool enable)
track or ignore changes while inserting scans (default: ignore)
Definition: OccupancyOcTreeBase.h:353
NODE * setNodeValueRecurs(NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false)
Definition: OccupancyOcTreeBase.hxx:431
size_t numChangesDetected() const
Number of changes since last reset.
Definition: OccupancyOcTreeBase.h:369
point3d bbx_max
Definition: OccupancyOcTreeBase.h:493
void computeDiscreteUpdate(const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
Helper for insertPointCloud().
Definition: OccupancyOcTreeBase.hxx:148
bool inBBX(const point3d &p) const
Definition: OccupancyOcTreeBase.hxx:902
bool use_bbx_limit
use bounding box for queries (needs to be set)?
Definition: OccupancyOcTreeBase.h:491
const iterator end() const
Definition: OcTreeBaseImpl.h:329
virtual void integrateHit(NODE *occupancyNode) const
integrate a "hit" measurement according to the tree's sensor model
Definition: OccupancyOcTreeBase.hxx:1103
void setBBXMin(const point3d &min)
sets the minimum for a query bounding box to use
Definition: OccupancyOcTreeBase.hxx:885
Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbou...
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
void useBBXLimit(bool enable)
use or ignore BBX limit (default: ignore)
Definition: OccupancyOcTreeBase.h:334
bool getNormals(const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const
Performs a step of the marching cubes surface reconstruction algorithm to retrieve the normal of the ...
Definition: OccupancyOcTreeBase.hxx:551
double resolution
in meters
Definition: OcTreeBaseImpl.h:547
KeyBoolMap changed_keys
Set of leaf keys (lowest level) which changed since last resetChangeDetection.
Definition: OccupancyOcTreeBase.h:499
std::istream & readBinaryNode(std::istream &s, NODE *node)
Read node from binary stream (max-likelihood value), recursively continue with all children.
Definition: OccupancyOcTreeBase.hxx:954
virtual void insertPointCloudRays(const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false)
Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
Definition: OccupancyOcTreeBase.hxx:116