0
$\begingroup$

Rosanswers logo

Dear all,

Willing to avoid the use of Transformer::waitForTransform() (as I find the loop it implies does not look clean), I used Transformer::addTransformsChangedListener() so as to create a callback on tf changed. Here is my code:

#include "ros/ros.h"
#include <tf/transform_listener.h>


////////////////////////////////////////////////////////////////////////////////
// Callback when tf is updated.
struct MyTfCommunicator
{
public:
    void connectOnTfChanged()
    {
        m_tf_connection = m_tf_listener.addTransformsChangedListener(boost::bind(&MyTfCommunicator::onTfChanged, this));
    }
    void disconnectOnTfChanged()
    {
        if (m_tf_connection.connected())
            m_tf_listener.removeTransformsChangedListener(m_tf_connection);
    }

protected:
    void onTfChanged()
    {
        try
        {
            // Read ee_link's position.
            tf::StampedTransform transform;
            m_tf_listener.lookupTransform("/ee_link", "/world", ros::Time(0), transform);

            // Read desired position.
    
            // Compute the error.
            ROS_INFO("EE pos.x: [%f]", transform.getOrigin().x());
        }
        catch (tf::TransformException &ex)
        {
            ROS_ERROR("%s", ex.what());
            ros::Duration(1.0).sleep();
        }
    }

    tf::TransformListener m_tf_listener;
    boost::signals::connection m_tf_connection;
};


////////////////////////////////////////////////////////////////////////////////
// This node computes the effector's positional and rotational errors and publishes them.
int main(int argc, char **argv)
{
    // Pass argc, arv to init() to allow cmd line remapping.
    ros::init(argc, argv, "lpc_error");

    // Handle to access ROS.
    ros::NodeHandle n;

    // Setup on tf update callback and spin.
    MyTfCommunicator tfCommunicator;

    tfCommunicator.connectOnTfChanged();
    ros::spin();
    tfCommunicator.disconnectOnTfChanged();

    // Exit.
    return 0;
}

This code returns me the following error (I used it against the UR5 model from ROS-I) before actually displaying a real position message 10 or 20 seconds after my node started:

[ERROR] [1407495099.316372953, 56679.089000000]: "world" passed to lookupTransform argument source_frame does not exist.

[ERROR] [1407495100.333225598, 56680.089000000]: Could not find a connection between 'ee_link' and 'world' because they are not part of the same tree.Tf has two or more unconnected trees.

[ERROR] [1407495100.333225598, 56680.089000000]: Could not find a connection between 'ee_link' and 'world' because they are not part of the same tree.Tf has two or more unconnected trees.

... (10 - 20 seconds)

[ INFO] [1407495286.595620292, 56859.293000000]: EE pos.x: [-0.642255]

[ INFO] [1407495286.595733987, 56859.293000000]: EE pos.x: [-0.642255]

[ INFO] [1407495286.595796002, 56859.293000000]: EE pos.x: [-0.642255]

...

