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 * 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 * Author: *
15 * Peter Weissig *
16 * *
17 *******************************************************************************
18 * *
19 * New BSD License *
20 * *
21 * Copyright (c) 2015-2021 TU Chemnitz *
22 * All rights reserved. *
23 * *
24 * Redistribution and use in source and binary forms, with or without *
25 * modification, are permitted provided that the following conditions are met: *
26 * * Redistributions of source code must retain the above copyright notice, *
27 * this list of conditions and the following disclaimer. *
28 * * Redistributions in binary form must reproduce the above copyright *
29 * notice, this list of conditions and the following disclaimer in the *
30 * documentation and/or other materials provided with the distribution. *
31 * * Neither the name of the copyright holder nor the names of its *
32 * contributors may be used to endorse or promote products derived from *
33 * this software without specific prior written permission. *
34 * *
35 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
36 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED *
37 * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR *
38 * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR *
39 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, *
40 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, *
41 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
42 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, *
43 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR *
44 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF *
45 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
46 * *
47 ******************************************************************************/
48 
49 #ifndef __OCTREE_BASE_PA_ROS_H
50 #define __OCTREE_BASE_PA_ROS_H
51 
52 // local headers
55 
56 // ros headers
57 #include <ros/ros.h>
58 
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>
65 
66 #include <octomap_msgs/Octomap.h>
67 
68 #include <tf/transform_datatypes.h>
69 
70 // additional libraries
71 #include <pcl/point_cloud.h>
72 #include <pcl/point_types.h>
73 
74 #include <octomap/octomap.h>
75 
76 //**************************[cOctreeBasePaRos]*********************************
77 template <typename OCTREE>
78 class cOctreeBasePaRos : public OCTREE {
79  public:
80 
81  typedef OCTREE TreeTypeBase;
83 
84  typedef pcl::PointCloud<pcl::PointXYZ> PclPointCloud;
85  typedef typename pcl::PointCloud<pcl::PointXYZ>::Ptr PclPointCloudPtr;
86  typedef typename pcl::PointCloud<pcl::PointXYZ>::ConstPtr
88 
89  typedef ::octomap::OcTreeKey OctKey;
90 
92  cOctreeBasePaRos(double resolution);
93 
95  virtual ~cOctreeBasePaRos();
96 
98  virtual void clear(void);
99 
102  bool addCloud(const sensor_msgs::PointCloud2 &cloud,
103  const cAddCloudParameter &params,
104  const tf::Transform transform = tf::Transform::getIdentity());
107  bool addCloud(const sensor_msgs::PointCloud &cloud,
108  const cAddCloudParameter &params,
109  const tf::Transform transform = tf::Transform::getIdentity());
112  bool addCloud(const sensor_msgs::LaserScan &cloud,
113  const cAddCloudParameter &params,
114  const tf::Transform transform = tf::Transform::getIdentity());
115 
117  octomap_msgs::OctomapPtr getOctomap(void) const;
119  octomap_msgs::OctomapPtr getOctomapFull(void) const;
120 
122  sensor_msgs::PointCloud2Ptr getOctomapPcd(
123  const int tree_depth = 0, const bool expand = false) const;
125  sensor_msgs::PointCloud2Ptr getOctomapPcdFree(
126  const int tree_depth = 0, const bool expand = false) const;
127 
131  bool updateTime(const ros::Time &time);
133  virtual ros::Time getLastInsertionTime(void) const;
136  virtual void setLastInsertionTime(const ros::Time &time);
138  ros::Time getOutputTime(void) const;
141  void setOutputTime(const ros::Time &time);
142 
144  OctKey pointToKey(const geometry_msgs::Point &point) const;
146  geometry_msgs::PointPtr keyToPoint(const OctKey &key) const;
148  void keyToPoint(const OctKey &key, double &x, double &y, double &z) const;
149 
155  bool getChildKey(const OctKey &current, const int current_level,
156  OctKey &child, const int child_pos) const;
159  bool getParentKey(const OctKey &current, const int current_level,
160  OctKey &parent) const;
161 
163  bool readFull(const std::string& filename);
164 
167 
168  protected:
173 
176  bool addCloud(const PclPointCloudPtr &cloud,
177  const cAddCloudParameter &params,
178  const tf::Transform &transform);
179 
181  void getOctomapPcdSub(const OctKey &key, const int current_level,
182  const int min_level, PclPointCloud &cloud) const;
183 
185  void getChildKeySimple(const OctKey &current, const int current_level,
186  OctKey &child, const int child_pos) const;
188  void getParentKeySimple(const OctKey &current, const int current_level,
189  OctKey &parent) const;
190 };
191 
192 #include "octomap_pa/octree_base_pa_ros.hxx"
193 
194 #endif // __OCTREE_BASE_PA_ROS_H
cOctreeBasePaRos::cOctreeBasePaRos
cOctreeBasePaRos(double resolution)
default constructor
cOctreeBasePaRos::addCloud
bool addCloud(const sensor_msgs::PointCloud2 &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
cOctreeBasePaRos::PclPointCloudPtr
pcl::PointCloud< pcl::PointXYZ >::Ptr PclPointCloudPtr
Definition: octree_base_pa_ros.h:131
addcloud_parameter.h
ros.h
cOctreeBasePaRos::readFull
bool readFull(const std::string &filename)
trying to read the given file into the current OcTree
cOctreeBasePaRos::getLastInsertionTime
virtual ros::Time getLastInsertionTime(void) const
function for returning the time the octomap was last updated
cOctreeBasePaRos::~cOctreeBasePaRos
virtual ~cOctreeBasePaRos()
default destructor
cOctreeBasePaRos::getParentKeySimple
void getParentKeySimple(const OctKey &current, const int current_level, OctKey &parent) const
helper function for getParentKey
cOctreeBasePaRos
Definition: octree_base_pa_ros.h:78
cOctreeBasePaRos::getOctomapFull
octomap_msgs::OctomapPtr getOctomapFull(void) const
function for getting the full octomap
cOctreeBasePaRos::PclPointCloudConstPtr
pcl::PointCloud< pcl::PointXYZ >::ConstPtr PclPointCloudConstPtr
Definition: octree_base_pa_ros.h:133
cOctreeBasePaRos::PclPointCloud
pcl::PointCloud< pcl::PointXYZ > PclPointCloud
Definition: octree_base_pa_ros.h:130
cOctreeBasePaRos::getOctomapPcdSub
void getOctomapPcdSub(const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const
helper function for getOctomapPcd...
cOctreeBasePaRos::setLastInsertionTime
virtual void setLastInsertionTime(const ros::Time &time)
tf::Transform::getIdentity
static const Transform & getIdentity()
cOctreeBasePaRosParameter
Definition: octree_base_pa_ros_parameter.h:59
octree_base_pa_ros_parameter.h
cOctreeBasePaRos::clear
virtual void clear(void)
clear local timestamps with octomap
cOctreeBasePaRos::current_output_time_
ros::Time current_output_time_
internal variable for storing current output time
Definition: octree_base_pa_ros.h:218
cOctreeBasePaRos::getOctomapPcd
sensor_msgs::PointCloud2Ptr getOctomapPcd(const int tree_depth=0, const bool expand=false) const
function for getting the pointcloud equivalent of the octomap
tf::Transform
cOctreeBasePaRos::TreeTypeFull
cOctreeBasePaRos< OCTREE > TreeTypeFull
Definition: octree_base_pa_ros.h:128
cOctreeBasePaRos::TreeTypeBase
OCTREE TreeTypeBase
Definition: octree_base_pa_ros.h:127
cOctreeBasePaRos::pointToKey
OctKey pointToKey(const geometry_msgs::Point &point) const
functions for converting from point (geometry_msg) to key
cOctreeBasePaRos::OctKey
::octomap::OcTreeKey OctKey
Definition: octree_base_pa_ros.h:135
cOctreeBasePaRos::updateTime
bool updateTime(const ros::Time &time)
transform_datatypes.h
ros::Time
cOctreeBasePaRos::setOutputTime
void setOutputTime(const ros::Time &time)
cAddCloudParameter
Definition: addcloud_parameter.h:53
cOctreeBasePaRos::keyToPoint
geometry_msgs::PointPtr keyToPoint(const OctKey &key) const
function for converting from key to point (geometry_msg)
cOctreeBasePaRos::getOutputTime
ros::Time getOutputTime(void) const
function for returning the time of output messages
cOctreeBasePaRos::getChildKeySimple
void getChildKeySimple(const OctKey &current, const int current_level, OctKey &child, const int child_pos) const
helper function for getChildKey
cOctreeBasePaRos::getChildKey
bool getChildKey(const OctKey &current, const int current_level, OctKey &child, const int child_pos) const
cOctreeBasePaRos::getOctomap
octomap_msgs::OctomapPtr getOctomap(void) const
function for getting the binary octomap
cOctreeBasePaRos::last_insertion_time_
ros::Time last_insertion_time_
internal variable for storing last insertion time
Definition: octree_base_pa_ros.h:216
cOctreeBasePaRos::getOctomapPcdFree
sensor_msgs::PointCloud2Ptr getOctomapPcdFree(const int tree_depth=0, const bool expand=false) const
similar to getOctomapPcd, but only returning just empty voxels
cOctreeBasePaRos::getParentKey
bool getParentKey(const OctKey &current, const int current_level, OctKey &parent) const
cOctreeBasePaRos::rosparams_base_
cOctreeBasePaRosParameter rosparams_base_
parameters
Definition: octree_base_pa_ros.h:212


octomap_pa
Author(s):
autogenerated on Wed Mar 2 2022 00:46:31