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;
68 __cfg_update_interval = 1.0;
70 __cfg_update_interval =
config->
get_float(
"/ros/tf/static-update-interval");
77 throw Exception(
"tf2 enabled in config but not available at compile time");
79 __sub_tf =
rosnode->subscribe(
"tf", 100, &RosTfThread::tf_message_cb_dynamic,
this);
80 __sub_static_tf =
rosnode->subscribe(
"tf_static", 100, &RosTfThread::tf_message_cb_static,
this);
81 __pub_tf =
rosnode->advertise< tf2_msgs::TFMessage >(
"tf", 100);
82 __pub_static_tf =
rosnode->advertise< tf2_msgs::TFMessage >(
"tf_static", 100,
true);
85 __sub_tf =
rosnode->subscribe(
"tf", 100, &RosTfThread::tf_message_cb,
this);
86 __pub_tf =
rosnode->advertise< ::tf::tfMessage >(
"tf", 100);
90 std::list<TransformInterface *>::iterator i;
91 for (i = __tfifs.begin(); i != __tfifs.end(); ++i) {
98 publish_static_transforms_to_ros();
114 std::list<TransformInterface *>::iterator i;
115 for (i = __tfifs.begin(); i != __tfifs.end(); ++i) {
125 __tf_msg_queue_mutex->
lock();
126 unsigned int queue = __active_queue;
127 __active_queue = 1 - __active_queue;
128 __tf_msg_queue_mutex->
unlock();
132 while (! __tf2_msg_queues[queue].empty()) {
133 const std::pair<bool, tf2_msgs::TFMessage::ConstPtr> &q = __tf2_msg_queues[queue].front();
134 const tf2_msgs::TFMessage::ConstPtr &msg = q.second;
135 const size_t tsize = msg->transforms.size();
136 for (
size_t i = 0; i < tsize; ++i) {
137 publish_transform_to_fawkes(msg->transforms[i], q.first);
139 __tf2_msg_queues[queue].pop();
143 while (! __tf_msg_queues[queue].empty()) {
144 const ::tf::tfMessage::ConstPtr &msg = __tf_msg_queues[queue].front();
145 const size_t tsize = msg->transforms.size();
146 for (
size_t i = 0; i < tsize; ++i) {
147 geometry_msgs::TransformStamped ts = msg->transforms[i];
148 if (! ts.header.frame_id.empty() && ts.header.frame_id[0] ==
'/') {
149 ts.header.frame_id = ts.header.frame_id.substr(1);
151 if (! ts.child_frame_id.empty() && ts.child_frame_id[0] ==
'/') {
152 ts.child_frame_id = ts.child_frame_id.substr(1);
154 publish_transform_to_fawkes(ts);
156 __tf_msg_queues[queue].pop();
160 if ((now - __last_update) > __cfg_update_interval) {
161 __last_update->
stamp();
163 publish_static_transforms_to_ros();
178 publish_static_transforms_to_ros();
182 tf2_msgs::TFMessage tmsg;
183 tmsg.transforms.push_back(create_transform_stamped(tfif));
184 __pub_tf.publish(tmsg);
187 ::tf::tfMessage tmsg;
193 tmsg.transforms.push_back(create_transform_stamped(tfif, ×tamp));
195 tmsg.transforms.push_back(create_transform_stamped(tfif));
197 __pub_tf.publish(tmsg);
206 if (strncmp(type,
"TransformInterface", __INTERFACE_TYPE_SIZE) != 0)
return;
208 for (
const auto &f : __ros_frames) {
228 __tfifs.push_back(tfif);
238 unsigned int instance_serial)
throw()
240 conditional_close(interface);
245 unsigned int instance_serial)
throw()
247 conditional_close(interface);
251 RosTfThread::conditional_close(
Interface *interface)
throw()
257 std::list<TransformInterface *>::iterator i;
258 for (i = __tfifs.begin(); i != __tfifs.end(); ++i) {
259 if (*interface == **i) {
276 geometry_msgs::TransformStamped
280 double *rotation = tfif->
rotation();
283 geometry_msgs::Vector3 t;
284 t.x = translation[0]; t.y = translation[1]; t.z = translation[2];
285 geometry_msgs::Quaternion r;
286 r.x = rotation[0]; r.y = rotation[1]; r.z = rotation[2]; r.w = rotation[3];
287 geometry_msgs::Transform tr;
291 geometry_msgs::TransformStamped ts;
292 __seq_num_mutex->
lock();
293 ts.header.seq = ++__seq_num;
294 __seq_num_mutex->
unlock();
296 ts.header.frame_id = tfif->
frame();
304 RosTfThread::publish_static_transforms_to_ros()
306 std::list<fawkes::TransformInterface *>::iterator t;
311 tf2_msgs::TFMessage tmsg;
312 for (t = __tfifs.begin(); t != __tfifs.end(); ++t) {
316 tmsg.transforms.push_back(create_transform_stamped(tfif, &now));
319 __pub_static_tf.publish(tmsg);
324 fawkes::Time timestamp = now + (__cfg_update_interval * 1.1);
326 ::tf::tfMessage tmsg;
327 for (t = __tfifs.begin(); t != __tfifs.end(); ++t) {
331 tmsg.transforms.push_back(create_transform_stamped(tfif, ×tamp));
334 __pub_tf.publish(tmsg);
340 RosTfThread::publish_transform_to_fawkes(
const geometry_msgs::TransformStamped &ts,
bool static_tf)
342 const geometry_msgs::Vector3 &t = ts.transform.translation;
343 const geometry_msgs::Quaternion &r = ts.transform.rotation;
345 fawkes::Time time(ts.header.stamp.sec, ts.header.stamp.nsec / 1000);
347 fawkes::tf::Transform tr(fawkes::tf::Quaternion(r.x, r.y, r.z, r.w),
348 fawkes::tf::Vector3(t.x, t.y, t.z));
350 st(tr, time, ts.header.frame_id, ts.child_frame_id);
354 __ros_frames.push_back(std::string(
"/tf/") + ts.child_frame_id);
356 tf_publishers[ts.child_frame_id]->send_transform(st, static_tf);
358 __ros_frames.pop_back();
359 logger->
log_warn(
name(),
"Failed to create Fawkes transform publisher for frame %s from ROS",
360 ts.child_frame_id.c_str());
364 tf_publishers[ts.child_frame_id]->send_transform(st, static_tf);
373 RosTfThread::tf_message_cb(
const ros::MessageEvent<::tf::tfMessage const> &msg_evt)
377 const ::tf::tfMessage::ConstPtr &msg = msg_evt.getConstMessage();
378 std::string authority = msg_evt.getPublisherName();
380 if (authority ==
"") {
382 }
else if (authority != ros::this_node::getName()) {
383 __tf_msg_queues[__active_queue].push(msg);
389 RosTfThread::tf_message_cb_static(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt)
391 tf_message_cb(msg_evt,
true);
395 RosTfThread::tf_message_cb_dynamic(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt)
397 tf_message_cb(msg_evt,
false);
401 RosTfThread::tf_message_cb(
const ros::MessageEvent<tf2_msgs::TFMessage const> &msg_evt,
bool static_tf)
405 const tf2_msgs::TFMessage::ConstPtr &msg = msg_evt.getConstMessage();
406 std::string authority = msg_evt.getPublisherName();
408 if (authority ==
"") {
410 }
else if (authority != ros::this_node::getName()) {
411 __tf2_msg_queues[__active_queue].push(std::make_pair(static_tf, msg));
virtual void register_observer(BlackBoardInterfaceObserver *observer)
Register BB interface observer.
virtual void log_info(const char *component, const char *format,...)=0
Log informational message.
virtual void bb_interface_data_changed(fawkes::Interface *interface)
BlackBoard data changed notification.
Fawkes library namespace.
virtual bool get_bool(const char *path)=0
Get value from configuration which is of type bool.
void unlock()
Unlock the mutex.
void bbil_add_writer_interface(Interface *interface)
Add an interface to the writer addition/removal watch list.
A class for handling time.
virtual const char * what() const
Get primary string.
virtual void unregister_listener(BlackBoardInterfaceListener *listener)
Unregister BB interface listener.
Thread class encapsulation of pthreads.
virtual void update_listener(BlackBoardInterfaceListener *listener, ListenerRegisterFlag flag=BBIL_FLAG_ALL)
Update BB event listener.
Base class for all Fawkes BlackBoard interfaces.
void bbil_remove_writer_interface(Interface *interface)
Remove an interface to the writer addition/removal watch list.
Logger * logger
This is the Logger member used to access the logger.
Clock * clock
By means of this member access to the clock is given.
Thread aspect to use blocked timing.
virtual void register_listener(BlackBoardInterfaceListener *listener, ListenerRegisterFlag flag=BBIL_FLAG_ALL)
Register BB event listener.
void bbio_add_observed_create(const char *type_pattern, const char *id_pattern="*")
Add interface creation type to watch list.
Base class for exceptions in Fawkes.
void set_clock(Clock *clock)
Set clock for this instance.
void read()
Read from BlackBoard into local copy.
virtual void finalize()
Finalize the thread.
long get_nsec() const
Get nanoseconds.
virtual void unregister_observer(BlackBoardInterfaceObserver *observer)
Unregister BB interface observer.
bool has_writer() const
Check if there is a writer for the interface.
const char * name() const
Get name of thread.
const char * uid() const
Get unique identifier of interface.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
const Time * timestamp() const
Get timestamp of last write.
virtual std::list< Interface * > open_multiple_for_reading(const char *type_pattern, const char *id_pattern="*", const char *owner=NULL)=0
Open multiple interfaces for reading.
void bbil_remove_data_interface(Interface *interface)
Remove an interface to the data modification watch list.
long get_sec() const
Get seconds.
void bbil_add_reader_interface(Interface *interface)
Add an interface to the reader addition/removal watch list.
RosTfThread()
Constructor.
virtual void loop()
Code to execute in the thread.
virtual void bb_interface_reader_removed(fawkes::Interface *interface, unsigned int instance_serial)
A reading instance has been closed for a watched interface.
void set_time(const timeval *tv)
Sets the time.
virtual Interface * open_for_reading(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for reading.
LockPtr< ros::NodeHandle > rosnode
Central ROS node handle.
void lock()
Lock this mutex.
Time & stamp()
Set this time to the current time.
unsigned int num_readers() const
Get the number of readers.
virtual void bb_interface_writer_removed(fawkes::Interface *interface, unsigned int instance_serial)
A writing instance has been closed for a watched interface.
Mutex mutual exclusion lock.
virtual void init()
Initialize the thread.
Configuration * config
This is the Configuration member used to access the configuration.
virtual float get_float(const char *path)=0
Get value from configuration which is of type float.
virtual void bb_interface_created(const char *type, const char *id)
BlackBoard interface created notification.
void bbil_remove_reader_interface(Interface *interface)
Remove an interface to the reader addition/removal watch list.
virtual ~RosTfThread()
Destructor.
BlackBoard interface listener.
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
void bbil_add_data_interface(Interface *interface)
Add an interface to the data modification watch list.
virtual void close(Interface *interface)=0
Close interface.