22 #include "tf_thread.h"
24 #include <core/threading/mutex_locker.h>
25 #include <ros/this_node.h>
44 tf_msg_queue_mutex_ =
new Mutex();
45 seq_num_mutex_ =
new Mutex();
46 last_update_ =
new Time();
52 delete tf_msg_queue_mutex_;
53 delete seq_num_mutex_;
66 cfg_update_interval_ = 1.0;
68 cfg_update_interval_ =
config->
get_float(
"/ros/tf/static-update-interval");
76 throw Exception(
"tf2 enabled in config but not available at compile time");
78 sub_tf_ =
rosnode->subscribe(
"tf", 100, &RosTfThread::tf_message_cb_dynamic,
this);
79 sub_static_tf_ =
rosnode->subscribe(
"tf_static", 100, &RosTfThread::tf_message_cb_static,
this);
80 pub_tf_ =
rosnode->advertise<tf2_msgs::TFMessage>(
"tf", 100);
81 pub_static_tf_ =
rosnode->advertise<tf2_msgs::TFMessage>(
"tf_static", 100,
true);
84 sub_tf_ =
rosnode->subscribe(
"tf", 100, &RosTfThread::tf_message_cb,
this);
85 pub_tf_ =
rosnode->advertise<::tf::tfMessage>(
"tf", 100);
89 std::list<TransformInterface *>::iterator i;
90 for (i = tfifs_.begin(); i != tfifs_.end(); ++i) {
97 publish_static_transforms_to_ros();
112 std::list<TransformInterface *>::iterator i;
113 for (i = tfifs_.begin(); i != tfifs_.end(); ++i) {
122 tf_msg_queue_mutex_->
lock();
123 unsigned int queue = active_queue_;
124 active_queue_ = 1 - active_queue_;
125 tf_msg_queue_mutex_->
unlock();
129 while (!tf2_msg_queues_[queue].empty()) {
130 const std::pair<bool, tf2_msgs::TFMessage::ConstPtr> &q = tf2_msg_queues_[queue].front();
131 const tf2_msgs::TFMessage::ConstPtr & msg = q.second;
132 const size_t tsize = msg->transforms.size();
133 for (
size_t i = 0; i < tsize; ++i) {
134 publish_transform_to_fawkes(msg->transforms[i], q.first);
136 tf2_msg_queues_[queue].pop();
140 while (!tf_msg_queues_[queue].empty()) {
141 const ::tf::tfMessage::ConstPtr &msg = tf_msg_queues_[queue].front();
142 const size_t tsize = msg->transforms.size();
143 for (
size_t i = 0; i < tsize; ++i) {
144 geometry_msgs::TransformStamped ts = msg->transforms[i];
145 if (!ts.header.frame_id.empty() && ts.header.frame_id[0] ==
'/') {
146 ts.header.frame_id = ts.header.frame_id.substr(1);
148 if (!ts.child_frame_id.empty() && ts.child_frame_id[0] ==
'/') {
149 ts.child_frame_id = ts.child_frame_id.substr(1);
151 publish_transform_to_fawkes(ts);
153 tf_msg_queues_[queue].pop();
157 if ((now - last_update_) > cfg_update_interval_) {
158 last_update_->
stamp();
160 publish_static_transforms_to_ros();
175 publish_static_transforms_to_ros();
179 tf2_msgs::TFMessage tmsg;
180 tmsg.transforms.push_back(create_transform_stamped(tfif));
181 pub_tf_.publish(tmsg);
184 ::tf::tfMessage tmsg;
190 tmsg.transforms.push_back(create_transform_stamped(tfif, ×tamp));
192 tmsg.transforms.push_back(create_transform_stamped(tfif));
194 pub_tf_.publish(tmsg);
202 if (strncmp(type,
"TransformInterface", INTERFACE_TYPE_SIZE_) != 0)
205 for (
const auto &f : ros_frames_) {
217 logger->
log_warn(name(),
"Failed to open %s:%s: %s", type, id, e.
what());
222 bbil_add_data_interface(tfif);
223 bbil_add_reader_interface(tfif);
224 bbil_add_writer_interface(tfif);
226 tfifs_.push_back(tfif);
228 blackboard->
close(tfif);
229 logger->
log_warn(name(),
"Failed to register for %s:%s: %s", type,
id, e.
what());
236 unsigned int instance_serial)
throw()
238 conditional_close(interface);
243 unsigned int instance_serial)
throw()
245 conditional_close(interface);
249 RosTfThread::conditional_close(
Interface *interface)
throw()
256 std::list<TransformInterface *>::iterator i;
257 for (i = tfifs_.begin(); i != tfifs_.end(); ++i) {
258 if (*interface == **i) {
259 if (!interface->has_writer() && (interface->num_readers() == 1)) {
261 logger->
log_info(name(),
"Last on %s, closing", interface->uid());
262 bbil_remove_data_interface(*i);
263 bbil_remove_reader_interface(*i);
264 bbil_remove_writer_interface(*i);
266 blackboard->
close(*i);
274 geometry_msgs::TransformStamped
278 double *rotation = tfif->
rotation();
282 geometry_msgs::Vector3 t;
283 t.x = translation[0];
284 t.y = translation[1];
285 t.z = translation[2];
286 geometry_msgs::Quaternion r;
291 geometry_msgs::Transform tr;
295 geometry_msgs::TransformStamped ts;
296 seq_num_mutex_->
lock();
297 ts.header.seq = ++seq_num_;
300 ts.header.frame_id = tfif->
frame();
308 RosTfThread::publish_static_transforms_to_ros()
310 std::list<fawkes::TransformInterface *>::iterator t;
315 tf2_msgs::TFMessage tmsg;
316 for (t = tfifs_.begin(); t != tfifs_.end(); ++t) {
320 tmsg.transforms.push_back(create_transform_stamped(tfif, &now));
323 pub_static_tf_.publish(tmsg);
328 fawkes::Time timestamp = now + (cfg_update_interval_ * 1.1);
330 ::tf::tfMessage tmsg;
331 for (t = tfifs_.begin(); t != tfifs_.end(); ++t) {
335 tmsg.transforms.push_back(create_transform_stamped(tfif, ×tamp));
338 pub_tf_.publish(tmsg);
343 RosTfThread::publish_transform_to_fawkes(
const geometry_msgs::TransformStamped &ts,
bool static_tf)
345 const geometry_msgs::Vector3 & t = ts.transform.translation;
346 const geometry_msgs::Quaternion &r = ts.transform.rotation;
348 fawkes::Time time(ts.header.stamp.sec, ts.header.stamp.nsec / 1000);
350 fawkes::tf::Transform tr(fawkes::tf::Quaternion(r.x, r.y, r.z, r.w),
351 fawkes::tf::Vector3(t.x, t.y, t.z));
356 ros_frames_.push_back(std::string(
"/tf/") + ts.child_frame_id);
358 tf_publishers[ts.child_frame_id]->send_transform(st, static_tf);
360 ros_frames_.pop_back();
362 "Failed to create Fawkes transform publisher for frame %s from ROS",
363 ts.child_frame_id.c_str());
367 tf_publishers[ts.child_frame_id]->send_transform(st, static_tf);
375 RosTfThread::tf_message_cb(
const ros::MessageEvent<::tf::tfMessage const> &msg_evt)
379 const ::tf::tfMessage::ConstPtr &msg = msg_evt.getConstMessage();
380 std::string authority = msg_evt.getPublisherName();
382 if (authority ==
"") {
384 }
else if (authority != ros::this_node::getName()) {
385 tf_msg_queues_[active_queue_].push(msg);
391 RosTfThread::tf_message_cb_static(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt)
393 tf_message_cb(msg_evt,
true);
397 RosTfThread::tf_message_cb_dynamic(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt)
399 tf_message_cb(msg_evt,
false);
403 RosTfThread::tf_message_cb(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt,
408 const tf2_msgs::TFMessage::ConstPtr &msg = msg_evt.getConstMessage();
409 std::string authority = msg_evt.getPublisherName();
411 if (authority ==
"") {
413 }
else if (authority != ros::this_node::getName()) {
414 tf2_msg_queues_[active_queue_].push(std::make_pair(static_tf, msg));