Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cOctreeBasePaRos< OCTREE > Class Template Reference

#include <octree_base_pa_ros.h>

Inheritance diagram for cOctreeBasePaRos< OCTREE >:
Inheritance graph
[legend]

Public Types

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 OCTREE TreeTypeBase
 
typedef cOctreeBasePaRos< OCTREE > TreeTypeFull
 

Public Member Functions

bool addCloud (const sensor_msgs::PointCloud2ConstPtr &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::PointCloudConstPtr &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::LaserScanConstPtr &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
 
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 &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

cOctreeBasePaRosParameter rosparams_base_
 parameters More...
 

Protected Member Functions

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 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

template<typename OCTREE>
class cOctreeBasePaRos< OCTREE >

Definition at line 75 of file octree_base_pa_ros.h.

Member Typedef Documentation

template<typename OCTREE>
typedef ::octomap::OcTreeKey cOctreeBasePaRos< OCTREE >::OctKey

Definition at line 86 of file octree_base_pa_ros.h.

template<typename OCTREE>
typedef pcl::PointCloud<pcl::PointXYZ> cOctreeBasePaRos< OCTREE >::PclPointCloud

Definition at line 81 of file octree_base_pa_ros.h.

template<typename OCTREE>
typedef pcl::PointCloud<pcl::PointXYZ>::ConstPtr cOctreeBasePaRos< OCTREE >::PclPointCloudConstPtr

Definition at line 84 of file octree_base_pa_ros.h.

template<typename OCTREE>
typedef pcl::PointCloud<pcl::PointXYZ>::Ptr cOctreeBasePaRos< OCTREE >::PclPointCloudPtr

Definition at line 82 of file octree_base_pa_ros.h.

template<typename OCTREE>
typedef OCTREE cOctreeBasePaRos< OCTREE >::TreeTypeBase

Definition at line 78 of file octree_base_pa_ros.h.

template<typename OCTREE>
typedef cOctreeBasePaRos<OCTREE> cOctreeBasePaRos< OCTREE >::TreeTypeFull

Definition at line 79 of file octree_base_pa_ros.h.

Constructor & Destructor Documentation

template<typename OCTREE>
cOctreeBasePaRos< OCTREE >::cOctreeBasePaRos ( double  resolution)

default constructor

template<typename OCTREE>
virtual cOctreeBasePaRos< OCTREE >::~cOctreeBasePaRos ( )
virtual

default destructor

Member Function Documentation

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::addCloud ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
const cAddCloudParameter params,
const tf::Transform  transform = tf::Transform::getIdentity() 
)

function for filtering and adding a pointcloud (call updateTime() before)

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::addCloud ( const sensor_msgs::PointCloudConstPtr cloud,
const cAddCloudParameter params,
const tf::Transform  transform = tf::Transform::getIdentity() 
)

function for filtering and adding a pointcloud (old format) (call updateTime() before)

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::addCloud ( const sensor_msgs::LaserScanConstPtr &  cloud,
const cAddCloudParameter params,
const tf::Transform  transform = tf::Transform::getIdentity() 
)

function for filtering and adding a pointcloud (laserscan) (call updateTime() before)

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::addCloud ( const PclPointCloudPtr cloud,
const cAddCloudParameter params,
const tf::Transform transform 
)
protected

internal function for adding a pointlcoud - the cloud will be manipulated !

template<typename OCTREE>
virtual void cOctreeBasePaRos< OCTREE >::clear ( void  )
virtual

clear local timestamps with octomap

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::getChildKey ( const OctKey current,
const int  current_level,
OctKey child,
const int  child_pos 
) const

helper function for calculating child key child_pos(bitmask) 0(x)[0=neg;1=pos] | 1(y)[0=neg;1=pos] | 2(z)[0=neg;1=pos] child_pos is the same as for octomap::OctreeNode::getChild() returns true if child key exists

template<typename OCTREE>
void cOctreeBasePaRos< OCTREE >::getChildKeySimple ( const OctKey current,
const int  current_level,
OctKey child,
const int  child_pos 
) const
protected

