#include <octree_base_pa_ros.h>
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 ¶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 | |
| cOctreeBasePaRos (double resolution) | |
| default constructor | |
| 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 | |
| octomap_msgs::OctomapPtr | getOctomapFull (void) const |
| function for getting the full octomap | |
| sensor_msgs::PointCloud2Ptr | getOctomapPcd (const int tree_depth=0, const bool expand=false) const |
| function for getting the pointcloud equivalent of the octomap | |
| sensor_msgs::PointCloud2Ptr | getOctomapPcdFree (const int tree_depth=0, const bool expand=false) const |
| similar to getOctomapPcd, but only returning just empty voxels | |
| 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) | |
| void | keyToPoint (const OctKey &key, double &x, double &y, double &z) const |
| function for converting from key to real coordinates | |
| OctKey | pointToKey (const geometry_msgs::Point &point) const |
| functions for converting from point (geometry_msg) to key | |
| bool | readFull (const std::string &filename) |
| trying to read the given file into the current OcTree | |
| virtual void | setLastInsertionTime (const ros::Time &time) |
| void | setOutputTime (const ros::Time &time) |
| bool | updateTime (const ros::Time &time) |
| virtual | ~cOctreeBasePaRos () |
| default destructor | |
Public Attributes | |
| cOctreeBasePaRosParameter | rosparams_base_ |
| parameters | |
Protected Member Functions | |
| 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 | |
| void | getOctomapPcdSub (const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const |
| helper function for getOctomapPcd... | |
| void | getParentKeySimple (const OctKey ¤t, const int current_level, OctKey &parent) const |
| helper function for getParentKey | |
Protected Attributes | |
| ros::Time | current_output_time_ |
| internal variable for storing current output time | |
| ros::Time | last_insertion_time_ |
| internal variable for storing last insertion time | |
Definition at line 75 of file octree_base_pa_ros.h.
| typedef ::octomap::OcTreeKey cOctreeBasePaRos< OCTREE >::OctKey |
Definition at line 86 of file octree_base_pa_ros.h.
| typedef pcl::PointCloud<pcl::PointXYZ> cOctreeBasePaRos< OCTREE >::PclPointCloud |
Definition at line 81 of file octree_base_pa_ros.h.
| typedef pcl::PointCloud<pcl::PointXYZ>::ConstPtr cOctreeBasePaRos< OCTREE >::PclPointCloudConstPtr |
Definition at line 84 of file octree_base_pa_ros.h.
| typedef pcl::PointCloud<pcl::PointXYZ>::Ptr cOctreeBasePaRos< OCTREE >::PclPointCloudPtr |
Definition at line 82 of file octree_base_pa_ros.h.
| typedef OCTREE cOctreeBasePaRos< OCTREE >::TreeTypeBase |
Reimplemented in cOctreeStampedNativeRos, cOctreePaRos, and cOctreeStampedPaRos.
Definition at line 78 of file octree_base_pa_ros.h.
| typedef cOctreeBasePaRos<OCTREE> cOctreeBasePaRos< OCTREE >::TreeTypeFull |
Definition at line 79 of file octree_base_pa_ros.h.
| cOctreeBasePaRos< OCTREE >::cOctreeBasePaRos | ( | double | resolution | ) |
default constructor
| virtual cOctreeBasePaRos< OCTREE >::~cOctreeBasePaRos | ( | ) | [virtual] |
default destructor
| 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)
| 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)
| 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)
| 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 !
| virtual void cOctreeBasePaRos< OCTREE >::clear | ( | void | ) | [virtual] |
clear local timestamps with octomap
| 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
| void cOctreeBasePaRos< OCTREE >::getChildKeySimple | ( | const OctKey & | current, |
| const int | current_level, | ||
| OctKey & | child, | ||
| const int | child_pos | ||
| ) | const [protected] |
helper function for getChildKey
| 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.
| octomap_msgs::OctomapPtr cOctreeBasePaRos< OCTREE >::getOctomap | ( | void | ) | const |
function for getting the binary octomap
| octomap_msgs::OctomapPtr cOctreeBasePaRos< OCTREE >::getOctomapFull | ( | void | ) | const |
function for getting the full octomap
| 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
| 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
| void cOctreeBasePaRos< OCTREE >::getOctomapPcdSub | ( | const OctKey & | key, |
| const int | current_level, | ||
| const int | min_level, | ||
| PclPointCloud & | cloud | ||
| ) | const [protected] |
helper function for getOctomapPcd...
| ros::Time cOctreeBasePaRos< OCTREE >::getOutputTime | ( | void | ) | const |
function for returning the time of output messages (instead of this function use updateTime() )
| 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
| void cOctreeBasePaRos< OCTREE >::getParentKeySimple | ( | const OctKey & | current, |
| const int | current_level, | ||
| OctKey & | parent | ||
| ) | const [protected] |
helper function for getParentKey
| geometry_msgs::PointPtr cOctreeBasePaRos< OCTREE >::keyToPoint | ( | const OctKey & | key | ) | const |
function for converting from key to point (geometry_msg)
| void cOctreeBasePaRos< OCTREE >::keyToPoint | ( | const OctKey & | key, |
| double & | x, | ||
| double & | y, | ||
| double & | z | ||
| ) | const |
function for converting from key to real coordinates
| OctKey cOctreeBasePaRos< OCTREE >::pointToKey | ( | const geometry_msgs::Point & | point | ) | const |
functions for converting from point (geometry_msg) to key
| bool cOctreeBasePaRos< OCTREE >::readFull | ( | const std::string & | filename | ) |
trying to read the given file into the current 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.
| void cOctreeBasePaRos< OCTREE >::setOutputTime | ( | const ros::Time & | time | ) |
function for setting the time of output messages (instead of this function use updateTime() )
| 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
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.
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.
| cOctreeBasePaRosParameter cOctreeBasePaRos< OCTREE >::rosparams_base_ |
parameters
Definition at line 165 of file octree_base_pa_ros.h.