#include <octree_stamped_pa_ros.h>

| Public Types | |
| typedef cOctreeBasePaRos< cOcTreeStampedPa > | TreeTypeBase | 
|  Public Types inherited from cOctreeBasePaRos< cOcTreeStampedPa > | |
| 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 cOcTreeStampedPa | TreeTypeBase | 
| typedef cOctreeBasePaRos< cOcTreeStampedPa > | TreeTypeFull | 
|  Public Types inherited from cOcTreeStampedPa | |
| typedef octomap::OcTreeNode | NodeTypeBase | 
| typedef cNodeStampedBasePa< NodeTypeBase > | NodeTypeFull | 
| typedef cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, NodeTypeBase > | TreeTypeBase | 
|  Public Types inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > | |
| typedef octomap::OcTreeNode | NodeTypeBase | 
| typedef cNodeStampedBasePa< octomap::OcTreeNode > | NodeTypeFull | 
| typedef octomap::OccupancyOcTreeBase< NodeTypeFull > | TreeTypeBase | 
| Public Member Functions | |
| 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... | |
|  Public Member Functions inherited from cOctreeBasePaRos< cOcTreeStampedPa > | |
| bool | addCloud (const sensor_msgs::LaserScan &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) | 
| bool | addCloud (const sensor_msgs::PointCloud &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) | 
| bool | addCloud (const sensor_msgs::PointCloud2 &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 | 
| function for returning the time of output messages  More... | |
| 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... | |
|  Public Member Functions inherited from cOcTreeStampedPa | |
| cOcTreeStampedPa (double resolution) | |
| Default constructor, sets resolution of leafs.  More... | |
| cOcTreeStampedPa * | create () const | 
| virtual std::string | getTreeType () const | 
| virtual | ~cOcTreeStampedPa (void) | 
|  Public Member Functions inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > | |
| 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) | 
| Public Attributes | |
| cOctreeStampedPaRosParameter | rosparams_ | 
| parameters  More... | |
|  Public Attributes inherited from cOctreeBasePaRos< cOcTreeStampedPa > | |
| cOctreeBasePaRosParameter | rosparams_base_ | 
| parameters  More... | |
| Protected Member Functions | |
| void | checkDegrading (void) | 
| helper function for automatic degrading  More... | |
|  Protected Member Functions inherited from cOctreeBasePaRos< cOcTreeStampedPa > | |
| 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 Attributes | |
| ros::Time | last_degrading_time_ | 
|  Protected Attributes inherited from cOctreeBasePaRos< cOcTreeStampedPa > | |
| ros::Time | current_output_time_ | 
| internal variable for storing current output time  More... | |
| ros::Time | last_insertion_time_ | 
| internal variable for storing last insertion time  More... | |
|  Protected Attributes inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > | |
| cTimePa | current_timestamp | 
| used to set new data (insertion of measurement) to actual time stamp  More... | |
| Additional Inherited Members | |
|  Static Protected Attributes inherited from cOcTreeStampedPa | |
| static StaticMemberInitializer | StaticMemberInit | 
| to ensure static initialization (only once)  More... | |
Definition at line 62 of file octree_stamped_pa_ros.h.
Definition at line 110 of file octree_stamped_pa_ros.h.
| cOctreeStampedPaRos::cOctreeStampedPaRos | ( | const double | resolution | ) | 
default constructor
Definition at line 58 of file octree_stamped_pa_ros.cpp.
| 
 | virtual | 
default destructor
Definition at line 64 of file octree_stamped_pa_ros.cpp.
| 
 | protected | 
helper function for automatic degrading
Definition at line 99 of file octree_stamped_pa_ros.cpp.
| void cOctreeStampedPaRos::degradeOutdatedNodes | ( | void | ) | 
degrading outdated nodes
Definition at line 68 of file octree_stamped_pa_ros.cpp.
| 
 | virtual | 
function for returning the time the octomap was last updated
Reimplemented from cOctreeBasePaRos< cOcTreeStampedPa >.
Definition at line 75 of file octree_stamped_pa_ros.cpp.
| 
 | virtual | 
function for setting the time the octomap was last updated
Reimplemented from cOctreeBasePaRos< cOcTreeStampedPa >.
Definition at line 81 of file octree_stamped_pa_ros.cpp.
function for converting from ros::Time to cTimePa
Definition at line 93 of file octree_stamped_pa_ros.cpp.
function for converting from cTimePa to ros::Time
Definition at line 87 of file octree_stamped_pa_ros.cpp.
| 
 | protected | 
Definition at line 135 of file octree_stamped_pa_ros.h.
| cOctreeStampedPaRosParameter cOctreeStampedPaRos::rosparams_ | 
parameters
Definition at line 132 of file octree_stamped_pa_ros.h.