helper function for getChildKey

template<typename OCTREE>
virtual ros::Time cOctreeBasePaRos< OCTREE >::getLastInsertionTime ( void  ) const
virtual

function for returning the time the octomap was last updated (instead of this function use updateTime() )

Reimplemented in cOctreeStampedPaRos.

template<typename OCTREE>
octomap_msgs::OctomapPtr cOctreeBasePaRos< OCTREE >::getOctomap ( void  ) const

function for getting the binary octomap

template<typename OCTREE>
octomap_msgs::OctomapPtr cOctreeBasePaRos< OCTREE >::getOctomapFull ( void  ) const

function for getting the full octomap

template<typename OCTREE>
sensor_msgs::PointCloud2Ptr cOctreeBasePaRos< OCTREE >::getOctomapPcd ( const int  tree_depth = 0,
const bool  expand = false 
) const

function for getting the pointcloud equivalent of the octomap

template<typename OCTREE>
sensor_msgs::PointCloud2Ptr cOctreeBasePaRos< OCTREE >::getOctomapPcdFree ( const int  tree_depth = 0,
const bool  expand = false 
) const

similar to getOctomapPcd, but only returning just empty voxels

template<typename OCTREE>
void cOctreeBasePaRos< OCTREE >::getOctomapPcdSub ( const OctKey key,
const int  current_level,
const int  min_level,
PclPointCloud cloud 
) const
protected

helper function for getOctomapPcd...

template<typename OCTREE>
ros::Time cOctreeBasePaRos< OCTREE >::getOutputTime ( void  ) const

function for returning the time of output messages (instead of this function use updateTime() )

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::getParentKey ( const OctKey current,
const int  current_level,
OctKey parent 
) const

helper function for calculating parent key returns true if parent key exists

template<typename OCTREE>
void cOctreeBasePaRos< OCTREE >::getParentKeySimple ( const OctKey current,
const int  current_level,
OctKey parent 
) const
protected

helper function for getParentKey

template<typename OCTREE>
geometry_msgs::PointPtr cOctreeBasePaRos< OCTREE >::keyToPoint ( const OctKey key) const

function for converting from key to point (geometry_msg)

template<typename OCTREE>
void cOctreeBasePaRos< OCTREE >::keyToPoint ( const OctKey key,
double &  x,
double &  y,
double &  z 
) const

function for converting from key to real coordinates

template<typename OCTREE>
OctKey cOctreeBasePaRos< OCTREE >::pointToKey ( const geometry_msgs::Point point) const

functions for converting from point (geometry_msg) to key

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::readFull ( const std::string &  filename)

trying to read the given file into the current OcTree

template<typename OCTREE>
virtual void cOctreeBasePaRos< OCTREE >::setLastInsertionTime ( const ros::Time time)
virtual

function for setting the time the octomap was last updated (instead of this function use updateTime() )

Reimplemented in cOctreeStampedPaRos.

template<typename OCTREE>
void cOctreeBasePaRos< OCTREE >::setOutputTime ( const ros::Time time)

function for setting the time of output messages (instead of this function use updateTime() )

template<typename OCTREE>
bool cOctreeBasePaRos< OCTREE >::updateTime ( const ros::Time time)

function for updating all timestamps (Insertion & Output) returns false if an time jump backwards is detected this might be used for resetting tf_listener

Member Data Documentation

template<typename OCTREE>
ros::Time cOctreeBasePaRos< OCTREE >::current_output_time_
protected

internal variable for storing current output time

Definition at line 171 of file octree_base_pa_ros.h.

template<typename OCTREE>
ros::Time cOctreeBasePaRos< OCTREE >::last_insertion_time_
protected

internal variable for storing last insertion time

Definition at line 169 of file octree_base_pa_ros.h.

template<typename OCTREE>
cOctreeBasePaRosParameter cOctreeBasePaRos< OCTREE >::rosparams_base_

parameters

Definition at line 165 of file octree_base_pa_ros.h.


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


octomap_pa
Author(s):
autogenerated on Thu Jun 11 2020 03:38:50