octree_base_pa_ros.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * octree_base_pa_ros.h *
4 * ==================== *
5 * *
6 *******************************************************************************
7 * *
8 * github repository *
9 * https://github.com/TUC-ProAut/ros_octomap *
10 * *
11 * Chair of Automation Technology, Technische Universität Chemnitz *
12 * https://www.tu-chemnitz.de/etit/proaut *
13 * *
14 *******************************************************************************
15 * *
16 * New BSD License *
17 * *
18 * Copyright (c) 2015-2020, Peter Weissig, Technische Universität Chemnitz *
19 * All rights reserved. *
20 * *
21 * Redistribution and use in source and binary forms, with or without *
22 * modification, are permitted provided that the following conditions are met: *
23 * * Redistributions of source code must retain the above copyright *
24 * notice, this list of conditions and the following disclaimer. *
25 * * Redistributions in binary form must reproduce the above copyright *
26 * notice, this list of conditions and the following disclaimer in the *
27 * documentation and/or other materials provided with the distribution. *
28 * * Neither the name of the Technische Universität Chemnitz nor the *
29 * names of its contributors may be used to endorse or promote products *
30 * derived from this software without specific prior written permission. *
31 * *
32 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" *
33 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
34 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
35 * ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY *
36 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
37 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR *
38 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
39 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
40 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY *
41 * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
42 * DAMAGE. *
43 * *
44 ******************************************************************************/
45 
46 #ifndef __OCTREE_BASE_PA_ROS_H
47 #define __OCTREE_BASE_PA_ROS_H
48 
49 // local headers
52 
53 // ros headers
54 #include <ros/ros.h>
55 
56 #include <geometry_msgs/Point.h>
57 #include <sensor_msgs/PointCloud.h>
58 #include <sensor_msgs/PointCloud2.h>
59 #include <sensor_msgs/LaserScan.h>
60 #include <nav_msgs/Path.h>
61 #include <std_srvs/Empty.h>
62 
63 #include <octomap_msgs/Octomap.h>
64 
65 #include <tf/transform_datatypes.h>
66 
67 // additional libraries
68 #include <pcl/point_cloud.h>
69 #include <pcl/point_types.h>
70 
71 #include <octomap/octomap.h>
72 
73 //**************************[cOctreeBasePaRos]*********************************
74 template <typename OCTREE>
75 class cOctreeBasePaRos : public OCTREE {
76  public:
77 
78  typedef OCTREE TreeTypeBase;
80 
81  typedef pcl::PointCloud<pcl::PointXYZ> PclPointCloud;
82  typedef typename pcl::PointCloud<pcl::PointXYZ>::Ptr PclPointCloudPtr;
83  typedef typename pcl::PointCloud<pcl::PointXYZ>::ConstPtr
85 
86  typedef ::octomap::OcTreeKey OctKey;
87 
89  cOctreeBasePaRos(double resolution);
90 
92  virtual ~cOctreeBasePaRos();
93 
95  virtual void clear(void);
96 
99  bool addCloud(const sensor_msgs::PointCloud2ConstPtr &cloud,
100  const cAddCloudParameter &params,
101  const tf::Transform transform = tf::Transform::getIdentity());
104  bool addCloud(const sensor_msgs::PointCloudConstPtr &cloud,
105  const cAddCloudParameter &params,
106  const tf::Transform transform = tf::Transform::getIdentity());
109  bool addCloud(const sensor_msgs::LaserScanConstPtr &cloud,
110  const cAddCloudParameter &params,
111  const tf::Transform transform = tf::Transform::getIdentity());
112 
114  octomap_msgs::OctomapPtr getOctomap(void) const;
116  octomap_msgs::OctomapPtr getOctomapFull(void) const;
117 
119  sensor_msgs::PointCloud2Ptr getOctomapPcd(
120  const int tree_depth = 0, const bool expand = false) const;
122  sensor_msgs::PointCloud2Ptr getOctomapPcdFree(
123  const int tree_depth = 0, const bool expand = false) const;
124 
128  bool updateTime(const ros::Time &time);
131  virtual ros::Time getLastInsertionTime(void) const;
134  virtual void setLastInsertionTime(const ros::Time &time);
137  ros::Time getOutputTime(void) const;
140  void setOutputTime(const ros::Time &time);
141 
143  OctKey pointToKey(const geometry_msgs::Point &point) const;
145  geometry_msgs::PointPtr keyToPoint(const OctKey &key) const;
147  void keyToPoint(const OctKey &key, double &x, double &y, double &z) const;
148 
154  bool getChildKey(const OctKey &current, const int current_level,
155  OctKey &child, const int child_pos) const;
158  bool getParentKey(const OctKey &current, const int current_level,
159  OctKey &parent) const;
160 
162  bool readFull(const std::string& filename);
163 
166 
167  protected:
172 
175  bool addCloud(const PclPointCloudPtr &cloud,
176  const cAddCloudParameter &params,
177  const tf::Transform &transform);
178 
180  void getOctomapPcdSub(const OctKey &key, const int current_level,
181  const int min_level, PclPointCloud &cloud) const;
182 
184  void getChildKeySimple(const OctKey &current, const int current_level,
185  OctKey &child, const int child_pos) const;
187  void getParentKeySimple(const OctKey &current, const int current_level,
188  OctKey &parent) const;
189 };
190 
191 #include "octomap_pa/octree_base_pa_ros.hxx"
192 
193 #endif // __OCTREE_BASE_PA_ROS_H
sensor_msgs::PointCloud2Ptr getOctomapPcdFree(const int tree_depth=0, const bool expand=false) const
similar to getOctomapPcd, but only returning just empty voxels
void getParentKeySimple(const OctKey &current, const int current_level, OctKey &parent) const
helper function for getParentKey
octomap_msgs::OctomapPtr getOctomapFull(void) const
function for getting the full octomap
virtual void clear(void)
clear local timestamps with octomap
OctKey pointToKey(const geometry_msgs::Point &point) const
functions for converting from point (geometry_msg) to key
::octomap::OcTreeKey OctKey
bool getParentKey(const OctKey &current, const int current_level, OctKey &parent) const
bool updateTime(const ros::Time &time)
cOctreeBasePaRos< OCTREE > TreeTypeFull
void getOctomapPcdSub(const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const
helper function for getOctomapPcd...
ros::Time getOutputTime(void) const
octomap_msgs::OctomapPtr getOctomap(void) const
function for getting the binary octomap
void setOutputTime(const ros::Time &time)
virtual ros::Time getLastInsertionTime(void) const
ros::Time last_insertion_time_
internal variable for storing last insertion time
bool addCloud(const sensor_msgs::PointCloud2ConstPtr &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
pcl::PointCloud< pcl::PointXYZ >::Ptr PclPointCloudPtr
cOctreeBasePaRos(double resolution)
default constructor
cOctreeBasePaRosParameter rosparams_base_
parameters
sensor_msgs::PointCloud2Ptr getOctomapPcd(const int tree_depth=0, const bool expand=false) const
function for getting the pointcloud equivalent of the octomap
virtual ~cOctreeBasePaRos()
default destructor
bool getChildKey(const OctKey &current, const int current_level, OctKey &child, const int child_pos) const
geometry_msgs::PointPtr keyToPoint(const OctKey &key) const
function for converting from key to point (geometry_msg)
bool readFull(const std::string &filename)
trying to read the given file into the current OcTree
static const Transform & getIdentity()
pcl::PointCloud< pcl::PointXYZ >::ConstPtr PclPointCloudConstPtr
pcl::PointCloud< pcl::PointXYZ > PclPointCloud
void getChildKeySimple(const OctKey &current, const int current_level, OctKey &child, const int child_pos) const
helper function for getChildKey
ros::Time current_output_time_
internal variable for storing current output time
virtual void setLastInsertionTime(const ros::Time &time)


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