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 * FOOTPRINTAL, 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_FOOTPRINT_FILTER_H 00036 #define LASER_SCAN_FOOTPRINT_FILTER_H 00037 00045 #include "filters/filter_base.h" 00046 #include "sensor_msgs/LaserScan.h" 00047 #include "tf/transform_listener.h" 00048 #include "sensor_msgs/PointCloud.h" 00049 #include "ros/ros.h" 00050 #include "laser_geometry/laser_geometry.h" 00051 00052 namespace laser_filters 00053 { 00054 00055 class LaserScanFootprintFilter : public filters::FilterBase<sensor_msgs::LaserScan> 00056 { 00057 public: 00058 LaserScanFootprintFilter(): up_and_running_(false) {} 00059 00060 bool configure() 00061 { 00062 if(!getParam("inscribed_radius", inscribed_radius_)) 00063 { 00064 ROS_ERROR("LaserScanFootprintFilter needs inscribed_radius to be set"); 00065 return false; 00066 } 00067 return true; 00068 } 00069 00070 virtual ~LaserScanFootprintFilter() 00071 { 00072 00073 } 00074 00075 bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan) 00076 { 00077 filtered_scan = input_scan ; 00078 sensor_msgs::PointCloud laser_cloud; 00079 00080 try{ 00081 projector_.transformLaserScanToPointCloud("base_link", input_scan, laser_cloud, tf_); 00082 } 00083 catch(tf::TransformException& ex){ 00084 if(up_and_running_){ 00085 ROS_WARN_THROTTLE(1, "Dropping Scan: Transform unavailable %s", ex.what()); 00086 } 00087 else { 00088 ROS_INFO_THROTTLE(.3, "Ignoring Scan: Waiting for TF"); 00089 } 00090 return false; 00091 } 00092 00093 int c_idx = indexChannel(laser_cloud); 00094 00095 if (c_idx == -1 || laser_cloud.channels[c_idx].values.size () == 0){ 00096 ROS_ERROR("We need an index channel to be able to filter out the footprint"); 00097 return false; 00098 } 00099 00100 for (unsigned int i=0; i < laser_cloud.points.size(); i++) 00101 { 00102 if (inFootprint(laser_cloud.points[i])){ 00103 int index = laser_cloud.channels[c_idx].values[i]; 00104 filtered_scan.ranges[index] = std::numeric_limits<float>::quiet_NaN(); 00105 } 00106 } 00107 00108 up_and_running_ = true; 00109 return true; 00110 } 00111 00112 int indexChannel(const sensor_msgs::PointCloud& scan_cloud){ 00113 int c_idx = -1; 00114 for (unsigned int d = 0; d < scan_cloud.channels.size (); d++) 00115 { 00116 if (scan_cloud.channels[d].name == "index") 00117 { 00118 c_idx = d; 00119 break; 00120 } 00121 } 00122 return c_idx; 00123 } 00124 00125 bool inFootprint(const geometry_msgs::Point32& scan_pt){ 00126 if(scan_pt.x < -1.0 * inscribed_radius_ || scan_pt.x > inscribed_radius_ || scan_pt.y < -1.0 * inscribed_radius_ || scan_pt.y > inscribed_radius_) 00127 return false; 00128 return true; 00129 } 00130 00131 private: 00132 tf::TransformListener tf_; 00133 laser_geometry::LaserProjection projector_; 00134 double inscribed_radius_; 00135 bool up_and_running_; 00136 } ; 00137 00138 } 00139 00140 #endif // LASER_SCAN_FOOTPRINT_FILTER_H