I can understand a few error messages while waiting for the buffers to fill up but in my case I have to wait for 10 or 20 seconds before I get the real position message displaying relevant data. This looked weird to me so I created a hacky code shown below and which uses a callback based on a usual subscriber (I no longer use the listener's callback), this code looks like this:

#include "ros/ros.h"
#include "tf2_msgs/TFMessage.h"


void onTfChanged(const tf2_msgs::TFMessage::ConstPtr& msg)
{
    // Compute the error.
    ROS_INFO("EE pos.x: [%f]", msg->transforms[0].transform.translation.x);
}


////////////////////////////////////////////////////////////////////////////////
// This node computes the effector's positional and rotational errors and publishes them.
int main(int argc, char **argv)
{
    // Pass argc, arv to init() to allow cmd line remapping.
    ros::init(argc, argv, "lpc_error");

    // Handle to access ROS.
    ros::NodeHandle n;

    // Setup on tf update callback and spin.
    ros::Subscriber sub = n.subscribe("tf", 3, onTfChanged);

    ros::spin();

    // Exit.
    return 0;
}

Now everything works fine and I get the expected position message without the 10-20 seconds delay:

[ERROR] [1407495285.580706104, 56858.293000000]: "ee_link" passed to lookupTransform argument target_frame does not exist.

[ INFO] [1407495286.595620292, 56859.293000000]: EE pos.x: [-0.642255]

[ INFO] [1407495286.595733987, 56859.293000000]: EE pos.x: [-0.642255]

[ INFO] [1407495286.595796002, 56859.293000000]: EE pos.x: [-0.642255]

...

Does anyone know more than me about the reason for the 10-20 second delay and the unexpected errors in the first case when I use the listener's callback?

Thanks,

Antoine.

---------------EDIT----------------

I have reworked sample code 2, maybe this makes my post clearer...

---------------EDIT EDIT----------------

Now I can see 4 models to consume tfs:

  1. timed loop + lookupTransform()
  2. simple loop + waitForTransform() + lookupTransform()
  3. TransformListener(),
  4. tf::MessageFilter

What I am not sure to understand is when to use which model. Intuitively I would say:

  • Callbacks are best as they limit approximations due to interpolations (as such TransformListener() looks a lot like tf::MessageFilter)
  • On the opposite timed loop + lookupTransform() allows to decouple from different sampling rates of the sensors (as you perform the computations when you like, not when the data is available): good for ease of use, less good for perfs and approximations induced, but this is a choice
  • And waitForTransform() is banned as it is a dirty form of callback

Can you comment on this?


Originally posted by arennuit on ROS Answers with karma: 955 on 2014-08-08

Post score: 1


Original comments

Comment by dornhege on 2014-08-08:
Your additional question doesn't really make sense. In your second example you are reading messages from a normal subscriber! This works perfectly fine. You are not forced to use a tf listener, it is just way more convenient to use.

Comment by dornhege on 2014-08-08:
Well, when you use the message directly it's your job to figure out what the actual transform is. Some translation for some transform is 0 here. Which one is also contained in the message. That is what a transform listener does for you.

Comment by arennuit on 2014-08-08:
@dornhege: when I read from the subscriber (e.g. msg->transforms[0].transform.translation.x) I actually get 0 (not -0.642255 as I fakely wrote in code sample 2) I believe this is another problem though (for which I have no solution right now).

Comment by dornhege on 2014-08-09:
This might just be another transform unless you are sure that there is just one transform in the whole system.

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

if you are having issues with transforms only appearing after a certain time. The usual problem is with your publishers not the listener. You should use view_frames and tf_monitor to debug your transforms sources. Debugging tutorial I'll also note that it's uncommon to want to take callbacks for every tf update. The best approach for holding data until it's available is to use the tf::MessageFilter

Subsidiary Question: tf messages are just a message, you can subscribe to them manually. However each message is only an incremental update which the listener aggregates and computes the net transform. You are looking up the first transform in a list of published transforms without checking the name so it's quite possible that the first transform in the list of transforms has value of 0 for the x translation component.

I recommend that you go through the full set of tf tutorials to understand how tf works better. http://wiki.ros.org/tf/Tutorials

Edit answering additional questions:

Interpolation is actually more accurate than taking data from the closest timestamp as long as you can make the assumption of continuous values and a publish frequency which is above the natural bandwidth of the physical system. And you make the assumption that publishing data for every timestep is much to high bandwidth.

Interpolation is necessary because tf is aggregating information from several asyncronous sources across a distributed network. The standard models for using tf are:

  1. Timing based - you want to know the latest available information during you update loop. To do this simply query with Time(0). Or if you're on a specific schedule you can use a specific time query.
  2. Data source driven - you have received some data and want to transform it into a different coordinate frame. If the data is in the buffer already you can simply lookup at the timestamp of the data. Doing interpolation to evaluate as accurately as possible each link of the chain to form the transform.
  • In simple cases you can simply wait for the transform to become available (waitForTransform) (useful for simple scripts which are single purpose and can block.)
  • If you are in a data intensive and latency intensive application you can buffer and hold the data until the required transform is available.
    • this is what the tf::MessageFilter does for you using the onUpdate callbacks internally

You're first implementation is a partial implementation of the tf::MessageFilter however it does not queue data for later callbacks because you have a hard coded query. Not only that you are simply querying at time 0 so it is going to start reporting as fast as possible when the transform becomes available. But as you mention it does not solve you lag of 20 seconds.

Your second example is not querying the data that you want and does not demonstrate that the data is available. It demonstrates that there is some message coming over the tf topic. you do not even look at the frame_id of that transform. Please follow the previous suggestions of going through the tf Tutorials especially the debugging tutorials to understand what is going on in your system. I expect that your issues are coming from the publishing side and you need to debug that.


Originally posted by tfoote with karma: 58457 on 2014-08-08

This answer was ACCEPTED on the original site

Post score: 0


Original comments

Comment by dornhege on 2014-08-08:
Something is still odd with the posted problem as both variants seem to only trigger the same functionality all the time either by the change handler or by the message callback.

Comment by arennuit on 2014-08-08:
@dornhege: I have cleaned my initial post, I believe things are clearer now, especially the way coordinate X is accessed (let me know). I admit things were a bit misleading in my initial post.

Comment by arennuit on 2014-08-08:
@tfoote: sure I went trough al the tutorials before posting ;) Now I refined my question for extra details on when to use which approach for tf data consumption... The update is marked EDIT EDIT. Also what do you mean by without checking the name?

Comment by tfoote on 2014-08-08:
@arennuit The data you are accessing likely does not represent the information that you are trying to plot. Please go over the linked tutorials so you can understand the tf data model. The value msg->transforms[0].transform.translation.x represents the x value of the first transform published by whatever publisher last published which is likely not the computed transform you are looking for.

Comment by arennuit on 2014-08-08:
Yep, I understand that: the value I put is actually a fake (I did not run the updated code sample 2) because what I am mainly interested in is a feedback on the tf consumption model which I mention in my last edit :)

Comment by arennuit on 2014-08-11:
Ok so I understand with tf it is common to work with data which is not sampled synchronously thanks to interpolation. To consume data you can have a loop timed independently of any data produced or you can use a callback on a data source using tf::MessageFilter. Now the tutorials and doxygen show...

Comment by arennuit on 2014-08-11:
...a data source external to tf but what if you want this callback to be triggered when a frame inside tf updates? Do you have to default back to using waitForPose()?

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.