tf_web_republisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Copyright (c) 2014, Willow Garage, Inc.
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
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of the Willow Garage nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32 
33  * Author: Julius Kammerl (jkammerl@willowgarage.com)
34  *
35  */
36 
37 #include <sstream>
38 
39 #include <ros/ros.h>
41 
42 #include <boost/thread/mutex.hpp>
43 #include "boost/thread.hpp"
44 
45 #include <tf/tfMessage.h>
46 #include <tf/transform_datatypes.h>
47 #include <geometry_msgs/TransformStamped.h>
48 
50 #include <tf2_web_republisher/TFSubscriptionAction.h>
51 
52 #include <tf2_web_republisher/RepublishTFs.h>
53 #include <tf2_web_republisher/TFArray.h>
54 
55 #include "tf_pair.h"
56 
58 {
59 protected:
62 
63  typedef tf2_web_republisher::RepublishTFs::Request Request;
64  typedef tf2_web_republisher::RepublishTFs::Response Response;
65 
68 
69  TFTransformServer as_;
71 
72  // base struct that holds information about the TFs
73  // a client (either Service or Action) has subscribed to
74  struct ClientInfo
75  {
76  std::vector<TFPair> tf_subscriptions_;
77  unsigned int client_ID_;
79  };
80 
81  // struct for Action client info
83  {
84  GoalHandle handle;
85  };
86 
87  // struct for Service client info
89  {
93  };
94 
95  std::list<boost::shared_ptr<ClientGoalInfo> > active_goals_;
96  boost::mutex goals_mutex_;
97 
98  std::list<boost::shared_ptr<ClientRequestInfo> > active_requests_;
99  boost::mutex requests_mutex_;
100 
101  // tf2 buffer and transformer
102 #if ROS_VERSION_MINOR < 10
103  tf2::Buffer tf_buffer_;
104  tf2::TransformListener tf_listener_;
105 #else
108 #endif
109  boost::mutex tf_buffer_mutex_;
110 
111  unsigned int client_ID_count_;
112 
113 public:
114 
115  TFRepublisher(const std::string& name) :
116  nh_(),
117  as_(nh_,
118  name,
119  boost::bind(&TFRepublisher::goalCB, this, _1),
120  boost::bind(&TFRepublisher::cancelCB, this, _1),
121  false),
122  priv_nh_("~"),
123  tf_buffer_(),
124  tf_listener_(tf_buffer_),
125  client_ID_count_(0)
126  {
127  tf_republish_service_ = nh_.advertiseService("republish_tfs",
129  this);
130  as_.start();
131  }
132 
134 
135 
136 
137  void cancelCB(GoalHandle gh)
138  {
139  boost::mutex::scoped_lock l(goals_mutex_);
140 
141  ROS_DEBUG("GoalHandle canceled");
142 
143  // search for goal handle and remove it from active_goals_ list
144  for(std::list<boost::shared_ptr<ClientGoalInfo> >::iterator it = active_goals_.begin(); it != active_goals_.end();)
145  {
146  ClientGoalInfo& info = **it;
147  if(info.handle == gh)
148  {
149  it = active_goals_.erase(it);
150  info.timer_.stop();
151  info.handle.setCanceled();
152  return;
153  }
154  else
155  ++it;
156  }
157  }
158 
159  const std::string cleanTfFrame( const std::string frame_id ) const
160  {
161  if ( frame_id[0] == '/' )
162  {
163  return frame_id.substr(1);
164  }
165  return frame_id;
166  }
167 
173  const std::vector<std::string>& source_frames,
174  const std::string& target_frame_,
175  float angular_thres,
176  float trans_thres) const
177  {
178  std::size_t request_size_ = source_frames.size();
179  info->tf_subscriptions_.resize(request_size_);
180 
181  for (std::size_t i=0; i<request_size_; ++i )
182  {
183  TFPair& tf_pair = info->tf_subscriptions_[i];
184 
185  std::string source_frame = cleanTfFrame(source_frames[i]);
186  std::string target_frame = cleanTfFrame(target_frame_);
187 
188  tf_pair.setSourceFrame(source_frame);
189  tf_pair.setTargetFrame(target_frame);
190  tf_pair.setAngularThres(angular_thres);
191  tf_pair.setTransThres(trans_thres);
192  }
193  }
194 
195  void goalCB(GoalHandle gh)
196  {
197  ROS_DEBUG("GoalHandle request received");
198 
199  // accept new goals
200  gh.setAccepted();
201 
202  // get goal from handle
203  const tf2_web_republisher::TFSubscriptionGoal::ConstPtr& goal = gh.getGoal();
204 
205  // generate goal_info struct
206  boost::shared_ptr<ClientGoalInfo> goal_info = boost::make_shared<ClientGoalInfo>();
207  goal_info->handle = gh;
208  goal_info->client_ID_ = client_ID_count_++;
209 
210  // add the tf_subscriptions to the ClientGoalInfo object
211  setSubscriptions(goal_info,
212  goal->source_frames,
213  goal->target_frame,
214  goal->angular_thres,
215  goal->trans_thres);
216 
217  goal_info->timer_ = nh_.createTimer(ros::Duration(1.0 / goal->rate),
218  boost::bind(&TFRepublisher::processGoal, this, goal_info, _1));
219 
220  {
221  boost::mutex::scoped_lock l(goals_mutex_);
222  // add new goal to list of active goals/clients
223  active_goals_.push_back(goal_info);
224  }
225 
226  }
227 
228  bool requestCB(Request& req, Response& res)
229  {
230  ROS_DEBUG("RepublishTF service request received");
231  // generate request_info struct
232  boost::shared_ptr<ClientRequestInfo> request_info = boost::make_shared<ClientRequestInfo>();
233 
234  request_info->client_ID_ = client_ID_count_;
235  std::stringstream topicname;
236  topicname << "tf_repub_" << client_ID_count_++;
237 
238  request_info->pub_ = priv_nh_.advertise<tf2_web_republisher::TFArray>(topicname.str(), 10, true);
239 
240  // add the tf_subscriptions to the ClientGoalInfo object
241  setSubscriptions(request_info,
242  req.source_frames,
243  req.target_frame,
244  req.angular_thres,
245  req.trans_thres);
246 
247  request_info->unsub_timeout_ = req.timeout;
248  request_info->unsub_timer_ = nh_.createTimer(request_info->unsub_timeout_,
249  boost::bind(&TFRepublisher::unadvertiseCB, this, request_info, _1),
250  true); // only fire once
251 
252  request_info->timer_ = nh_.createTimer(ros::Duration(1.0 / req.rate),
253  boost::bind(&TFRepublisher::processRequest, this, request_info, _1));
254 
255  {
256  boost::mutex::scoped_lock l(requests_mutex_);
257  // add new request to list of active requests
258  active_requests_.push_back(request_info);
259  }
260  res.topic_name = request_info->pub_.getTopic();
261  ROS_INFO_STREAM("Publishing requested TFs on topic " << res.topic_name);
262 
263  return true;
264  }
265 
267  {
268  ROS_INFO_STREAM("No subscribers on tf topic for request "
269  << request_info->client_ID_
270  << " for " << request_info->unsub_timeout_.toSec()
271  << " seconds. Unadvertising topic:"
272  << request_info->pub_.getTopic());
273  request_info->pub_.shutdown();
274  request_info->unsub_timer_.stop();
275  request_info->timer_.stop();
276 
277  // search for ClientRequestInfo struct and remove it from active_requests_ list
278  for(std::list<boost::shared_ptr<ClientRequestInfo> >::iterator it = active_requests_.begin(); it != active_requests_.end(); ++it)
279  {
280  ClientRequestInfo& info = **it;
281  if(info.pub_ == request_info->pub_)
282  {
283  active_requests_.erase(it);
284  return;
285  }
286  }
287  }
288 
289  void updateSubscriptions(std::vector<TFPair>& tf_subscriptions,
290  std::vector<geometry_msgs::TransformStamped>& transforms)
291  {
292  // iterate over tf_subscription vector
293  std::vector<TFPair>::iterator it ;
294  std::vector<TFPair>::const_iterator end = tf_subscriptions.end();
295 
296  for (it=tf_subscriptions.begin(); it!=end; ++it)
297  {
298  geometry_msgs::TransformStamped transform;
299 
300  try
301  {
302  // protecting tf_buffer
303  boost::mutex::scoped_lock lock (tf_buffer_mutex_);
304 
305  // lookup transformation for tf_pair
306  transform = tf_buffer_.lookupTransform(it->getTargetFrame(),
307  it->getSourceFrame(),
308  ros::Time(0));
309 
310  // If the transform broke earlier, but worked now (we didn't get
311  // booted into the catch block), tell the user all is well again
312  if (!it->is_okay)
313  {
314  it->is_okay = true;
315  ROS_INFO_STREAM("Transform from "
316  << it->getSourceFrame()
317  << " to "
318  << it->getTargetFrame()
319  << " is working again at time "
320  << transform.header.stamp.toSec());
321  }
322  // update tf_pair with transformtion
323  it->updateTransform(transform);
324  }
325  catch (tf2::TransformException ex)
326  {
327  // Only log an error if the transform was okay before
328  if (it->is_okay)
329  {
330  it->is_okay = false;
331  ROS_ERROR("%s", ex.what());
332  }
333  }
334 
335  // check angular and translational thresholds
336  if (it->updateNeeded())
337  {
338  transform.header.stamp = ros::Time::now();
339  transform.header.frame_id = it->getTargetFrame();
340  transform.child_frame_id = it->getSourceFrame();
341 
342  // notify tf_subscription that a network transmission has been triggered
343  it->transmissionTriggered();
344 
345  // add transform to the array
346  transforms.push_back(transform);
347  }
348  }
349  }
350 
352  {
353  tf2_web_republisher::TFSubscriptionFeedback feedback;
354 
355  updateSubscriptions(goal_info->tf_subscriptions_,
356  feedback.transforms);
357 
358  if (feedback.transforms.size() > 0)
359  {
360  // publish feedback
361  goal_info->handle.publishFeedback(feedback);
362  ROS_DEBUG("Client %d: TF feedback published:", goal_info->client_ID_);
363  } else
364  {
365  ROS_DEBUG("Client %d: No TF frame update needed:", goal_info->client_ID_);
366  }
367  }
368 
370  {
371  if (request_info->pub_.getNumSubscribers() == 0)
372  {
373  request_info->unsub_timer_.start();
374  }
375  else
376  {
377  request_info->unsub_timer_.stop();
378  }
379 
380  tf2_web_republisher::TFArray array_msg;
381  updateSubscriptions(request_info->tf_subscriptions_,
382  array_msg.transforms);
383 
384  if (array_msg.transforms.size() > 0)
385  {
386  // publish TFs
387  request_info->pub_.publish(array_msg);
388  ROS_DEBUG("Request %d: TFs published:", request_info->client_ID_);
389  }
390  else
391  {
392  ROS_DEBUG("Request %d: No TF frame update needed:", request_info->client_ID_);
393  }
394  }
395 };
396 
397 int main(int argc, char **argv)
398 {
399  ros::init(argc, argv, "tf2_web_republisher");
400 
401  TFRepublisher tf2_web_republisher(ros::this_node::getName());
402  ros::spin();
403 
404  return 0;
405 }
unsigned int client_ID_count_
TFTransformServer::GoalHandle GoalHandle
void goalCB(GoalHandle gh)
int main(int argc, char **argv)
boost::shared_ptr< const Goal > getGoal() const
void setTargetFrame(const std::string &target_frame)
Definition: tf_pair.h:84
boost::mutex goals_mutex_
void setSourceFrame(const std::string &source_frame)
Definition: tf_pair.h:73
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Definition: tf_pair.h:42
void stop()
TFTransformServer as_
bool requestCB(Request &req, Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
void setSubscriptions(boost::shared_ptr< ClientInfo > info, const std::vector< std::string > &source_frames, const std::string &target_frame_, float angular_thres, float trans_thres) const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
tf2::TransformListener tf_listener_
boost::mutex requests_mutex_
tf2::Buffer tf_buffer_
tf2_web_republisher::RepublishTFs::Request Request
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ros::NodeHandle priv_nh_
void setAccepted(const std::string &text=std::string(""))
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void unadvertiseCB(boost::shared_ptr< ClientRequestInfo > request_info, const ros::TimerEvent &)
TFRepublisher(const std::string &name)
void processRequest(boost::shared_ptr< ClientRequestInfo > request_info, const ros::TimerEvent &)
const std::string cleanTfFrame(const std::string frame_id) const
void processGoal(boost::shared_ptr< ClientGoalInfo > goal_info, const ros::TimerEvent &)
std::list< boost::shared_ptr< ClientGoalInfo > > active_goals_
boost::mutex tf_buffer_mutex_
void setTransThres(float trans_thres)
Definition: tf_pair.h:106
void updateSubscriptions(std::vector< TFPair > &tf_subscriptions, std::vector< geometry_msgs::TransformStamped > &transforms)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
void setAngularThres(float angular_thres)
Definition: tf_pair.h:95
ros::NodeHandle nh_
std::list< boost::shared_ptr< ClientRequestInfo > > active_requests_
#define ROS_INFO_STREAM(args)
ros::ServiceServer tf_republish_service_
actionlib::ActionServer< tf2_web_republisher::TFSubscriptionAction > TFTransformServer
static Time now()
void cancelCB(GoalHandle gh)
#define ROS_ERROR(...)
std::vector< TFPair > tf_subscriptions_
tf2_web_republisher::RepublishTFs::Response Response
#define ROS_DEBUG(...)


tf2_web_republisher
Author(s): Julius Kammer
autogenerated on Mon Feb 28 2022 23:52:49