v4r_laser_range_filter_node.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002  * Copyright (c) 2014 Markus Bader <markus.bader@tuwien.ac.at>
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 1. Redistributions of source code must retain the above copyright
00008  *    notice, this list of conditions and the following disclaimer.
00009  * 2. Redistributions in binary form must reproduce the above copyright
00010  *    notice, this list of conditions and the following disclaimer in the
00011  *    documentation and/or other materials provided with the distribution.
00012  * 3. All advertising materials mentioning features or use of this software
00013  *    must display the following acknowledgement:
00014  *    This product includes software developed by the TU-Wien.
00015  * 4. Neither the name of the TU-Wien nor the
00016  *    names of its contributors may be used to endorse or promote products
00017  *    derived from this software without specific prior written permission.
00018  * 
00019  * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY
00020  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  ***************************************************************************/
00030 
00031 #include "ros/ros.h"
00032 #include <sensor_msgs/LaserScan.h>
00033 #include <sstream>
00034 
00035 #define MX_LASER_RANGE_FILTER_INF_TO_MAX true
00036 #define MX_LASER_RANGE_FILTER_NAN_TO_MIN false
00037 #define MX_LASER_RANGE_FILTER_MAX_OFFSET -0.01
00038 #define MX_LASER_RANGE_FILTER_MIN_OFFSET 0.01
00039 #define MX_LASER_RANGE_FILTER_MAX  -1
00040 #define MX_LASER_RANGE_FILTER_MIN  -1
00041 
00043 class LaserRangeFilterNode {
00044 public:
00045     LaserRangeFilterNode ( ros::NodeHandle &n )
00046         :n_ ( n ), n_param_ ( "~" ) {
00047         sub_ = n_.subscribe("scan", 1000, &LaserRangeFilterNode::callback, this);
00048         pub_ = n_.advertise<sensor_msgs::LaserScan>("scan_filtered", 1000);
00049         
00050         n_param_.param<bool>("inf2max", inf2max_, MX_LASER_RANGE_FILTER_INF_TO_MAX);
00051         ROS_INFO("%s: max_range: %s", n_param_.getNamespace().c_str(), ((inf2max_) ? "true" : "false"));
00052         n_param_.param<bool>("nan2min", nan2min_, MX_LASER_RANGE_FILTER_NAN_TO_MIN);
00053         ROS_INFO("%s: min_range: %s", n_param_.getNamespace().c_str(), ((nan2min_) ? "true" : "false"));
00054         n_param_.param<double>("max_offset", max_offset_, MX_LASER_RANGE_FILTER_MAX_OFFSET);
00055         ROS_INFO("%s: max_offset: %4.3f", n_param_.getNamespace().c_str(), max_offset_);
00056         n_param_.param<double>("min_offset", min_offset_, MX_LASER_RANGE_FILTER_MIN_OFFSET);
00057         ROS_INFO("%s: min_offset: %4.3f", n_param_.getNamespace().c_str(), min_offset_);
00058         n_param_.param<double>("max", max_, MX_LASER_RANGE_FILTER_MAX);
00059         ROS_INFO("%s: max: %4.3f", n_param_.getNamespace().c_str(), max_);
00060         n_param_.param<double>("min", min_, MX_LASER_RANGE_FILTER_MIN);
00061         ROS_INFO("%s: min: %4.3f", n_param_.getNamespace().c_str(), min_);
00062         
00063     }
00064     void callback (const sensor_msgs::LaserScan::ConstPtr& _msg) {
00065       if(pub_.getNumSubscribers() == 0) return;
00066         sensor_msgs::LaserScan msg = *_msg;
00067         unsigned int nrOfRanges = msg.ranges.size();
00068         unsigned int nrOfIntensities = msg.intensities.size();
00069         for (int i = 0; i < nrOfRanges; i++) {
00070             float &range = msg.ranges[i];
00071             if (nan2min_ && isnan(range)) {
00072               range = msg.range_min + min_offset_;
00073             }
00074             if (inf2max_ && isinf(range)) {
00075                 range = msg.range_max + max_offset_;
00076             }
00077             if ((max_ > 0.) && range > max_) {
00078               range = max_;
00079             }
00080             if ((min_ > 0.) && range < min_) {
00081               range = min_;
00082             }
00083         }        
00084         pub_.publish(msg);
00085     }
00086 private:
00087     ros::Publisher pub_;
00088     ros::Subscriber sub_;
00089 private: // variables
00090     ros::NodeHandle n_;
00091     ros::NodeHandle n_param_;
00092     bool inf2max_;
00093     bool nan2min_;
00094     double max_offset_;
00095     double min_offset_;
00096     double max_;
00097     double min_;
00098 };
00099 
00100 int main(int argc, char **argv) {
00101 
00102     ros::init(argc, argv, "LaserFilter");
00103     ros::NodeHandle n;
00104     LaserRangeFilterNode my_node(n);
00105     ros::spin();
00106     return 0;
00107 }


v4r_laser_filter
Author(s):
autogenerated on Wed Aug 26 2015 16:41:46