range_filter.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2013, JSK (The University of Tokyo).
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef LASER_SCAN_RANGE_FILTER_H
00036 #define LASER_SCAN_RANGE_FILTER_H
00037 
00043 #include "filters/filter_base.h"
00044 #include "sensor_msgs/LaserScan.h"
00045 
00046 namespace laser_filters
00047 {
00048 
00049 class LaserScanRangeFilter : public filters::FilterBase<sensor_msgs::LaserScan>
00050 {
00051 public:
00052 
00053   double lower_threshold_ ;
00054   double upper_threshold_ ;
00055   bool use_message_range_limits_ ;
00056   float lower_replacement_value_ ;
00057   float upper_replacement_value_ ;
00058 
00059   bool configure()
00060   {
00061     use_message_range_limits_ = false;
00062     getParam("use_message_range_limits", use_message_range_limits_);
00063 
00064     // work around the not implemented getParam(std::string name, float& value) method
00065     double temp_replacement_value = std::numeric_limits<double>::quiet_NaN();
00066     getParam("lower_replacement_value", temp_replacement_value);
00067     lower_replacement_value_ = static_cast<float>(temp_replacement_value);
00068 
00069     // work around the not implemented getParam(std::string name, float& value) method
00070     temp_replacement_value = std::numeric_limits<double>::quiet_NaN();
00071     getParam("upper_replacement_value", temp_replacement_value);
00072     upper_replacement_value_ = static_cast<float>(temp_replacement_value);
00073 
00074 
00075     lower_threshold_ = 0.0;
00076     upper_threshold_ = 100000.0;
00077     getParam("lower_threshold", lower_threshold_);
00078     getParam("upper_threshold", upper_threshold_) ;
00079     return true;
00080   }
00081 
00082   virtual ~LaserScanRangeFilter()
00083   {
00084 
00085   }
00086 
00087   bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
00088   {
00089     if (use_message_range_limits_)
00090     {
00091       lower_threshold_ = input_scan.range_min;
00092       upper_threshold_ = input_scan.range_max;
00093     }
00094     filtered_scan = input_scan;
00095     for (unsigned int i=0;
00096          i < input_scan.ranges.size();
00097          i++) // Need to check ever reading in the current scan
00098     {
00099 
00100       if (filtered_scan.ranges[i] <= lower_threshold_)
00101       {
00102         filtered_scan.ranges[i] = lower_replacement_value_;
00103 
00104       }
00105       else if (filtered_scan.ranges[i] >= upper_threshold_)
00106       {
00107         filtered_scan.ranges[i] = upper_replacement_value_;
00108       }
00109     }
00110 
00111     return true;
00112   }
00113 } ;
00114 
00115 }
00116 
00117 #endif // LASER_SCAN_RANGE_FILTER_H


laser_filters
Author(s): Tully Foote
autogenerated on Sat Sep 9 2017 02:57:38