scan_to_scan_filter_chain.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 
31 #include "ros/ros.h"
32 #include "sensor_msgs/LaserScan.h"
34 #include "tf/message_filter.h"
35 #include "tf/transform_listener.h"
36 #include <filters/filter_chain.hpp>
37 
38 #if BUILDING_NODELET
39 #include <nodelet/nodelet.h>
41 #endif
42 
44 {
45 protected:
46  // Our NodeHandle
49 
50  // Components for tf::MessageFilter
55 
56  // Filter Chain
58 
59  // Components for publishing
60  sensor_msgs::LaserScan msg_;
62 
63  // Deprecation helpers
66 
67 public:
68  // Constructor
69  ScanToScanFilterChain(const ros::NodeHandle& nh = {}, const ros::NodeHandle& pnh = {"~"}) :
70  nh_(nh),
71  private_nh_(pnh),
72  tf_(nullptr),
73  scan_sub_(nh_, "scan", 50),
74  tf_filter_(nullptr),
75  filter_chain_("sensor_msgs::LaserScan")
76  {
77  // Configure filter chain
78 
80 
82  filter_chain_.configure("filter_chain", private_nh_);
83  else
84  filter_chain_.configure("scan_filter_chain", private_nh_);
85 
86  std::string tf_message_filter_target_frame;
87 
88  if (private_nh_.hasParam("tf_message_filter_target_frame"))
89  {
90  private_nh_.getParam("tf_message_filter_target_frame", tf_message_filter_target_frame);
91 
92  private_nh_.param("tf_message_filter_tolerance", tf_filter_tolerance_, 0.03);
93 
94  tf_ = new tf::TransformListener();
96  tf_filter_->setTargetFrame(tf_message_filter_target_frame);
98 
99  // Setup tf::MessageFilter generates callback
100  tf_filter_->registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, boost::placeholders::_1));
101  }
102  else
103  {
104  // Pass through if no tf_message_filter_target_frame
105  scan_sub_.registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, boost::placeholders::_1));
106  }
107 
108  // Advertise output
109  output_pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan_filtered", 1000);
110 
111  // Set up deprecation printout
112  deprecation_timer_ = nh_.createTimer(ros::Duration(5.0), boost::bind(&ScanToScanFilterChain::deprecation_warn, this, boost::placeholders::_1));
113  }
114 
115  // Destructor
117  {
118  if (tf_filter_)
119  delete tf_filter_;
120  if (tf_)
121  delete tf_;
122  }
123 
124  // Deprecation warning callback
126  {
128  ROS_WARN("Use of '~filter_chain' parameter in scan_to_scan_filter_chain has been deprecated. Please replace with '~scan_filter_chain'.");
129  }
130 
131  // Callback
132  void callback(const sensor_msgs::LaserScan::ConstPtr& msg_in)
133  {
134  // Run the filter chain
135  if (filter_chain_.update(*msg_in, msg_))
136  {
137  //only publish result if filter succeeded
139  } else {
140  ROS_ERROR_THROTTLE(1, "Filtering the scan from time %i.%i failed.", msg_in->header.stamp.sec, msg_in->header.stamp.nsec);
141  }
142  }
143 };
144 
145 #if BUILDING_NODELET
146 
147 class ScanToScanFilterChainNodelet : public nodelet::Nodelet
148 {
149  std::unique_ptr<ScanToScanFilterChain> chain_;
150 
151  void onInit() override {
152  chain_ = std::unique_ptr<ScanToScanFilterChain>(new ScanToScanFilterChain(getNodeHandle(), getPrivateNodeHandle()));
153  }
154 };
155 
156 PLUGINLIB_EXPORT_CLASS(ScanToScanFilterChainNodelet, nodelet::Nodelet)
157 
158 #else
159 
160 int main(int argc, char **argv)
161 {
162  ros::init(argc, argv, "scan_to_scan_filter_chain");
163 
165  ros::spin();
166 
167  return 0;
168 }
169 
170 #endif
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
ScanToScanFilterChain::filter_chain_
filters::FilterChain< sensor_msgs::LaserScan > filter_chain_
Definition: scan_to_scan_filter_chain.cpp:57
ScanToScanFilterChain
Definition: scan_to_scan_filter_chain.cpp:43
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ScanToScanFilterChain::private_nh_
ros::NodeHandle private_nh_
Definition: scan_to_scan_filter_chain.cpp:48
tf::MessageFilter::setTolerance
void setTolerance(const ros::Duration &tolerance)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ScanToScanFilterChain::tf_filter_tolerance_
double tf_filter_tolerance_
Definition: scan_to_scan_filter_chain.cpp:54
main
int main(int argc, char **argv)
Definition: scan_to_scan_filter_chain.cpp:160
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
filters::FilterChain::configure
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
ScanToScanFilterChain::deprecation_timer_
ros::Timer deprecation_timer_
Definition: scan_to_scan_filter_chain.cpp:64
message_filters::Subscriber< sensor_msgs::LaserScan >
nodelet::Nodelet::onInit
virtual void onInit()=0
filters::FilterChain< sensor_msgs::LaserScan >
ScanToScanFilterChain::nh_
ros::NodeHandle nh_
Definition: scan_to_scan_filter_chain.cpp:47
ScanToScanFilterChain::using_filter_chain_deprecated_
bool using_filter_chain_deprecated_
Definition: scan_to_scan_filter_chain.cpp:65
ScanToScanFilterChain::~ScanToScanFilterChain
~ScanToScanFilterChain()
Definition: scan_to_scan_filter_chain.cpp:116
filters::FilterChain::update
bool update(const T &data_in, T &data_out)
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
message_filter.h
subscriber.h
ScanToScanFilterChain::output_pub_
ros::Publisher output_pub_
Definition: scan_to_scan_filter_chain.cpp:61
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
ScanToScanFilterChain::ScanToScanFilterChain
ScanToScanFilterChain(const ros::NodeHandle &nh={}, const ros::NodeHandle &pnh={"~"})
Definition: scan_to_scan_filter_chain.cpp:69
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const boost::function< void(P)> &callback)
ros::TimerEvent
ScanToScanFilterChain::deprecation_warn
void deprecation_warn(const ros::TimerEvent &e)
Definition: scan_to_scan_filter_chain.cpp:125
ScanToScanFilterChain::tf_filter_
tf::MessageFilter< sensor_msgs::LaserScan > * tf_filter_
Definition: scan_to_scan_filter_chain.cpp:53
transform_listener.h
nodelet::Nodelet
tf::MessageFilter::setTargetFrame
void setTargetFrame(const std::string &target_frame)
nodelet.h
tf::MessageFilter< sensor_msgs::LaserScan >
ScanToScanFilterChain::scan_sub_
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
Definition: scan_to_scan_filter_chain.cpp:52
ScanToScanFilterChain::msg_
sensor_msgs::LaserScan msg_
Definition: scan_to_scan_filter_chain.cpp:60
class_list_macros.hpp
tf::TransformListener
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
ScanToScanFilterChain::tf_
tf::TransformListener * tf_
Definition: scan_to_scan_filter_chain.cpp:51
filter_chain.hpp
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ScanToScanFilterChain::callback
void callback(const sensor_msgs::LaserScan::ConstPtr &msg_in)
Definition: scan_to_scan_filter_chain.cpp:132
t
geometry_msgs::TransformStamped t
ros::NodeHandle


laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57