ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

TransformBroadcaster as member of ROS2 Node

asked 2018-09-23 08:40:41 -0500

Christian Rauch gravatar image

What is the proper way to create a tf2_ros::TransformBroadcaster inside a rclcpp::Node?

I am trying to create a TransformBroadcaster as a member of a ROS2 node, i.e. constructing from this. So far, I am constructing the ROS2 node member tf_broadcaster from a shared pointer to this:

MyNode::MyNode() : Node("my_node", "node_namespace", true) {
    // in header: std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster;
    tf_broadcaster = std::make_unique<tf2_ros::TransformBroadcaster>(rclcpp::Node::SharedPtr(this));
}

This seems to work in general, e.g. I can publish my transforms. However, I get a double free corruption error when the node is deconstructed, because the node is deconstructed a second time when shared_ptr goes out of scope.

Neither this->shared_from_this() (error at construction: terminate called after throwing an instance of 'std::bad_weak_ptr') nor std::shared_ptr<rclcpp::Node>(this) (error at deconstruction: free(): invalid pointer) allow me to create a shared pointer of this.

Wouldn't it be easier, if the rclcpp::Node would inherit the transformer methods from a TransformBroadcaster class instead of instantiating it manually? E.g. class MyNode : public rclcpp::Node, tf2_ros::TransformBroadcaster {} and then just call this->sendTransform(tf);.

edit retag flag offensive close merge delete

Comments

I had a TransformBroadcaster member variable that couldn't be constructed from shared_from_this at container class construction time, so I made it a shared ptr and initialized that later, which appeared to function but ctrl-c wouldn't kill the node properly (two ctrl-c in a row would work)

lucasw gravatar image lucasw  ( 2018-12-03 11:24:16 -0500 )edit

weak_ptr would break the cyclical shared_ptr there.

lucasw gravatar image lucasw  ( 2018-12-03 21:36:56 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2018-09-24 18:04:18 -0500

Christian Rauch gravatar image

updated 2020-09-07 19:09:10 -0500

A workaround would be to simply create the publisher for tf2_msgs::msg::TFMessage on "/tf" manually like this:

#include <tf2_msgs/msg/tf_message.hpp>
...
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr pub_tf;
...
rmw_qos_profile_t tf_qos_profile = rmw_qos_profile_default;
tf_qos_profile.depth = 100;
pub_tf = this->create_publisher<tf2_msgs::msg::TFMessage>("/tf", tf_qos_profile);
tf2_msgs::msg::TFMessage tfs;
geometry_msgs::msg::TransformStamped tf;
// set tf.transform
tfs.transforms.push_back(tf);
// optionally add multiple TransformStamped to tfs.transforms
pub_tf->publish(tfs);

For now, the implementation of TransformBroadcaster is basically doing the same.

Edit: At least with foxy, it is possible to initialise the TransformBroadcaster as intended:

class MultiWiiNode : public rclcpp::Node {
  tf2_ros::TransformBroadcaster tf_broadcaster;
}

MyNode::MyNode() : Node("my_node"), tf_broadcaster(this) { }
edit flag offensive delete link more

Comments

I had strange behavior in bouncy with StaticTransformBroadcaster (including problems kill the node with ctrl-c and 'invalid start byte' messages from launch.LaunchService), switched to TFMessage publication and now am avoiding those issues.

lucasw gravatar image lucasw  ( 2018-12-03 12:49:45 -0500 )edit
0

answered 2018-09-24 14:45:00 -0500

William gravatar image

updated 2018-09-24 14:49:22 -0500

You cannot use a shared pointer to this in the constructor. You should use this->shared_from_this() but you cannot do that in the constructor.

You could try creating the tf_broadcaster on the first time you use it (store nullptr until then).

Also, ideally the tf2_ros::TransformBroadcaster would take some of the node interfaces, allowing you to pass them in the constructor.

EDIT: with respect to your suggestion...

Wouldn't it be easier, if the rclcpp::Node would inherit the transformer methods from a TransformBroadcaster class instead of instantiating it manually? E.g. class MyNode : public rclcpp::Node, tf2_ros::TransformBroadcaster {} and then just call this->sendTransform(tf);.

That doesn't resolve the issue because the tf2_ros::TransformBroadcaster still needs to access the node, so you'd need to delegate to the constructor for it during the member initialization (e.g. class MyNode : public rclcpp::Node, tf2_ros::TransformBroadcaster : rclcpp::Node(...), tf2_ros::TransformBroadcaster(this) {}) and that requires that you pass this, just like you have the issue now.

edit flag offensive delete link more

Comments

Maybe templating TransformBroadcaster could solve the problem? The TransformBroadcaster does not actually need to store a pointer to the node, only the publisher. It could be constructed from a reference or raw pointer like TransformBroadcaster(T* node) { node->create_publisher(); }.

Christian Rauch gravatar image Christian Rauch  ( 2018-09-24 18:09:34 -0500 )edit

Yeah, that could also work.

William gravatar image William  ( 2018-09-24 18:10:48 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2018-09-23 08:40:41 -0500

Seen: 1,669 times

Last updated: Sep 07 '20