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);
506 #include "octomap/OccupancyOcTreeBase.hxx"
void updateInnerOccupancyRecurs(NODE *node, unsigned int depth)
point3d getBBXMin() const
std::ostream & writeBinaryNode(std::ostream &s, const NODE *node) const
void updateInnerOccupancy()
void computeDiscreteUpdate(const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
point3d getBBXMax() const
virtual NODE * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
bool integrateMissOnRay(const point3d &origin, const point3d &end, bool lazy_eval=false)
const iterator end() const
size_t numChangesDetected() const
Number of changes since last reset.
std::istream & readBinaryData(std::istream &s)
virtual ~OccupancyOcTreeBase()
unordered_ns::unordered_map< OcTreeKey, bool, OcTreeKey::KeyHash > KeyBoolMap
double resolution
in meters
virtual void integrateHit(NODE *occupancyNode) const
integrate a "hit" measurement according to the tree's sensor model
OccupancyOcTreeBase(double resolution)
Default constructor, sets resolution of leafs.
bool inBBX(const point3d &p) const
void setBBXMax(point3d &max)
sets the maximum for a query bounding box to use
std::ostream & writeBinaryData(std::ostream &s) const
virtual NODE * setNodeValue(const OcTreeKey &key, float log_odds_value, bool lazy_eval=false)
virtual void insertPointCloud(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
bool isChangeDetectionEnabled() const
virtual bool insertRay(const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false)
virtual bool castRay(const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
std::istream & readBinaryNode(std::istream &s, NODE *node)
virtual void updateNodeLogOdds(NODE *occupancyNode, const float &update) const
update logodds value of node by adding to the current value.
bool use_bbx_limit
use bounding box for queries (needs to be set)?
virtual void nodeToMaxLikelihood(NODE *occupancyNode) const
converts the node to the maximum likelihood value according to the tree's parameter for "occupancy" ...
virtual void insertPointCloudRays(const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false)
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
NODE * setNodeValueRecurs(NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false)
This class represents a tree-dimensional pose of an object.
point3d getBBXCenter() const
bool getNormals(const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const
void useBBXLimit(bool enable)
use or ignore BBX limit (default: ignore)
NODE * updateNodeRecurs(NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false)
This class represents a three-dimensional vector.
void setBBXMin(point3d &min)
sets the minimum for a query bounding box to use
virtual void toMaxLikelihood()
KeyBoolMap::const_iterator changedKeysBegin() const
void computeUpdate(const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
KeyBoolMap changed_keys
Set of leaf keys (lowest level) which changed since last resetChangeDetection.
void resetChangeDetection()
Reset the set of changed keys. Call this after you obtained all changed nodes.
virtual bool getRayIntersection(const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const
void enableChangeDetection(bool enable)
track or ignore changes while inserting scans (default: ignore)
bool use_change_detection
const unsigned int tree_max_val
void toMaxLikelihoodRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
point3d getBBXBounds() const
virtual void integrateMiss(NODE *occupancyNode) const
integrate a "miss" measurement according to the tree's sensor model
KeyBoolMap::const_iterator changedKeysEnd() const
Iterator to traverse all keys of changed nodes.