Go to the documentation of this file.
49 #ifndef __OCTREE_BASE_PA_ROS_H
50 #define __OCTREE_BASE_PA_ROS_H
59 #include <geometry_msgs/Point.h>
60 #include <sensor_msgs/PointCloud.h>
61 #include <sensor_msgs/PointCloud2.h>
62 #include <sensor_msgs/LaserScan.h>
63 #include <nav_msgs/Path.h>
64 #include <std_srvs/Empty.h>
66 #include <octomap_msgs/Octomap.h>
71 #include <pcl/point_cloud.h>
72 #include <pcl/point_types.h>
74 #include <octomap/octomap.h>
77 template <
typename OCTREE>
86 typedef typename pcl::PointCloud<pcl::PointXYZ>::ConstPtr
89 typedef ::octomap::OcTreeKey
OctKey;
98 virtual void clear(
void);
102 bool addCloud(
const sensor_msgs::PointCloud2 &cloud,
107 bool addCloud(
const sensor_msgs::PointCloud &cloud,
112 bool addCloud(
const sensor_msgs::LaserScan &cloud,
117 octomap_msgs::OctomapPtr
getOctomap(
void)
const;
123 const int tree_depth = 0,
const bool expand =
false)
const;
126 const int tree_depth = 0,
const bool expand =
false)
const;
156 OctKey &child,
const int child_pos)
const;
163 bool readFull(
const std::string& filename);
186 OctKey &child,
const int child_pos)
const;
192 #include "octomap_pa/octree_base_pa_ros.hxx"
194 #endif // __OCTREE_BASE_PA_ROS_H
cOctreeBasePaRos(double resolution)
default constructor
bool addCloud(const sensor_msgs::PointCloud2 &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity())
pcl::PointCloud< pcl::PointXYZ >::Ptr PclPointCloudPtr
bool readFull(const std::string &filename)
trying to read the given file into the current OcTree
virtual ros::Time getLastInsertionTime(void) const
function for returning the time the octomap was last updated
virtual ~cOctreeBasePaRos()
default destructor
void getParentKeySimple(const OctKey ¤t, const int current_level, OctKey &parent) const
helper function for getParentKey
octomap_msgs::OctomapPtr getOctomapFull(void) const
function for getting the full octomap
pcl::PointCloud< pcl::PointXYZ >::ConstPtr PclPointCloudConstPtr
pcl::PointCloud< pcl::PointXYZ > PclPointCloud
void getOctomapPcdSub(const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const
helper function for getOctomapPcd...
virtual void setLastInsertionTime(const ros::Time &time)
virtual void clear(void)
clear local timestamps with octomap
ros::Time current_output_time_
internal variable for storing current output time
sensor_msgs::PointCloud2Ptr getOctomapPcd(const int tree_depth=0, const bool expand=false) const
function for getting the pointcloud equivalent of the octomap
cOctreeBasePaRos< OCTREE > TreeTypeFull
OctKey pointToKey(const geometry_msgs::Point &point) const
functions for converting from point (geometry_msg) to key
::octomap::OcTreeKey OctKey
bool updateTime(const ros::Time &time)
void setOutputTime(const ros::Time &time)
geometry_msgs::PointPtr keyToPoint(const OctKey &key) const
function for converting from key to point (geometry_msg)
ros::Time getOutputTime(void) const
function for returning the time of output messages
void getChildKeySimple(const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const
helper function for getChildKey
bool getChildKey(const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const
octomap_msgs::OctomapPtr getOctomap(void) const
function for getting the binary octomap
ros::Time last_insertion_time_
internal variable for storing last insertion time
sensor_msgs::PointCloud2Ptr getOctomapPcdFree(const int tree_depth=0, const bool expand=false) const
similar to getOctomapPcd, but only returning just empty voxels
bool getParentKey(const OctKey ¤t, const int current_level, OctKey &parent) const
cOctreeBasePaRosParameter rosparams_base_
parameters
octomap_pa
Author(s):
autogenerated on Wed Mar 2 2022 00:46:31