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

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.

asked 2014-08-08 06:22:30 -0600

arennuit gravatar image

updated 2014-08-08 18:15:36 -0600

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 ... (more)

edit retag flag offensive close merge delete

Comments

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.

dornhege gravatar image dornhege  ( 2014-08-08 07:53:55 -0600 )edit

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.

dornhege gravatar image dornhege  ( 2014-08-08 12:36:56 -0600 )edit

@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).

arennuit gravatar image arennuit  ( 2014-08-08 18:18:55 -0600 )edit

This might just be another transform unless you are sure that there is just one transform in the whole system.

dornhege gravatar image dornhege  ( 2014-08-09 08:51:10 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2014-08-08 12:34:45 -0600

tfoote gravatar image

updated 2014-08-08 18:53:16 -0600

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 ... (more)

edit flag offensive delete link more

Comments

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.

dornhege gravatar image dornhege  ( 2014-08-08 12:40:18 -0600 )edit

@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.

arennuit gravatar image arennuit  ( 2014-08-08 17:15:16 -0600 )edit

@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?

arennuit gravatar image arennuit  ( 2014-08-08 18:05:57 -0600 )edit
1

@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.

tfoote gravatar image tfoote  ( 2014-08-08 18:16:00 -0600 )edit

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 :)

arennuit gravatar image arennuit  ( 2014-08-08 18:29:31 -0600 )edit

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...

arennuit gravatar image arennuit  ( 2014-08-11 05:13:35 -0600 )edit

...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()?

arennuit gravatar image arennuit  ( 2014-08-11 05:15:53 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2014-08-08 06:22:30 -0600

Seen: 1,598 times

Last updated: Aug 08 '14