interpolation_filter.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
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 INTERPOLATION_FILTER_H
00036 #define INTERPOLATION_FILTER_H
00037 
00044 #include "filters/filter_base.h"
00045 #include "sensor_msgs/LaserScan.h"
00046 
00047 namespace laser_filters
00048 {
00049 
00050 class InterpolationFilter : public filters::FilterBase<sensor_msgs::LaserScan>
00051 {
00052 public:
00053 
00054   bool configure()
00055   {
00056     return true;
00057   }
00058 
00059   virtual ~InterpolationFilter()
00060   { 
00061   }
00062 
00063   bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
00064   {
00065     double previous_valid_range = input_scan.range_max - .01;
00066     double next_valid_range = input_scan.range_max - .01;
00067     filtered_scan= input_scan;
00068 
00069     unsigned int i = 0;
00070     while(i < input_scan.ranges.size()) // Need to check every reading in the current scan
00071     {
00072       //check if the reading is out of range for some reason
00073       if (filtered_scan.ranges[i] <= input_scan.range_min ||
00074           filtered_scan.ranges[i] >= input_scan.range_max){
00075 
00076         //we need to find the next valid range reading
00077         unsigned int j = i + 1;
00078         unsigned int start_index = i;
00079         unsigned int end_index = i;
00080         while(j < input_scan.ranges.size()){
00081           if (filtered_scan.ranges[j] <= input_scan.range_min || 
00082               filtered_scan.ranges[j] >= input_scan.range_max){                                                                                 
00083             end_index = j;
00084           }
00085           else{
00086             next_valid_range = filtered_scan.ranges[j];
00087             break;
00088           }
00089           ++j;
00090         }
00091 
00092         //for now, we'll just take the average between the two valid range readings
00093         double average_range = (previous_valid_range + next_valid_range) / 2.0;
00094 
00095         for(unsigned int k = start_index; k <= end_index; k++){
00096           filtered_scan.ranges[k] = average_range;
00097         }
00098 
00099         //make sure to update our previous valid range reading
00100         previous_valid_range = next_valid_range;
00101         i = j + 1;
00102       }
00103       else{
00104         previous_valid_range = filtered_scan.ranges[i];
00105         ++i;
00106       }
00107 
00108     }
00109     return true;
00110   }
00111 };
00112 
00113 }
00114 
00115 #endif // LASER_SCAN_INTENSITY_FILTER_H


laser_filters
Author(s): Tully Foote
autogenerated on Fri Jan 3 2014 11:27:39