scan_to_cloud_filter_chain.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008 Radu Bogdan Rusu <rusu@cs.tum.edu>
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  *
27  * $Id: scan_shadows_filter.cpp,v 1.0 2008/12/04 12:00:00 rusu Exp $
28  *
29  */
30 
31 /*
32 \author Radu Bogdan Rusu <rusu@cs.tum.edu>
33 
34 
35  */
36 
37 #include <ros/ros.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/LaserScan.h>
40 
41 #include <float.h>
42 
43 // Laser projection
45 
46 // TF
47 #include <tf/transform_listener.h>
48 #include "tf/message_filter.h"
50 
51 //Filters
52 #include "filters/filter_chain.h"
53 
57 {
58 public:
59 
60  // ROS related
61  laser_geometry::LaserProjection projector_; // Used to project laser scans
62 
63  double laser_max_range_; // Used in laser scan projection
64  int window_;
65 
66  bool high_fidelity_; // High fidelity (interpolating time across scan)
67  std::string target_frame_; // Target frame for high fidelity result
68  std::string scan_topic_, cloud_topic_;
69 
72 
73  // TF
75 
78 
79  double tf_tolerance_;
83 
84  // Timer for displaying deprecation warnings
96 
98  ScanToCloudFilterChain () : laser_max_range_ (DBL_MAX), private_nh("~"), filter_(tf_, "", 50),
99  cloud_filter_chain_("sensor_msgs::PointCloud2"), scan_filter_chain_("sensor_msgs::LaserScan")
100  {
101  private_nh.param("high_fidelity", high_fidelity_, false);
102  private_nh.param("notifier_tolerance", tf_tolerance_, 0.03);
103  private_nh.param("target_frame", target_frame_, std::string ("base_link"));
104 
105  // DEPRECATED with default value
106  using_default_target_frame_deprecated_ = !private_nh.hasParam("target_frame");
107 
108  // DEPRECATED
109  using_scan_topic_deprecated_ = private_nh.hasParam("scan_topic");
110  using_cloud_topic_deprecated_ = private_nh.hasParam("cloud_topic");
111  using_laser_max_range_deprecated_ = private_nh.hasParam("laser_max_range");
112  using_filter_window_deprecated_ = private_nh.hasParam("filter_window");
113  using_cloud_filters_deprecated_ = private_nh.hasParam("cloud_filters/filter_chain");
114  using_scan_filters_deprecated_ = private_nh.hasParam("scan_filters/filter_chain");
115  using_cloud_filters_wrong_deprecated_ = private_nh.hasParam("cloud_filters/cloud_filter_chain");
116  using_scan_filters_wrong_deprecated_ = private_nh.hasParam("scan_filters/scan_filter_chain");
117 
118 
119  private_nh.param("filter_window", window_, 2);
120  private_nh.param("laser_max_range", laser_max_range_, DBL_MAX);
121  private_nh.param("scan_topic", scan_topic_, std::string("tilt_scan"));
122  private_nh.param("cloud_topic", cloud_topic_, std::string("tilt_laser_cloud_filtered"));
123  private_nh.param("incident_angle_correction", incident_angle_correction_, true);
124 
125  filter_.setTargetFrame(target_frame_);
126  filter_.registerCallback(boost::bind(&ScanToCloudFilterChain::scanCallback, this, _1));
127  filter_.setTolerance(ros::Duration(tf_tolerance_));
128 
129  if (using_scan_topic_deprecated_)
130  sub_.subscribe(nh, scan_topic_, 50);
131  else
132  sub_.subscribe(nh, "scan", 50);
133 
134  filter_.connectInput(sub_);
135 
136  if (using_cloud_topic_deprecated_)
137  cloud_pub_ = nh.advertise<sensor_msgs::PointCloud2> (cloud_topic_, 10);
138  else
139  cloud_pub_ = nh.advertise<sensor_msgs::PointCloud2> ("cloud_filtered", 10);
140 
141  std::string cloud_filter_xml;
142 
143  if (using_cloud_filters_deprecated_)
144  cloud_filter_chain_.configure("cloud_filters/filter_chain", private_nh);
145  else if (using_cloud_filters_wrong_deprecated_)
146  cloud_filter_chain_.configure("cloud_filters/cloud_filter_chain", private_nh);
147  else
148  cloud_filter_chain_.configure("cloud_filter_chain", private_nh);
149 
150  if (using_scan_filters_deprecated_)
151  scan_filter_chain_.configure("scan_filter/filter_chain", private_nh);
152  else if (using_scan_filters_wrong_deprecated_)
153  scan_filter_chain_.configure("scan_filters/scan_filter_chain", private_nh);
154  else
155  scan_filter_chain_.configure("scan_filter_chain", private_nh);
156 
157  deprecation_timer_ = nh.createTimer(ros::Duration(5.0), boost::bind(&ScanToCloudFilterChain::deprecation_warn, this, _1));
158  }
159 
160  // We use a deprecation warning on a timer to avoid warnings getting lost in the noise
162  {
163  if (using_scan_topic_deprecated_)
164  ROS_WARN("Use of '~scan_topic' parameter in scan_to_cloud_filter_chain has been deprecated.");
165 
166  if (using_cloud_topic_deprecated_)
167  ROS_WARN("Use of '~cloud_topic' parameter in scan_to_cloud_filter_chain has been deprecated.");
168 
169  if (using_laser_max_range_deprecated_)
170  ROS_WARN("Use of '~laser_max_range' parameter in scan_to_cloud_filter_chain has been deprecated.");
171 
172  if (using_filter_window_deprecated_)
173  ROS_WARN("Use of '~filter_window' parameter in scan_to_cloud_filter_chain has been deprecated.");
174 
175  if (using_default_target_frame_deprecated_)
176  ROS_WARN("Use of default '~target_frame' parameter in scan_to_cloud_filter_chain has been deprecated. Default currently set to 'base_link' please set explicitly as appropriate.");
177 
178  if (using_cloud_filters_deprecated_)
179  ROS_WARN("Use of '~cloud_filters/filter_chain' parameter in scan_to_cloud_filter_chain has been deprecated. Replace with '~cloud_filter_chain'");
180 
181  if (using_scan_filters_deprecated_)
182  ROS_WARN("Use of '~scan_filters/filter_chain' parameter in scan_to_cloud_filter_chain has been deprecated. Replace with '~scan_filter_chain'");
183 
184  if (using_cloud_filters_wrong_deprecated_)
185  ROS_WARN("Use of '~cloud_filters/cloud_filter_chain' parameter in scan_to_cloud_filter_chain is incorrect. Please Replace with '~cloud_filter_chain'");
186 
187  if (using_scan_filters_wrong_deprecated_)
188  ROS_WARN("Use of '~scan_filters/scan_filter_chain' parameter in scan_to_scan_filter_chain is incorrect. Please Replace with '~scan_filter_chain'");
189 
190  }
191 
192 
194  void
195  scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
196  {
197  // sensor_msgs::LaserScan scan_msg = *scan_in;
198 
199  sensor_msgs::LaserScan filtered_scan;
200  scan_filter_chain_.update (*scan_msg, filtered_scan);
201 
202  // Project laser into point cloud
203  sensor_msgs::PointCloud2 scan_cloud;
204 
205  //\TODO CLEAN UP HACK
206  // This is a trial at correcting for incident angles. It makes many assumptions that do not generalise
207  if(incident_angle_correction_)
208  {
209  for (unsigned int i = 0; i < filtered_scan.ranges.size(); i++)
210  {
211  double angle = filtered_scan.angle_min + i * filtered_scan.angle_increment;
212  filtered_scan.ranges[i] = filtered_scan.ranges[i] + 0.03 * exp(-fabs(sin(angle)));
213  }
214  }
215 
216  // Transform into a PointCloud message
221 
222  if (high_fidelity_)
223  {
224  try
225  {
226  projector_.transformLaserScanToPointCloud (target_frame_, filtered_scan, scan_cloud, tf_, laser_max_range_, mask);
227  }
228  catch (tf::TransformException &ex)
229  {
230  ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s", target_frame_.c_str (), ex.what ());
231  return;
232  //projector_.projectLaser (filtered_scan, scan_cloud, laser_max_range_, preservative_, mask);
233  }
234  }
235  else
236  {
237  projector_.transformLaserScanToPointCloud(target_frame_, filtered_scan, scan_cloud, tf_, laser_max_range_, mask);
238  }
239 
240  sensor_msgs::PointCloud2 filtered_cloud;
241  cloud_filter_chain_.update (scan_cloud, filtered_cloud);
242 
243  cloud_pub_.publish(filtered_cloud);
244  }
245 
246 } ;
247 
248 
249 
250 int
251 main (int argc, char** argv)
252 {
253  ros::init (argc, argv, "scan_to_cloud_filter_chain");
256 
257  ros::spin();
258 
259  return (0);
260 }
261 
262 
void connectInput(F &f)
tf::MessageFilter< sensor_msgs::LaserScan > filter_
void publish(const boost::shared_ptr< M > &message) const
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
#define ROS_WARN(...)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
filters::FilterChain< sensor_msgs::LaserScan > scan_filter_chain_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void deprecation_warn(const ros::TimerEvent &e)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
filters::FilterChain< sensor_msgs::PointCloud2 > cloud_filter_chain_
message_filters::Subscriber< sensor_msgs::LaserScan > sub_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool update(const T &data_in, T &data_out)
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
void setTargetFrame(const std::string &target_frame)
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)
bool hasParam(const std::string &key) const
laser_geometry::LaserProjection projector_
void setTolerance(const ros::Duration &tolerance)
int main(int argc, char **argv)
Connection registerCallback(const C &callback)


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