#include <octree_stamped_native_ros.h>
Public Types | |
typedef cOctreeBasePaRos< OcTreeStamped > | TreeTypeBase |
![]() | |
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... | |
![]() | |
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 |
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 ¤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 Attributes | |
cOctreeStampedPaRosParameter | rosparams_ |
parameters More... | |
![]() | |
cOctreeBasePaRosParameter | rosparams_base_ |
parameters More... | |
Protected Member Functions | |
void | checkDegrading (void) |
helper function for automatic degrading More... | |
![]() | |
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_ |
![]() | |
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... | |
Definition at line 64 of file octree_stamped_native_ros.h.
typedef cOctreeBasePaRos<OcTreeStamped> cOctreeStampedNativeRos::TreeTypeBase |
Definition at line 113 of file octree_stamped_native_ros.h.
cOctreeStampedNativeRos::cOctreeStampedNativeRos | ( | const double | resolution | ) |
default constructor
Definition at line 58 of file octree_stamped_native_ros.cpp.
|
virtual |
default destructor
Definition at line 64 of file octree_stamped_native_ros.cpp.
|
protected |
helper function for automatic degrading
Definition at line 75 of file octree_stamped_native_ros.cpp.
void cOctreeStampedNativeRos::degradeOutdatedNodes | ( | void | ) |
degrading outdated nodes
Definition at line 68 of file octree_stamped_native_ros.cpp.
|
protected |
Definition at line 128 of file octree_stamped_native_ros.h.
cOctreeStampedPaRosParameter cOctreeStampedNativeRos::rosparams_ |
parameters
Definition at line 125 of file octree_stamped_native_ros.h.