footprint_filter.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * FOOTPRINTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef LASER_SCAN_FOOTPRINT_FILTER_H
36 #define LASER_SCAN_FOOTPRINT_FILTER_H
37 
45 #include "filters/filter_base.h"
46 #include "sensor_msgs/LaserScan.h"
47 #include "tf/transform_listener.h"
48 #include "sensor_msgs/PointCloud.h"
49 #include "ros/ros.h"
51 
52 namespace laser_filters
53 {
54 
55 class LaserScanFootprintFilter : public filters::FilterBase<sensor_msgs::LaserScan>
56 {
57 public:
59 
60  bool configure()
61  {
62  if(!getParam("inscribed_radius", inscribed_radius_))
63  {
64  ROS_ERROR("LaserScanFootprintFilter needs inscribed_radius to be set");
65  return false;
66  }
67  return true;
68  }
69 
71  {
72 
73  }
74 
75  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
76  {
77  filtered_scan = input_scan ;
78  sensor_msgs::PointCloud laser_cloud;
79 
80  try{
81  projector_.transformLaserScanToPointCloud("base_link", input_scan, laser_cloud, tf_);
82  }
83  catch(tf::TransformException& ex){
84  if(up_and_running_){
85  ROS_WARN_THROTTLE(1, "Dropping Scan: Transform unavailable %s", ex.what());
86  }
87  else {
88  ROS_INFO_THROTTLE(.3, "Ignoring Scan: Waiting for TF");
89  }
90  return false;
91  }
92 
93  int c_idx = indexChannel(laser_cloud);
94 
95  if (c_idx == -1 || laser_cloud.channels[c_idx].values.size () == 0){
96  ROS_ERROR("We need an index channel to be able to filter out the footprint");
97  return false;
98  }
99 
100  for (unsigned int i=0; i < laser_cloud.points.size(); i++)
101  {
102  if (inFootprint(laser_cloud.points[i])){
103  int index = laser_cloud.channels[c_idx].values[i];
104  filtered_scan.ranges[index] = std::numeric_limits<float>::quiet_NaN();
105  }
106  }
107 
108  up_and_running_ = true;
109  return true;
110  }
111 
112  int indexChannel(const sensor_msgs::PointCloud& scan_cloud){
113  int c_idx = -1;
114  for (unsigned int d = 0; d < scan_cloud.channels.size (); d++)
115  {
116  if (scan_cloud.channels[d].name == "index")
117  {
118  c_idx = d;
119  break;
120  }
121  }
122  return c_idx;
123  }
124 
125  bool inFootprint(const geometry_msgs::Point32& scan_pt){
126  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_)
127  return false;
128  return true;
129  }
130 
131 private:
136 } ;
137 
138 }
139 
140 #endif // LASER_SCAN_FOOTPRINT_FILTER_H
d
laser_geometry::LaserProjection projector_
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
bool getParam(const std::string &name, std::string &value)
bool inFootprint(const geometry_msgs::Point32 &scan_pt)
#define ROS_INFO_THROTTLE(period,...)
#define ROS_WARN_THROTTLE(period,...)
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
int indexChannel(const sensor_msgs::PointCloud &scan_cloud)
#define ROS_ERROR(...)


laser_filters
Author(s): Tully Foote
autogenerated on Wed Jul 3 2019 19:33:47