|
| 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...
|
|
|
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...
|
|
Definition at line 64 of file octree_stamped_native_ros.h.