|
| cOctreeStampedPaNode () |
| default constructor More...
|
|
void | publishOctomap (void) |
| function for publishing the octomap More...
|
|
| ~cOctreeStampedPaNode () |
| default destructor More...
|
|
| cOctreeStampedPaRos (const double resolution) |
| default constructor More...
|
|
void | degradeOutdatedNodes (void) |
| degrading outdated nodes More...
|
|
ros::Time | getLastInsertionTime (void) const |
| function for returning the time the octomap was last updated More...
|
|
void | setLastInsertionTime (const ros::Time &time) |
| function for setting the time the octomap was last updated More...
|
|
cTimePa | timeFromRos (const ros::Time &time) const |
| function for converting from ros::Time to cTimePa More...
|
|
ros::Time | timeToRos (const cTimePa &time) const |
| function for converting from cTimePa to ros::Time More...
|
|
virtual | ~cOctreeStampedPaRos () |
| default destructor More...
|
|
bool | addCloud (const sensor_msgs::PointCloud2ConstPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
|
bool | addCloud (const sensor_msgs::PointCloudConstPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
|
bool | addCloud (const sensor_msgs::LaserScanConstPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
|
virtual void | clear (void) |
| clear local timestamps with octomap More...
|
|
| cOctreeBasePaRos (double resolution) |
| default constructor More...
|
|
bool | getChildKey (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
|
octomap_msgs::OctomapPtr | getOctomap (void) const |
| function for getting the binary octomap More...
|
|
octomap_msgs::OctomapPtr | getOctomapFull (void) const |
| function for getting the full octomap More...
|
|
sensor_msgs::PointCloud2Ptr | getOctomapPcd (const int tree_depth=0, const bool expand=false) const |
| function for getting the pointcloud equivalent of the octomap More...
|
|
sensor_msgs::PointCloud2Ptr | getOctomapPcdFree (const int tree_depth=0, const bool expand=false) const |
| similar to getOctomapPcd, but only returning just empty voxels More...
|
|
ros::Time | getOutputTime (void) const |
|
bool | getParentKey (const OctKey ¤t, const int current_level, OctKey &parent) const |
|
geometry_msgs::PointPtr | keyToPoint (const OctKey &key) const |
| function for converting from key to point (geometry_msg) More...
|
|
void | keyToPoint (const OctKey &key, double &x, double &y, double &z) const |
| function for converting from key to real coordinates More...
|
|
OctKey | pointToKey (const geometry_msgs::Point &point) const |
| functions for converting from point (geometry_msg) to key More...
|
|
bool | readFull (const std::string &filename) |
| trying to read the given file into the current OcTree More...
|
|
void | setOutputTime (const ros::Time &time) |
|
bool | updateTime (const ros::Time &time) |
|
virtual | ~cOctreeBasePaRos () |
| default destructor More...
|
|
| cOcTreeStampedPa (double resolution) |
| Default constructor, sets resolution of leafs. More...
|
|
cOcTreeStampedPa * | create () const |
|
virtual std::string | getTreeType () const |
|
virtual | ~cOcTreeStampedPa (void) |
|
| cOcTreeStampedBasePa (double resolution) |
| Default constructor, sets resolution of leafs. More...
|
|
cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > * | create () const |
|
void | degradeOutdatedNodes (const cTimePa timediff) |
|
const cTimePa & | getTimestamp (void) const |
|
void | setTimestamp (const cTimePa timestamp) |
|
virtual void | updateNodeLogOdds (NodeTypeFull *node, const float &update) const |
|
virtual | ~cOcTreeStampedBasePa (void) |
|
bool | bbxSet () const |
|
virtual bool | castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const |
|
KeyBoolMap::const_iterator | changedKeysBegin () const |
|
KeyBoolMap::const_iterator | changedKeysEnd () const |
|
void | computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
|
void | computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
|
void | enableChangeDetection (bool enable) |
|
point3d | getBBXBounds () const |
|
point3d | getBBXCenter () const |
|
point3d | getBBXMax () const |
|
point3d | getBBXMin () const |
|
bool | getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const |
|
virtual bool | getRayIntersection (const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const |
|
bool | inBBX (const point3d &p) const |
|
bool | inBBX (const OcTreeKey &key) const |
|
virtual void | insertPointCloud (const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
|
virtual void | insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
|
virtual void | insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
|
virtual void | insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false) |
|
virtual bool | insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false) |
|
virtual void | integrateHit (cNodeStampedBasePa< octomap::OcTreeNode > *occupancyNode) const |
|
virtual void | integrateMiss (cNodeStampedBasePa< octomap::OcTreeNode > *occupancyNode) const |
|
bool | isChangeDetectionEnabled () const |
|
virtual void | nodeToMaxLikelihood (cNodeStampedBasePa< octomap::OcTreeNode > *occupancyNode) const |
|
virtual void | nodeToMaxLikelihood (cNodeStampedBasePa< octomap::OcTreeNode > &occupancyNode) const |
|
size_t | numChangesDetected () const |
|
| OccupancyOcTreeBase (double resolution) |
|
| OccupancyOcTreeBase (const OccupancyOcTreeBase< cNodeStampedBasePa< octomap::OcTreeNode > > &rhs) |
|
std::istream & | readBinaryData (std::istream &s) |
|
std::istream & | readBinaryNode (std::istream &s, cNodeStampedBasePa< octomap::OcTreeNode > *node) |
|
void | resetChangeDetection () |
|
void | setBBXMax (point3d &max) |
|
void | setBBXMin (point3d &min) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false) |
|
virtual void | toMaxLikelihood () |
|
void | updateInnerOccupancy () |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (const point3d &value, bool occupied, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false) |
|
virtual cNodeStampedBasePa< octomap::OcTreeNode > * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false) |
|
void | useBBXLimit (bool enable) |
|
std::ostream & | writeBinaryData (std::ostream &s) const |
|
std::ostream & | writeBinaryNode (std::ostream &s, const cNodeStampedBasePa< octomap::OcTreeNode > *node) const |
|
virtual | ~OccupancyOcTreeBase () |
|
OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const |
|
key_type | adjustKeyAtDepth (key_type key, unsigned int depth) const |
|
iterator | begin (unsigned char maxDepth=0) const |
|
leaf_iterator | begin_leafs (unsigned char maxDepth=0) const |
|
leaf_bbx_iterator | begin_leafs_bbx (const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const |
|
leaf_bbx_iterator | begin_leafs_bbx (const point3d &min, const point3d &max, unsigned char maxDepth=0) const |
|
tree_iterator | begin_tree (unsigned char maxDepth=0) const |
|
size_t | calcNumNodes () const |
|
void | clear () |
|
void | clearKeyRays () |
|
bool | computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray) |
|
bool | computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const |
|
OcTreeKey | coordToKey (double x, double y, double z) const |
|
OcTreeKey | coordToKey (const point3d &coord, unsigned depth) const |
|
OcTreeKey | coordToKey (double x, double y, double z, unsigned depth) const |
|
key_type | coordToKey (double coordinate) const |
|
key_type | coordToKey (double coordinate, unsigned depth) const |
|
OcTreeKey | coordToKey (const point3d &coord) const |
|
bool | coordToKeyChecked (const point3d &coord, OcTreeKey &key) const |
|
bool | coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const |
|
bool | coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const |
|
bool | coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const |
|
bool | coordToKeyChecked (double coordinate, key_type &key) const |
|
bool | coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | createNodeChild (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int childIdx) |
|
bool | deleteNode (double x, double y, double z, unsigned int depth=0) |
|
bool | deleteNode (const point3d &value, unsigned int depth=0) |
|
bool | deleteNode (const OcTreeKey &key, unsigned int depth=0) |
|
void | deleteNodeChild (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int childIdx) |
|
const iterator | end () const |
|
const leaf_iterator | end_leafs () const |
|
const leaf_bbx_iterator | end_leafs_bbx () const |
|
const tree_iterator | end_tree () const |
|
virtual void | expand () |
|
virtual void | expandNode (cNodeStampedBasePa< octomap::OcTreeNode > *node) |
|
virtual void | getMetricMax (double &x, double &y, double &z) |
|
void | getMetricMax (double &x, double &y, double &z) const |
|
virtual void | getMetricMin (double &x, double &y, double &z) |
|
void | getMetricMin (double &x, double &y, double &z) const |
|
virtual void | getMetricSize (double &x, double &y, double &z) |
|
virtual void | getMetricSize (double &x, double &y, double &z) const |
|
const cNodeStampedBasePa< octomap::OcTreeNode > * | getNodeChild (const cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int childIdx) const |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | getNodeChild (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int childIdx) const |
|
double | getNodeSize (unsigned depth) const |
|
size_t | getNumLeafNodes () const |
|
double | getResolution () const |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | getRoot () const |
|
unsigned int | getTreeDepth () const |
|
std::string | getTreeType () const |
|
void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const |
|
virtual bool | isNodeCollapsible (const cNodeStampedBasePa< octomap::OcTreeNode > *node) const |
|
point3d | keyToCoord (const OcTreeKey &key) const |
|
point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const |
|
double | keyToCoord (key_type key) const |
|
double | keyToCoord (key_type key, unsigned depth) const |
|
unsigned long long | memoryFullGrid () const |
|
virtual size_t | memoryUsage () const |
|
virtual size_t | memoryUsageNode () const |
|
bool | nodeChildExists (const cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int childIdx) const |
|
bool | nodeHasChildren (const cNodeStampedBasePa< octomap::OcTreeNode > *node) const |
|
| OcTreeBaseImpl (const OcTreeBaseImpl< cNodeStampedBasePa< octomap::OcTreeNode >, AbstractOccupancyOcTree > &rhs) |
|
| OcTreeBaseImpl (double resolution) |
|
bool | operator== (const OcTreeBaseImpl< cNodeStampedBasePa< octomap::OcTreeNode >, AbstractOccupancyOcTree > &rhs) const |
|
virtual void | prune () |
|
virtual bool | pruneNode (cNodeStampedBasePa< octomap::OcTreeNode > *node) |
|
std::istream & | readData (std::istream &s) |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | search (const point3d &value, unsigned int depth=0) const |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | search (const OcTreeKey &key, unsigned int depth=0) const |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | search (double x, double y, double z, unsigned int depth=0) const |
|
void | setResolution (double r) |
|
virtual size_t | size () const |
|
void | swapContent (OcTreeBaseImpl< cNodeStampedBasePa< octomap::OcTreeNode >, AbstractOccupancyOcTree > &rhs) |
|
double | volume () |
|
std::ostream & | writeData (std::ostream &s) const |
|
virtual | ~OcTreeBaseImpl () |
|
|
void | addLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg) |
| callback function for receiving a laserscan More...
|
|
void | addPointcloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg) |
| callback function for receiving a pointcloud More...
|
|
void | addPointcloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg) |
| callback function for receiving a pointcloud (old format) More...
|
|
bool | clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
|
bool | getSizeCallbackSrv (octomap_pa::OctomapPaGetSize::Request &req, octomap_pa::OctomapPaGetSize::Response &res) |
|
bool | loadCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res) |
|
bool | saveCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res) |
|
void | checkDegrading (void) |
| helper function for automatic degrading More...
|
|
bool | addCloud (const PclPointCloudPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform &transform) |
|
void | getChildKeySimple (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
| helper function for getChildKey More...
|
|
void | getOctomapPcdSub (const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const |
| helper function for getOctomapPcd... More...
|
|
void | getParentKeySimple (const OctKey ¤t, const int current_level, OctKey &parent) const |
| helper function for getParentKey More...
|
|
bool | integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false) |
|
| OccupancyOcTreeBase (double resolution, unsigned int tree_depth, unsigned int tree_max_val) |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | setNodeValueRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false) |
|
void | toMaxLikelihoodRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int depth, unsigned int max_depth) |
|
void | updateInnerOccupancyRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int depth) |
|
cNodeStampedBasePa< octomap::OcTreeNode > * | updateNodeRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false) |
|
void | allocNodeChildren (cNodeStampedBasePa< octomap::OcTreeNode > *node) |
|
void | calcMinMax () |
|
void | calcNumNodesRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, size_t &num_nodes) const |
|
void | deleteNodeRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node) |
|
bool | deleteNodeRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key) |
|
void | expandRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int depth, unsigned int max_depth) |
|
size_t | getNumLeafNodesRecurs (const cNodeStampedBasePa< octomap::OcTreeNode > *parent) const |
|
void | init () |
|
| OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val) |
|
void | pruneRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned) |
|
std::istream & | readNodesRecurs (cNodeStampedBasePa< octomap::OcTreeNode > *, std::istream &s) |
|
std::ostream & | writeNodesRecurs (const cNodeStampedBasePa< octomap::OcTreeNode > *, std::ostream &s) const |
|