laser_scan_densifier.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 /*
00017  * Copyright (c) 2011, Ivan Dryanovski, William Morris
00018  * All rights reserved.
00019  *
00020  * Redistribution and use in source and binary forms, with or without
00021  * modification, are permitted provided that the following conditions are met:
00022  *
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 CCNY Robotics Lab nor the names of its
00029  *       contributors may be used to endorse or promote products derived from
00030  *       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 THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00036  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00037  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00038  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00039  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00040  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00041  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00042  * POSSIBILITY OF SUCH DAMAGE.
00043  */
00044 
00045 #include "laser_scan_densifier/laser_scan_densifier.h"
00046 
00047 namespace scan_tools {
00048 
00049 LaserScanDensifier::LaserScanDensifier(ros::NodeHandle nh, ros::NodeHandle nh_private):
00050   nh_(nh), 
00051   nh_private_(nh_private)
00052 {
00053   ROS_INFO ("Starting LaserScanDensifier");
00054 
00055   // **** get paramters
00056 
00057   nh_private_.param("step", step_, 2);
00058   nh_private_.param("mode", mode_, 0);
00059 
00060   ROS_ASSERT_MSG(step_ > 0, "step parameter is set to %, must be > 0", step_);
00061 
00062   switch(mode_) {
00063     case 0: ROS_INFO("LaserScanDensifier started with mode %d: copy data points", mode_);
00064             break;
00065     case 1: ROS_INFO("LaserScanDensifier started with mode %d: interpolate data points", mode_);
00066             break;
00067     default: ROS_WARN("LaserScanDensifier started with unsupported mode %d. Defaulting to mode 0: copy data points", mode_);
00068              mode_ = 0;
00069              break;
00070   }
00071 
00072   // **** advertise topics
00073 
00074   scan_publisher_ = nh_.advertise<sensor_msgs::LaserScan>("scan_dense", 1);
00075 
00076   // **** subscribe to laser scan messages
00077 
00078   scan_subscriber_ = nh_.subscribe("scan", 1, &LaserScanDensifier::scanCallback, this);
00079 }
00080 
00081 LaserScanDensifier::~LaserScanDensifier ()
00082 {
00083   ROS_INFO ("Destroying LaserScanDensifier");
00084 }
00085 
00086 void LaserScanDensifier::scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg)
00087 {
00088   sensor_msgs::LaserScan::Ptr scan_dense;
00089   scan_dense = boost::make_shared<sensor_msgs::LaserScan>();
00090 
00091   // copy over equal fields
00092 
00093   scan_dense->header          = scan_msg->header;
00094   scan_dense->range_min       = scan_msg->range_min;
00095   scan_dense->range_max       = scan_msg->range_max;
00096   scan_dense->angle_min       = scan_msg->angle_min;
00097   scan_dense->angle_max       = scan_msg->angle_max;
00098   scan_dense->angle_increment = scan_msg->angle_increment / step_;
00099   scan_dense->time_increment  = scan_msg->time_increment;
00100   scan_dense->scan_time       = scan_msg->scan_time;
00101 
00102   scan_dense->ranges.clear();
00103   scan_dense->intensities.clear();
00104 
00105   for (size_t i = 0; i < scan_msg->ranges.size()-1; i++)
00106   {
00107     switch (mode_) {
00108       case 0: { //copy data points
00109         scan_dense->ranges.insert(scan_dense->ranges.end(), step_, scan_msg->ranges[i]);
00110         scan_dense->intensities.insert(scan_dense->intensities.end(), step_, scan_msg->intensities[i]);
00111         break;
00112       }
00113       case 1: { //interpolate data points
00114         double delta_range = (scan_msg->ranges[i+1]-scan_msg->ranges[i])/step_;
00115         double delta_intensities = (scan_msg->intensities[i+1]-scan_msg->intensities[i])/step_;
00116         for (int k = 0; k < step_; k++) {
00117           scan_dense->ranges.insert(scan_dense->ranges.end(), 1, scan_msg->ranges[i]+k*delta_range);
00118           scan_dense->intensities.insert(scan_dense->intensities.end(), 1, scan_msg->intensities[i]+k*delta_intensities);
00119         }
00120         break;
00121       }
00122     }
00123   }
00124   // add angle_max data point
00125   scan_dense->ranges.push_back(scan_msg->ranges.back());
00126   scan_dense->intensities.push_back(scan_msg->intensities.back());
00127 
00128   scan_publisher_.publish(scan_dense);
00129 }
00130 
00131 } //namespace scan_tools
00132 


laser_scan_densifier
Author(s): Felix Messmer
autogenerated on Sat Jun 8 2019 21:02:37