octree_pa_node.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002 *                                                                             *
00003 * octree_pa_node.cpp                                                          *
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 // local headers
00047 #include "octomap_pa/octree_pa_node.h"
00048 
00049 // ros headers
00050 #include <parameter_pa/parameter_pa_ros.h>
00051 
00052 // standard headers
00053 #include <string>
00054 
00055 //**************************[main]*********************************************
00056 int main(int argc, char **argv) {
00057 
00058     ros::init(argc, argv, "octree_pa_node");
00059     cOctreePaNode octomap;
00060 
00061     ros::spin();
00062 
00063     return 0;
00064 }
00065 
00066 //**************************[cOctreePaNode]************************************
00067 cOctreePaNode::cOctreePaNode() :
00068   cOctreePaRos(0.1), tf_listener_(ros::Duration(20), true) {
00069 
00070     cParameterPaRos paramloader;
00071 
00072     paramloader.load("~/output_frame", rosparams_base_.output_frame_);
00073 
00074     // octomap parameter
00075     double temp;
00076     temp = 0.1 ;
00077     paramloader.load("~/map_resolution"    , temp); setResolution      (temp);
00078     temp = 0.5 ;
00079     paramloader.load("~/map_prob_threshold", temp); setOccupancyThres  (temp);
00080     temp = 0.12;
00081     paramloader.load("~/map_clamp_min"     , temp); setClampingThresMin(temp);
00082     temp = 0.97;
00083     paramloader.load("~/map_clamp_max"     , temp); setClampingThresMax(temp);
00084 
00085     // pointcloud insertion parameter
00086     paramloader.load("~/map_prob_hit"      , addparams_.map_prob_hit_      );
00087     paramloader.load("~/map_prob_miss"     , addparams_.map_prob_miss_     );
00088     paramloader.load("~/pcd_voxel_active"  , addparams_.pcd_voxel_active_  );
00089     paramloader.load("~/pcd_voxel_explicit", addparams_.pcd_voxel_explicit_);
00090     paramloader.load("~/pcd_voxel_explicit_relative_resolution",
00091       addparams_.pcd_voxel_explicit_relative_resolution_);
00092     paramloader.load("~/pcd_explicit_transform",
00093       addparams_.pcd_explicit_transform_);
00094 
00095     // topics in
00096     paramloader.loadTopic("~/topic_in_cloud"    ,
00097       nodeparams_.topic_in_cloud_    );
00098     paramloader.loadTopic("~/topic_in_cloud_old",
00099       nodeparams_.topic_in_cloud_old_);
00100     paramloader.loadTopic("~/topic_in_laser"    ,
00101       nodeparams_.topic_in_laser_    );
00102 
00103     // topics out
00104     paramloader.loadTopic("~/topic_out_octomap"       ,
00105       nodeparams_.topic_out_octomap_);
00106     paramloader.loadTopic("~/topic_out_octomap_full"  ,
00107       nodeparams_.topic_out_octomap_full_);
00108     paramloader.loadTopic("~/topic_out_cloud_free"    ,
00109       nodeparams_.topic_out_cloud_free_);
00110     paramloader.loadTopic("~/topic_out_cloud_occupied",
00111       nodeparams_.topic_out_cloud_occupied_);
00112 
00113 
00114     // Subscriber for pointclouds
00115     if (nodeparams_.topic_in_cloud_ != "") {
00116         sub_cloud_ = nh_.subscribe<sensor_msgs::PointCloud2>(
00117           nodeparams_.topic_in_cloud_, 10,
00118           &cOctreePaNode::addPointcloudCallbackSub, this);
00119     }
00120 
00121     // Subscriber for pointclouds (old format)
00122     if (nodeparams_.topic_in_cloud_old_ != "") {
00123         sub_cloud_old_ = nh_.subscribe<sensor_msgs::PointCloud>(
00124           nodeparams_.topic_in_cloud_old_, 10,
00125           &cOctreePaNode::addPointcloudOldCallbackSub, this);
00126     }
00127     // Subscriber for laserscans
00128     if (nodeparams_.topic_in_laser_ != "") {
00129         sub_laser_ = nh_.subscribe<sensor_msgs::LaserScan>(
00130           nodeparams_.topic_in_laser_, 10,
00131           &cOctreePaNode::addLaserCallbackSub, this);
00132     }
00133 
00134 
00135     // puplisher for the octomap (binary data)
00136     pub_octomap_        = nh_.advertise<octomap_msgs::Octomap>(
00137       nodeparams_.topic_out_octomap_, 10, true);
00138     // puplisher for the octomap (full data)
00139     pub_octomap_full_   = nh_.advertise<octomap_msgs::Octomap>(
00140       nodeparams_.topic_out_octomap_full_, 10, true);
00141 
00142     // puplisher for free voxels as pointcloud
00143     pub_cloud_free_     = nh_.advertise<sensor_msgs::PointCloud2>(
00144       nodeparams_.topic_out_cloud_free_, 10, true);
00145     // puplisher for occupied voxels as pointcloud
00146     pub_cloud_occupied_ = nh_.advertise<sensor_msgs::PointCloud2>(
00147       nodeparams_.topic_out_cloud_occupied_, 10, true);
00148 
00149     std::string str_service("~/");
00150     str_service = paramloader.resolveRessourcename(str_service);
00151     // service for clearing the octomap
00152     srv_clear_ = nh_.advertiseService(str_service + "clear",
00153       &cOctreePaNode::clearCallbackSrv, this);
00154     // service for receiving the size of the octomap
00155     srv_getsize_ = nh_.advertiseService(str_service + "getsize",
00156       &cOctreePaNode::getSizeCallbackSrv, this);
00157     // service for saving the octomap
00158     srv_save_ = nh_.advertiseService(str_service + "save",
00159       &cOctreePaNode::saveCallbackSrv, this);
00160     // service for loading a octomap
00161     srv_load_ = nh_.advertiseService(str_service + "load",
00162       &cOctreePaNode::loadCallbackSrv, this);
00163 
00164     // count number of inserted pointclouds
00165     count_cloud_     = 0;
00166     count_cloud_old_ = 0;
00167     count_laser_     = 0;
00168 }
00169 
00170 //**************************[~cOctreePaNode]***********************************
00171 cOctreePaNode::~cOctreePaNode() {
00172 
00173 }
00174 
00175 //**************************[publishOctomap]***********************************
00176 void cOctreePaNode::publishOctomap() {
00177 
00178     if (pub_octomap_.getNumSubscribers() > 0) {
00179         pub_octomap_.publish(getOctomap());
00180     }
00181     if (pub_octomap_full_.getNumSubscribers() > 0) {
00182         pub_octomap_.publish(getOctomapFull());
00183     }
00184 
00185     if (pub_cloud_occupied_.getNumSubscribers() > 0) {
00186         pub_cloud_occupied_.publish(getOctomapPcd());
00187     }
00188     if (pub_cloud_free_.getNumSubscribers() > 0) {
00189         pub_cloud_free_.publish(getOctomapPcdFree());
00190     }
00191 }
00192 
00193 //**************************[addPointcloudCallbackSub]*************************
00194 void cOctreePaNode::addPointcloudCallbackSub(
00195   const sensor_msgs::PointCloud2ConstPtr &msg) {
00196 
00197     if (!updateTime(msg->header.stamp)) {
00198         tf_listener_.clear();
00199         return;
00200     }
00201 
00202     tf::StampedTransform transform;
00203 
00204     try {
00205         tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00206           msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00207         tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00208           msg->header.frame_id, msg->header.stamp, transform);
00209     } catch (tf::TransformException &ex){
00210         ROS_WARN("%s",ex.what());
00211         return;
00212     }
00213 
00214     if (addCloud(msg, addparams_, transform)) {
00215         count_cloud_++;
00216         publishOctomap();
00217     }
00218 }
00219 
00220 //**************************[addPointcloudCallbackSub]*************************
00221 void cOctreePaNode::addPointcloudOldCallbackSub(
00222   const sensor_msgs::PointCloudConstPtr &msg) {
00223 
00224     if (!updateTime(msg->header.stamp)) {
00225         tf_listener_.clear();
00226         return;
00227     }
00228 
00229     tf::StampedTransform transform;
00230 
00231     try {
00232         tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00233           msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00234         tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00235           msg->header.frame_id, msg->header.stamp, transform);
00236     } catch (tf::TransformException &ex){
00237         ROS_WARN("%s",ex.what());
00238         return;
00239     }
00240 
00241     if (addCloud(msg, addparams_, transform)) {
00242         count_cloud_old_++;
00243         publishOctomap();
00244     }
00245 }
00246 
00247 //**************************[addLaserCallbackSub]******************************
00248 void cOctreePaNode::addLaserCallbackSub(
00249   const sensor_msgs::LaserScanConstPtr &msg) {
00250 
00251     if (!updateTime(msg->header.stamp)) {
00252         tf_listener_.clear();
00253         return;
00254     }
00255 
00256     tf::StampedTransform transform;
00257 
00258     try {
00259         tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00260           msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00261         tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00262           msg->header.frame_id, msg->header.stamp, transform);
00263     } catch (tf::TransformException &ex){
00264         ROS_WARN("%s",ex.what());
00265         return;
00266     }
00267 
00268     updateTime(msg->header.stamp);
00269     if (addCloud(msg, addparams_, transform)) {
00270         count_laser_++;
00271         publishOctomap();
00272     }
00273 }
00274 
00275 
00276 //**************************[clearCallbackSrv]*********************************
00277 bool cOctreePaNode::clearCallbackSrv(std_srvs::Empty::Request  &req,
00278   std_srvs::Empty::Response &res) {
00279 
00280     ROS_INFO("cOctreePaNode::clear()");
00281 
00282     count_cloud_     = 0;
00283     count_cloud_old_ = 0;
00284     count_laser_     = 0;
00285 
00286     clear();
00287     tf_listener_.clear();
00288 
00289     return true;
00290 }
00291 
00292 //**************************[getSizeCallbackSrv]*******************************
00293 bool cOctreePaNode::getSizeCallbackSrv (
00294   octomap_pa::OctomapPaGetSize::Request  &req,
00295   octomap_pa::OctomapPaGetSize::Response &res) {
00296 
00297     ROS_INFO("cOctreePaNode::getsize()");
00298 
00299     res.size = size();
00300     res.memoryusage = (int64_t) memoryUsage();
00301 
00302     res.count_cloud     = count_cloud_    ;
00303     res.count_cloud_old = count_cloud_old_;
00304     res.count_laser     = count_laser_    ;
00305 
00306     return true;
00307 }
00308 
00309 //**************************[saveCallbackSrv]**********************************
00310 bool cOctreePaNode::saveCallbackSrv(
00311   octomap_pa::OctomapPaFileName::Request  &req,
00312   octomap_pa::OctomapPaFileName::Response &res) {
00313 
00314     ROS_INFO_STREAM("cOctreePaNode::save(" << req.filename << ")");
00315 
00316     std::string filename;
00317     filename = req.filename;
00318     cParameterPaRos par;
00319     par.replaceFindpack(filename);
00320 
00321     //res.ok = writeBinary(filename);
00322     res.ok = this->write(filename);
00323 
00324     return res.ok;
00325 }
00326 
00327 //**************************[loadCallbackSrv]**********************************
00328 bool cOctreePaNode::loadCallbackSrv(
00329   octomap_pa::OctomapPaFileName::Request  &req,
00330   octomap_pa::OctomapPaFileName::Response &res) {
00331 
00332     ROS_INFO_STREAM("cOctreePaNode::load(" << req.filename << ")");
00333 
00334     std::string filename;
00335     filename = req.filename;
00336     cParameterPaRos par;
00337     par.replaceFindpack(filename);
00338 
00339     // res.ok = readBinary(filename);
00340     res.ok = readFull(filename);
00341 
00342     publishOctomap();
00343     return res.ok;
00344 }


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