octree_base_pa_ros.h
Go to the documentation of this file.
00001 /******************************************************************************
00002 *                                                                             *
00003 * octree_base_pa_ros.h                                                        *
00004 * ====================                                                        *
00005 *                                                                             *
00006 *******************************************************************************
00007 *                                                                             *
00008 * github repository                                                           *
00009 *   https://github.com/TUC-ProAut/ros_octomap                                 *
00010 *                                                                             *
00011 * Chair of Automation Technology, Technische Universität Chemnitz             *
00012 *   https://www.tu-chemnitz.de/etit/proaut                                    *
00013 *                                                                             *
00014 *******************************************************************************
00015 *                                                                             *
00016 * New BSD License                                                             *
00017 *                                                                             *
00018 * Copyright (c) 2015-2018, Peter Weissig, Technische Universität Chemnitz     *
00019 * All rights reserved.                                                        *
00020 *                                                                             *
00021 * Redistribution and use in source and binary forms, with or without          *
00022 * modification, are permitted provided that the following conditions are met: *
00023 *     * Redistributions of source code must retain the above copyright        *
00024 *       notice, this list of conditions and the following disclaimer.         *
00025 *     * Redistributions in binary form must reproduce the above copyright     *
00026 *       notice, this list of conditions and the following disclaimer in the   *
00027 *       documentation and/or other materials provided with the distribution.  *
00028 *     * Neither the name of the Technische Universität Chemnitz nor the       *
00029 *       names of its contributors may be used to endorse or promote products  *
00030 *       derived from this software without specific prior written permission. *
00031 *                                                                             *
00032 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" *
00033 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE   *
00034 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE  *
00035 * ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY      *
00036 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES  *
00037 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR          *
00038 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER  *
00039 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT          *
00040 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY   *
00041 * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
00042 * DAMAGE.                                                                     *
00043 *                                                                             *
00044 ******************************************************************************/
00045 
00046 #ifndef __OCTREE_BASE_PA_ROS_H
00047 #define __OCTREE_BASE_PA_ROS_H
00048 
00049 // local headers
00050 #include "octomap_pa/addcloud_parameter.h"
00051 #include "octomap_pa/octree_base_pa_ros_parameter.h"
00052 
00053 // ros headers
00054 #include <ros/ros.h>
00055 
00056 #include <geometry_msgs/Point.h>
00057 #include <sensor_msgs/PointCloud.h>
00058 #include <sensor_msgs/PointCloud2.h>
00059 #include <sensor_msgs/LaserScan.h>
00060 #include <nav_msgs/Path.h>
00061 #include <std_srvs/Empty.h>
00062 
00063 #include <octomap_msgs/Octomap.h>
00064 
00065 #include <tf/transform_datatypes.h>
00066 
00067 // additional libraries
00068 #include <pcl/point_cloud.h>
00069 #include <pcl/point_types.h>
00070 
00071 #include <octomap/octomap.h>
00072 
00073 //**************************[cOctreeBasePaRos]*********************************
00074 template <typename OCTREE>
00075 class cOctreeBasePaRos : public OCTREE {
00076   public:
00077 
00078     typedef OCTREE                   TreeTypeBase;
00079     typedef cOctreeBasePaRos<OCTREE> TreeTypeFull;
00080 
00081     typedef          pcl::PointCloud<pcl::PointXYZ>      PclPointCloud;
00082     typedef typename pcl::PointCloud<pcl::PointXYZ>::Ptr PclPointCloudPtr;
00083     typedef typename pcl::PointCloud<pcl::PointXYZ>::ConstPtr
00084         PclPointCloudConstPtr;
00085 
00086     typedef ::octomap::OcTreeKey OctKey;
00087 
00089     cOctreeBasePaRos(double resolution);
00090 
00092     virtual ~cOctreeBasePaRos();
00093 
00095     virtual void clear(void);
00096 
00099     bool addCloud(const sensor_msgs::PointCloud2ConstPtr &cloud,
00100       const cAddCloudParameter &params,
00101       const tf::Transform transform = tf::Transform::getIdentity());
00104     bool addCloud(const sensor_msgs::PointCloudConstPtr &cloud,
00105       const cAddCloudParameter &params,
00106       const tf::Transform transform = tf::Transform::getIdentity());
00109     bool addCloud(const sensor_msgs::LaserScanConstPtr &cloud,
00110       const cAddCloudParameter &params,
00111       const tf::Transform transform = tf::Transform::getIdentity());
00112 
00114     octomap_msgs::OctomapPtr getOctomap(void) const;
00116     octomap_msgs::OctomapPtr getOctomapFull(void) const;
00117 
00119     sensor_msgs::PointCloud2Ptr getOctomapPcd(
00120       const int tree_depth = 0, const bool expand = false) const;
00122     sensor_msgs::PointCloud2Ptr getOctomapPcdFree(
00123       const int tree_depth = 0, const bool expand = false) const;
00124 
00128     bool updateTime(const ros::Time &time);
00131     virtual ros::Time getLastInsertionTime(void) const;
00134     virtual void setLastInsertionTime(const ros::Time &time);
00137     ros::Time getOutputTime(void) const;
00140     void setOutputTime(const ros::Time &time);
00141 
00143     OctKey pointToKey(const geometry_msgs::Point &point) const;
00145     geometry_msgs::PointPtr keyToPoint(const OctKey &key) const;
00147     void keyToPoint(const OctKey &key, double &x, double &y, double &z) const;
00148 
00154     bool getChildKey(const OctKey &current, const int current_level,
00155       OctKey &child, const int child_pos) const;
00158     bool getParentKey(const OctKey &current, const int current_level,
00159       OctKey &parent) const;
00160 
00162     bool readFull(const std::string& filename);
00163 
00165     cOctreeBasePaRosParameter rosparams_base_;
00166 
00167   protected:
00169     ros::Time last_insertion_time_;
00171     ros::Time current_output_time_;
00172 
00175     bool addCloud(const PclPointCloudPtr &cloud,
00176       const cAddCloudParameter &params,
00177       const tf::Transform &transform);
00178 
00180     void getOctomapPcdSub(const OctKey &key, const int current_level,
00181       const int min_level, PclPointCloud &cloud) const;
00182 
00184     void getChildKeySimple(const OctKey &current, const int current_level,
00185       OctKey &child, const int child_pos) const;
00187     void getParentKeySimple(const OctKey &current, const int current_level,
00188       OctKey &parent) const;
00189 };
00190 
00191 #include "octomap_pa/octree_base_pa_ros.hxx"
00192 
00193 #endif // __OCTREE_BASE_PA_ROS_H


octomap_pa
Author(s):
autogenerated on Thu Jun 6 2019 17:53:30