00001 /* 00002 * Copyright (c) 2008 Radu Bogdan Rusu <rusu@cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id: $ 00028 * 00029 */ 00030 00031 #include "laser_filters/array_filter.h" 00032 00033 namespace laser_filters 00034 { 00035 LaserArrayFilter::LaserArrayFilter() : 00036 num_ranges_(1), range_filter_(NULL), intensity_filter_(NULL) 00037 { 00038 00039 }; 00040 00041 bool LaserArrayFilter::configure() 00042 { 00043 00044 bool found_range_config = getParam("range_filter_chain", range_config_); 00045 bool found_intensity_config = getParam("intensity_filter_chain", intensity_config_); 00046 00047 if (!found_range_config && !found_intensity_config) 00048 { 00049 ROS_ERROR("Cannot Configure LaserArrayFilter: Didn't find \"range_filter\" or \"intensity _filter\" tag within LaserArrayFilter params. Filter definitions needed inside for processing range and intensity"); 00050 return false; 00051 } 00052 00053 if (range_filter_) 00054 delete range_filter_; 00055 00056 if (intensity_filter_) 00057 delete intensity_filter_; 00058 00059 if (found_range_config) 00060 { 00061 range_filter_ = new filters::MultiChannelFilterChain<float>("float"); 00062 if (!range_filter_->configure(num_ranges_, range_config_)) 00063 return false; 00064 } 00065 00066 if (found_intensity_config) 00067 { 00068 intensity_filter_ = new filters::MultiChannelFilterChain<float>("float"); 00069 if (!intensity_filter_->configure(num_ranges_, intensity_config_)) 00070 return false; 00071 } 00072 00073 return true; 00074 }; 00075 00076 LaserArrayFilter::~LaserArrayFilter() 00077 { 00078 if (range_filter_) 00079 delete range_filter_; 00080 00081 if (intensity_filter_) 00082 delete intensity_filter_; 00083 }; 00084 00085 bool LaserArrayFilter::update(const sensor_msgs::LaserScan& scan_in, sensor_msgs::LaserScan& scan_out) 00086 { 00087 if (!this->configured_) 00088 { 00089 ROS_ERROR("LaserArrayFilter not configured"); 00090 return false; 00091 } 00092 00093 boost::mutex::scoped_lock lock(data_lock); 00094 scan_out = scan_in; 00095 00096 if (scan_in.ranges.size() != num_ranges_) //Reallocating 00097 { 00098 num_ranges_ = scan_in.ranges.size(); 00099 00100 ROS_INFO("LaserArrayFilter cleaning and reallocating due to larger scan size"); 00101 00102 configure(); 00103 } 00104 00106 range_filter_->update(scan_in.ranges, scan_out.ranges); 00107 intensity_filter_->update(scan_in.intensities, scan_out.intensities); 00108 00109 00110 return true; 00111 } 00112 }