point_cloud_footprint_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 *  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 
00044 #include "laser_geometry/laser_geometry.h"
00045 #include "filters/filter_base.h"
00046 #include "tf/transform_listener.h"
00047 #include "sensor_msgs/PointCloud.h"
00048 #include "ros/ros.h"
00049 
00050 namespace laser_filters
00051 {
00052 
00053 class PointCloudFootprintFilter : public filters::FilterBase<sensor_msgs::PointCloud>
00054 {
00055 public:
00056   PointCloudFootprintFilter() {
00057     ROS_WARN("PointCloudFootprintFilter has been deprecated.  Please use PR2PointCloudFootprintFilter instead.\n");
00058   }
00059 
00060   bool configure()
00061   {
00062     if(!getParam("inscribed_radius", inscribed_radius_))
00063     {
00064       ROS_ERROR("PointCloudFootprintFilter needs inscribed_radius to be set");
00065       return false;
00066     }
00067     return true;
00068   }
00069 
00070   virtual ~PointCloudFootprintFilter()
00071   { 
00072 
00073   }
00074 
00075   bool update(const sensor_msgs::PointCloud& input_scan, sensor_msgs::PointCloud& filtered_scan)
00076   {
00077     if(&input_scan == &filtered_scan){
00078       ROS_ERROR("This filter does not currently support in place copying");
00079       return false;
00080     }
00081     sensor_msgs::PointCloud laser_cloud;
00082 
00083     try{
00084       tf_.transformPointCloud("base_link", input_scan, laser_cloud);
00085     }
00086     catch(tf::TransformException& ex){
00087       ROS_ERROR("Transform unavailable %s", ex.what());
00088       return false;
00089     }
00090 
00091     filtered_scan.header = input_scan.header;
00092     filtered_scan.points.resize (input_scan.points.size());
00093     filtered_scan.channels.resize (input_scan.channels.size());
00094     for (unsigned int d = 0; d < input_scan.channels.size (); d++){
00095       filtered_scan.channels[d].values.resize  (input_scan.points.size());
00096       filtered_scan.channels[d].name = input_scan.channels[d].name;
00097     }
00098 
00099     int num_pts = 0;
00100     for (unsigned int i=0; i < laser_cloud.points.size(); i++)  
00101     {
00102       if (!inFootprint(laser_cloud.points[i])){
00103         filtered_scan.points[num_pts] = input_scan.points[i];
00104         for (unsigned int d = 0; d < filtered_scan.channels.size (); d++)
00105           filtered_scan.channels[d].values[num_pts] = input_scan.channels[d].values[i];
00106         num_pts++;
00107       }
00108     }
00109 
00110     // Resize output vectors
00111     filtered_scan.points.resize (num_pts);
00112     for (unsigned int d = 0; d < filtered_scan.channels.size (); d++)
00113       filtered_scan.channels[d].values.resize (num_pts);
00114 
00115     return true;
00116   }
00117 
00118 
00119   bool inFootprint(const geometry_msgs::Point32& scan_pt){
00120     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_)
00121       return false;
00122     return true;
00123   }
00124 
00125 private:
00126   tf::TransformListener tf_;
00127   laser_geometry::LaserProjection projector_;
00128   double inscribed_radius_;
00129 } ;
00130 
00131 }
00132 
00133 #endif // LASER_SCAN_FOOTPRINT_FILTER_H


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