point_cloud_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 "tf/transform_listener.h"
47 #include "sensor_msgs/PointCloud.h"
48 #include "ros/ros.h"
49 
50 namespace laser_filters
51 {
52 
53 class PointCloudFootprintFilter : public filters::FilterBase<sensor_msgs::PointCloud>
54 {
55 public:
57  ROS_WARN("PointCloudFootprintFilter has been deprecated. Please use PR2PointCloudFootprintFilter instead.\n");
58  }
59 
60  bool configure()
61  {
62  if(!getParam("inscribed_radius", inscribed_radius_))
63  {
64  ROS_ERROR("PointCloudFootprintFilter 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::PointCloud& input_scan, sensor_msgs::PointCloud& filtered_scan)
76  {
77  if(&input_scan == &filtered_scan){
78  ROS_ERROR("This filter does not currently support in place copying");
79  return false;
80  }
81  sensor_msgs::PointCloud laser_cloud;
82 
83  try{
84  tf_.transformPointCloud("base_link", input_scan, laser_cloud);
85  }
86  catch(tf::TransformException& ex){
87  ROS_ERROR("Transform unavailable %s", ex.what());
88  return false;
89  }
90 
91  filtered_scan.header = input_scan.header;
92  filtered_scan.points.resize (input_scan.points.size());
93  filtered_scan.channels.resize (input_scan.channels.size());
94  for (unsigned int d = 0; d < input_scan.channels.size (); d++){
95  filtered_scan.channels[d].values.resize (input_scan.points.size());
96  filtered_scan.channels[d].name = input_scan.channels[d].name;
97  }
98 
99  int num_pts = 0;
100  for (unsigned int i=0; i < laser_cloud.points.size(); i++)
101  {
102  if (!inFootprint(laser_cloud.points[i])){
103  filtered_scan.points[num_pts] = input_scan.points[i];
104  for (unsigned int d = 0; d < filtered_scan.channels.size (); d++)
105  filtered_scan.channels[d].values[num_pts] = input_scan.channels[d].values[i];
106  num_pts++;
107  }
108  }
109 
110  // Resize output vectors
111  filtered_scan.points.resize (num_pts);
112  for (unsigned int d = 0; d < filtered_scan.channels.size (); d++)
113  filtered_scan.channels[d].values.resize (num_pts);
114 
115  return true;
116  }
117 
118 
119  bool inFootprint(const geometry_msgs::Point32& scan_pt){
120  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_)
121  return false;
122  return true;
123  }
124 
125 private:
129 } ;
130 
131 }
132 
133 #endif // LASER_SCAN_FOOTPRINT_FILTER_H
d
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
bool inFootprint(const geometry_msgs::Point32 &scan_pt)
#define ROS_WARN(...)
bool update(const sensor_msgs::PointCloud &input_scan, sensor_msgs::PointCloud &filtered_scan)
bool getParam(const std::string &name, std::string &value)
void transformPointCloud(const std::string &target_frame, const sensor_msgs::PointCloud &pcin, sensor_msgs::PointCloud &pcout) const
#define ROS_ERROR(...)


laser_filters
Author(s): Tully Foote
autogenerated on Tue Mar 17 2020 03:40:02