42 #include <boost/thread/mutex.hpp>
43 #include "boost/thread.hpp"
45 #include <tf/tfMessage.h>
47 #include <geometry_msgs/TransformStamped.h>
50 #include <tf2_web_republisher/TFSubscriptionAction.h>
52 #include <tf2_web_republisher/RepublishTFs.h>
53 #include <tf2_web_republisher/TFArray.h>
63 typedef tf2_web_republisher::RepublishTFs::Request
Request;
64 typedef tf2_web_republisher::RepublishTFs::Response
Response;
102 #if ROS_VERSION_MINOR < 10
173 const std::vector<std::string>& source_frames,
174 const std::string& target_frame_,
176 float trans_thres)
const
178 std::size_t request_size_ = source_frames.size();
179 info->tf_subscriptions_.resize(request_size_);
181 for (std::size_t i=0; i<request_size_; ++i )
183 TFPair& tf_pair = info->tf_subscriptions_[i];
185 std::string source_frame =
cleanTfFrame(source_frames[i]);
197 ROS_DEBUG(
"GoalHandle request received");
203 const tf2_web_republisher::TFSubscriptionGoal::ConstPtr& goal = gh.getGoal();
207 goal_info->handle = gh;
230 ROS_DEBUG(
"RepublishTF service request received");
235 std::stringstream topicname;
238 request_info->pub_ =
priv_nh_.
advertise<tf2_web_republisher::TFArray>(topicname.str(), 10,
true);
247 request_info->unsub_timeout_ = req.timeout;
248 request_info->unsub_timer_ =
nh_.
createTimer(request_info->unsub_timeout_,
260 res.topic_name = request_info->pub_.getTopic();
261 ROS_INFO_STREAM(
"Publishing requested TFs on topic " << res.topic_name);
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();
280 ClientRequestInfo& info = **it;
281 if(info.pub_ == request_info->pub_)
290 std::vector<geometry_msgs::TransformStamped>& transforms)
293 std::vector<TFPair>::iterator it ;
294 std::vector<TFPair>::const_iterator end = tf_subscriptions.end();
296 for (it=tf_subscriptions.begin(); it!=end; ++it)
298 geometry_msgs::TransformStamped transform;
306 transform =
tf_buffer_.lookupTransform(it->getTargetFrame(),
307 it->getSourceFrame(),
316 << it->getSourceFrame()
318 << it->getTargetFrame()
319 <<
" is working again at time "
320 << transform.header.stamp.toSec());
323 it->updateTransform(transform);
336 if (it->updateNeeded())
339 transform.header.frame_id = it->getTargetFrame();
340 transform.child_frame_id = it->getSourceFrame();
343 it->transmissionTriggered();
346 transforms.push_back(transform);
353 tf2_web_republisher::TFSubscriptionFeedback feedback;
356 feedback.transforms);
358 if (feedback.transforms.size() > 0)
361 goal_info->handle.publishFeedback(feedback);
362 ROS_DEBUG(
"Client %d: TF feedback published:", goal_info->client_ID_);
365 ROS_DEBUG(
"Client %d: No TF frame update needed:", goal_info->client_ID_);
371 if (request_info->pub_.getNumSubscribers() == 0)
373 request_info->unsub_timer_.start();
377 request_info->unsub_timer_.stop();
380 tf2_web_republisher::TFArray array_msg;
382 array_msg.transforms);
384 if (array_msg.transforms.size() > 0)
387 request_info->pub_.publish(array_msg);
388 ROS_DEBUG(
"Request %d: TFs published:", request_info->client_ID_);
392 ROS_DEBUG(
"Request %d: No TF frame update needed:", request_info->client_ID_);
397 int main(
int argc,
char **argv)
399 ros::init(argc, argv,
"tf2_web_republisher");