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.
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 ...
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.
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: 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).
This might just be another transform unless you are sure that there is just one transform in the whole system.