Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cOctreeStampedNativeRos Class Reference

#include <octree_stamped_native_ros.h>

Inheritance diagram for cOctreeStampedNativeRos:
Inheritance graph
[legend]

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 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::LaserScan &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::PointCloud &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::PointCloud2 &cloud, const cAddCloudParameter &params, 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 &current, const int current_level, OctKey &child, const int child_pos) const
 
virtual ros::Time getLastInsertionTime (void) const
 function for returning the time the octomap was last updated More...
 
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 &current, 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 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 &params, const tf::Transform &transform)
 
void getChildKeySimple (const OctKey &current, 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 &current, const int current_level, OctKey &parent) const
 helper function for getParentKey More...
 

Protected Attributes

ros::Time last_degrading_time_
 
- Protected Attributes inherited from cOctreeBasePaRos< octomap::OcTreeStamped >
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...
 

Detailed Description

Definition at line 64 of file octree_stamped_native_ros.h.

Member Typedef Documentation

◆ TreeTypeBase

Definition at line 113 of file octree_stamped_native_ros.h.

Constructor & Destructor Documentation

◆ cOctreeStampedNativeRos()

cOctreeStampedNativeRos::cOctreeStampedNativeRos ( const double  resolution)

default constructor

Definition at line 58 of file octree_stamped_native_ros.cpp.

◆ ~cOctreeStampedNativeRos()

cOctreeStampedNativeRos::~cOctreeStampedNativeRos ( )
virtual

default destructor

Definition at line 64 of file octree_stamped_native_ros.cpp.

Member Function Documentation

◆ checkDegrading()

void cOctreeStampedNativeRos::checkDegrading ( void  )
protected

helper function for automatic degrading

Definition at line 75 of file octree_stamped_native_ros.cpp.

◆ degradeOutdatedNodes()

void cOctreeStampedNativeRos::degradeOutdatedNodes ( void  )

degrading outdated nodes

Definition at line 68 of file octree_stamped_native_ros.cpp.

Member Data Documentation

◆ last_degrading_time_

ros::Time cOctreeStampedNativeRos::last_degrading_time_
protected

Definition at line 128 of file octree_stamped_native_ros.h.

◆ rosparams_

cOctreeStampedPaRosParameter cOctreeStampedNativeRos::rosparams_

parameters

Definition at line 125 of file octree_stamped_native_ros.h.


The documentation for this class was generated from the following files:


octomap_pa
Author(s):
autogenerated on Wed Mar 2 2022 00:46:31