#include <octree_stamped_native_ros.h>

| Public Types | |
| typedef cOctreeBasePaRos< OcTreeStamped > | TreeTypeBase | 
|  Public Types inherited from cOctreeBasePaRos< octomap::OcTreeStamped > | |
| typedef ::octomap::OcTreeKey | OctKey | 
| typedef pcl::PointCloud< pcl::PointXYZ > | PclPointCloud | 
| typedef pcl::PointCloud< pcl::PointXYZ >::ConstPtr | PclPointCloudConstPtr | 
| typedef pcl::PointCloud< pcl::PointXYZ >::Ptr | PclPointCloudPtr | 
| typedef octomap::OcTreeStamped | TreeTypeBase | 
| typedef cOctreeBasePaRos< octomap::OcTreeStamped > | TreeTypeFull | 
|  Public Types inherited from OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > | |
| typedef leaf_iterator | iterator | 
| typedef OcTreeNodeStamped | NodeType | 
| Public Member Functions | |
| cOctreeStampedNativeRos (const double resolution) | |
| default constructor  More... | |
| void | degradeOutdatedNodes (void) | 
| degrading outdated nodes  More... | |
| virtual | ~cOctreeStampedNativeRos () | 
| default destructor  More... | |
|  Public Member Functions inherited from cOctreeBasePaRos< octomap::OcTreeStamped > | |
| 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 | 
| virtual ros::Time | getLastInsertionTime (void) 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... | |
| virtual void | setLastInsertionTime (const ros::Time &time) | 
| void | setOutputTime (const ros::Time &time) | 
| bool | updateTime (const ros::Time &time) | 
| virtual | ~cOctreeBasePaRos () | 
| default destructor  More... | |
|  Public Member Functions inherited from octomap::OcTreeStamped | |
| OcTreeStamped * | create () const | 
| void | degradeOutdatedNodes (unsigned int time_thres) | 
| unsigned int | getLastUpdateTime () | 
| std::string | getTreeType () const | 
| void | integrateMissNoTime (OcTreeNodeStamped *node) const | 
| OcTreeStamped (double resolution) | |
| virtual void | updateNodeLogOdds (OcTreeNodeStamped *node, const float &update) const | 
|  Public Member Functions inherited from OccupancyOcTreeBase< OcTreeNodeStamped > | |
| 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 (OcTreeNodeStamped *occupancyNode) const | 
| virtual void | integrateMiss (OcTreeNodeStamped *occupancyNode) const | 
| bool | isChangeDetectionEnabled () const | 
| virtual void | nodeToMaxLikelihood (OcTreeNodeStamped *occupancyNode) const | 
| virtual void | nodeToMaxLikelihood (OcTreeNodeStamped &occupancyNode) const | 
| size_t | numChangesDetected () const | 
| OccupancyOcTreeBase (double resolution) | |
| OccupancyOcTreeBase (const OccupancyOcTreeBase< OcTreeNodeStamped > &rhs) | |
| OCTOMAP_DEPRECATED (virtual void insertScanNaive(const Pointcloud &scan, const point3d &sensor_origin, double maxrange, bool lazy_eval=false)) | |
| OCTOMAP_DEPRECATED (virtual void insertScan(const ScanNode &scan, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) | |
| OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) | |
| OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) | |
| std::istream & | readBinaryData (std::istream &s) | 
| std::istream & | readBinaryNode (std::istream &s, OcTreeNodeStamped *node) const | 
| void | resetChangeDetection () | 
| void | setBBXMax (point3d &max) | 
| void | setBBXMin (point3d &min) | 
| virtual OcTreeNodeStamped * | setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false) | 
| virtual void | toMaxLikelihood () | 
| void | updateInnerOccupancy () | 
| virtual OcTreeNodeStamped * | updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | updateNode (const point3d &value, bool occupied, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false) | 
| virtual OcTreeNodeStamped * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false) | 
| virtual void | updateNodeLogOdds (OcTreeNodeStamped *occupancyNode, const float &update) const | 
| void | useBBXLimit (bool enable) | 
| std::ostream & | writeBinaryData (std::ostream &s) const | 
| std::ostream & | writeBinaryNode (std::ostream &s, const OcTreeNodeStamped *node) const | 
| virtual | ~OccupancyOcTreeBase () | 
|  Public Member Functions inherited from OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > | |
| OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const | 
| unsigned short int | adjustKeyAtDepth (unsigned short int 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 | 
| 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 (const point3d &coord, unsigned depth) const | 
| OcTreeKey | coordToKey (double x, double y, double z, unsigned depth) const | 
| unsigned short int | coordToKey (double coordinate) const | 
| unsigned short int | coordToKey (double coordinate, unsigned depth) const | 
| OcTreeKey | coordToKey (const point3d &coord) const | 
| OcTreeKey | coordToKey (double x, double y, double z) 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, unsigned short int &key) const | 
| bool | coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const | 
| 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) | 
| 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 | 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 | 
| double | getNodeSize (unsigned depth) const | 
| size_t | getNumLeafNodes () const | 
| double | getResolution () const | 
| OcTreeNodeStamped * | getRoot () const | 
| unsigned int | getTreeDepth () const | 
| void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const | 
| point3d | keyToCoord (const OcTreeKey &key) const | 
| double | keyToCoord (unsigned short int key, unsigned depth) const | 
| double | keyToCoord (unsigned short int key) const | 
| point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const | 
| unsigned long long | memoryFullGrid () const | 
| virtual size_t | memoryUsage () const | 
| virtual size_t | memoryUsageNode () const | 
| OcTreeBaseImpl (const OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > &rhs) | |
| OcTreeBaseImpl (double resolution) | |
| bool | operator== (const OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > &rhs) const | 
| virtual void | prune () | 
| std::istream & | readData (std::istream &s) | 
| OcTreeNodeStamped * | search (const OcTreeKey &key, unsigned int depth=0) const | 
| OcTreeNodeStamped * | search (const point3d &value, unsigned int depth=0) const | 
| OcTreeNodeStamped * | search (double x, double y, double z, unsigned int depth=0) const | 
| void | setResolution (double r) | 
| virtual size_t | size () const | 
| void | swapContent (OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > &rhs) | 
| double | volume () | 
| std::ostream & | writeData (std::ostream &s) const | 
| virtual | ~OcTreeBaseImpl () | 
|  Public Member Functions inherited from octomap::AbstractOccupancyOcTree | |
| AbstractOccupancyOcTree () | |
| double | getClampingThresMax () const | 
| float | getClampingThresMaxLog () const | 
| double | getClampingThresMin () const | 
| float | getClampingThresMinLog () const | 
| double | getOccupancyThres () const | 
| float | getOccupancyThresLog () const | 
| double | getProbHit () const | 
| float | getProbHitLog () const | 
| double | getProbMiss () const | 
| float | getProbMissLog () const | 
| bool | isNodeAtThreshold (const OcTreeNode *occupancyNode) const | 
| bool | isNodeAtThreshold (const OcTreeNode &occupancyNode) const | 
| bool | isNodeOccupied (const OcTreeNode *occupancyNode) const | 
| bool | isNodeOccupied (const OcTreeNode &occupancyNode) const | 
| bool | readBinary (std::istream &s) | 
| bool | readBinary (const std::string &filename) | 
| void | setClampingThresMax (double thresProb) | 
| void | setClampingThresMin (double thresProb) | 
| void | setOccupancyThres (double prob) | 
| void | setProbHit (double prob) | 
| void | setProbMiss (double prob) | 
| virtual OcTreeNode * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0 | 
| virtual OcTreeNode * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)=0 | 
| bool | writeBinary (const std::string &filename) | 
| bool | writeBinary (std::ostream &s) | 
| bool | writeBinaryConst (std::ostream &s) const | 
| bool | writeBinaryConst (const std::string &filename) const | 
| virtual | ~AbstractOccupancyOcTree () | 
|  Public Member Functions inherited from octomap::AbstractOcTree | |
| AbstractOcTree () | |
| bool | write (std::ostream &s) const | 
| bool | write (const std::string &filename) const | 
| virtual | ~AbstractOcTree () | 
| Public Attributes | |
| cOctreeStampedPaRosParameter | rosparams_ | 
| parameters  More... | |
|  Public Attributes inherited from cOctreeBasePaRos< octomap::OcTreeStamped > | |
| cOctreeBasePaRosParameter | rosparams_base_ | 
| parameters  More... | |
| Protected Member Functions | |
| void | checkDegrading (void) | 
| helper function for automatic degrading  More... | |
|  Protected Member Functions inherited from cOctreeBasePaRos< octomap::OcTreeStamped > | |
| 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... | |
|  Protected Member Functions inherited from OccupancyOcTreeBase< OcTreeNodeStamped > | |
| bool | integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false) | 
| OccupancyOcTreeBase (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
| OcTreeNodeStamped * | setNodeValueRecurs (OcTreeNodeStamped *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false) | 
| void | toMaxLikelihoodRecurs (OcTreeNodeStamped *node, unsigned int depth, unsigned int max_depth) | 
| void | updateInnerOccupancyRecurs (OcTreeNodeStamped *node, unsigned int depth) | 
| OcTreeNodeStamped * | updateNodeRecurs (OcTreeNodeStamped *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false) | 
|  Protected Member Functions inherited from OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree > | |
| void | calcMinMax () | 
| void | calcNumNodesRecurs (OcTreeNodeStamped *node, size_t &num_nodes) const | 
| bool | deleteNodeRecurs (OcTreeNodeStamped *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key) | 
| void | expandRecurs (OcTreeNodeStamped *node, unsigned int depth, unsigned int max_depth) | 
| size_t | getNumLeafNodesRecurs (const OcTreeNodeStamped *parent) const | 
| void | init () | 
| OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
| void | pruneRecurs (OcTreeNodeStamped *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned) | 
|  Protected Member Functions inherited from octomap::AbstractOccupancyOcTree | |
| bool | readBinaryLegacyHeader (std::istream &s, unsigned int &size, double &res) | 
| Additional Inherited Members | |
|  Static Public Member Functions inherited from octomap::AbstractOcTree | |
| static AbstractOcTree * | createTree (const std::string id, double res) | 
| static AbstractOcTree * | read (std::istream &s) | 
| static AbstractOcTree * | read (const std::string &filename) | 
|  Static Protected Member Functions inherited from octomap::AbstractOcTree | |
| static bool | readHeader (std::istream &s, std::string &id, unsigned &size, double &res) | 
| static void | registerTreeType (AbstractOcTree *tree) | 
|  Static Protected Attributes inherited from octomap::OcTreeStamped | |
| static StaticMemberInitializer | ocTreeStampedMemberInit | 
|  Static Protected Attributes inherited from octomap::AbstractOccupancyOcTree | |
| static const std::string | binaryFileHeader | 
|  Static Protected Attributes inherited from octomap::AbstractOcTree | |
| static const std::string | fileHeader | 
Definition at line 61 of file octree_stamped_native_ros.h.
Definition at line 64 of file octree_stamped_native_ros.h.
| cOctreeStampedNativeRos::cOctreeStampedNativeRos | ( | const double | resolution | ) | 
default constructor
Definition at line 55 of file octree_stamped_native_ros.cpp.
| 
 | virtual | 
default destructor
Definition at line 61 of file octree_stamped_native_ros.cpp.
| 
 | protected | 
helper function for automatic degrading
Definition at line 72 of file octree_stamped_native_ros.cpp.
| void cOctreeStampedNativeRos::degradeOutdatedNodes | ( | void | ) | 
degrading outdated nodes
Definition at line 65 of file octree_stamped_native_ros.cpp.
| 
 | protected | 
Definition at line 79 of file octree_stamped_native_ros.h.
| cOctreeStampedPaRosParameter cOctreeStampedNativeRos::rosparams_ | 
parameters
Definition at line 76 of file octree_stamped_native_ros.h.