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

Why should tf2_ros::TransformBroadcaster be defined as static?

asked 2021-07-07 00:41:32 -0500

Rika gravatar image

Hello everyone, this is a followup question to this one.
To cut a long story short, I found out (the hardway!) that if I do not use a static/single instance of broadcaster, the turtles will act erratically, going in circles.
If I only use a static instance, it works just fine. I read the tutorials about tf2, but there is no explanation about this.
Why is that? Could someone kindly explain whats happening here?
Thanks a lot in advance

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2021-07-07 04:01:01 -0500

gvdhoorn gravatar image

updated 2021-07-08 07:21:57 -0500

Why should tf2_ros::TransformBroadcaster be defined as static?

the answer to this would be: it doesn't need to be.

But this seems to be the longer version of the question you include at the end of #q381845:

I'd be grateful if someone could explain why it has to be one instance of the broadcaster for this to work and what happens when its not. (why the eratic behavior?)

This is most likely not "special" to TF/TF2, but an instance of the creating-publishers-in-short-lived-scopes anti-pattern.

This has been discussed many times on ROS Answers.

As a summary: it takes time to setup pub-sub connections between nodes. If you (re)create your publishers at high rates, you're essentially forcing your susbcribers to (re)subscribe at that same rate, or risk losing messages. As in most cases it will be impossible to (re)subscribe fast enough, messages are lost and all sorts of "unexplainable things" start to happen.

ros::TransformBroadcaster creates ros::Publishers internally, so what I wrote above also applies to it.

If I only use a static instance, it works just fine.

that's because if variables are declared static, they will be initialised (ie: created) once, at program start. This will immediately solve the problem, as now subscribers have all the time they need to setup the subscription connections (or: as long as your node is running).

While static works (in this case), it's not too nice, and it's also not needed.

All you need to do is make sure you create your ros::TransformBroadcaster in a scope which lives longer than that of the callback which is using it. For the code you show in #q381845, that would basically mean the scope of main(..) (as you are using lambdas to implement your callbacks). In more traditional code, you'd make the broadcaster a member variable of a class, or keep it in global scope (although that comes with its own disadvantages).


Edit: the comments in #q381845 are also not completely correct:

//Its very important that broadcaster is shared between all turtles
//that is if you define broadcaster in this function/it must be static
//otherwise, you will endup with multiple broadcasters, sending coords
// which will mess everything up. previously I forgot about this

as I now assume you understand, there is no real requirement to only have a single instance, nor must it be shared necessarily. It's perfectly possible to have multiple broadcasters in a single process.

What is important is to make sure it has a sane lifecycle (ie: it does not get created and destroyed every few milliseconds).

edit flag offensive delete link more

Comments

Thanks a lot. really appreciate your kind and thorough explanation :) yes, I'll update my previous comment there as well and add this as a reference there too.

Rika gravatar image Rika  ( 2021-07-07 04:08:16 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-07-07 00:41:32 -0500

Seen: 204 times

Last updated: Jul 08 '21