pr2_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 PR2_POINT_CLOUD_FOOTPRINT_FILTER_H
36 #define PR2_POINT_CLOUD_FOOTPRINT_FILTER_H
37 
45 #include "filters/filter_base.h"
46 #include "tf/transform_listener.h"
47 #include "ros/ros.h"
48 #include <pcl_ros/point_cloud.h>
49 #include <pcl/point_types.h>
50 #include <pcl_ros/transforms.h>
51 #include <sensor_msgs/PointCloud2.h>
52 
54 {
55 
56 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
57 
58 class PR2PointCloudFootprintFilterNew : public filters::FilterBase<sensor_msgs::PointCloud2>
59 {
60 public:
62 
63  bool configure()
64  {
65  if(!getParam("inscribed_radius", inscribed_radius_))
66  {
67  ROS_ERROR("PR2PointCloudPointCloudFootprintFilter needs inscribed_radius to be set");
68  return false;
69  }
70  return true;
71  }
72 
74  {
75 
76  }
77 
78  bool update(const sensor_msgs::PointCloud2& input_scan2, sensor_msgs::PointCloud2& filtered_scan2)
79  {
80  if(&input_scan2 == &filtered_scan2){
81  ROS_ERROR("This filter does not currently support in place copying");
82  return false;
83  }
84 
85  PointCloud input_scan, filtered_scan, laser_cloud;
86  pcl::fromROSMsg(input_scan2, input_scan);
87 
88  try{
89  std_msgs::Header header;
90  header = pcl_conversions::fromPCL(input_scan.header);
91  tf_.waitForTransform(input_scan.header.frame_id, "base_link", header.stamp, ros::Duration(0.2));
92  pcl_ros::transformPointCloud("base_link", input_scan, laser_cloud, tf_);
93  }
94  catch(tf::TransformException& ex){
95  ROS_ERROR("Transform unavailable %s", ex.what());
96  return false;
97  }
98 
99  filtered_scan.header = input_scan.header;
100  filtered_scan.points.resize (input_scan.points.size());
101 
102  int num_pts = 0;
103  for (unsigned int i=0; i < laser_cloud.points.size(); i++)
104  {
105  if (!inFootprint(laser_cloud.points[i])){
106  filtered_scan.points[num_pts] = input_scan.points[i];
107  num_pts++;
108  }
109  }
110 
111  // Resize output vectors
112  filtered_scan.points.resize (num_pts);
113  pcl::toROSMsg(filtered_scan, filtered_scan2);
114 
115  return true;
116  }
117 
118 
119  bool inFootprint(const pcl::PointXYZ& 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 // PR2_POINT_CLOUD_FOOTPRINT_FILTER_H
bool update(const sensor_msgs::PointCloud2 &input_scan2, sensor_msgs::PointCloud2 &filtered_scan2)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool getParam(const std::string &name, std::string &value)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
pcl::PointCloud< pcl::PointXYZ > PointCloud
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
#define ROS_ERROR(...)


pr2_navigation_perception
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 10 2019 14:29:08