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

tf: Lookup would require extrapolation into the past

asked 2014-07-28 10:56:03 -0500

rkeatin3 gravatar image

I've written the following method for returning the homogeneous transformation matrix between two tf links:

Eigen::Matrix4f getTransformation(std::string parentName, std::string childName){
  parentName.insert(0,"/");
  childName.insert(0,"/");
  tf::StampedTransform transform;
  tf::TransformListener listener;
  ros::Time t = ros::Time::now();
  try{
    listener.waitForTransform(parentName, childName, t, ros::Duration(4.0));
    listener.lookupTransform(parentName, childName, t, transform);
  }
  catch (tf::TransformException ex){
    ROS_ERROR("%s",ex.what());
  }
  tf::Matrix3x3 rot = transform.getBasis();
  tf::Vector3 trans = transform.getOrigin();
  Eigen::Matrix4f tranformation = Eigen::MatrixXf::Identity(4,4);
  Eigen::Matrix3f upleft3x3;
  upleft3x3 << rot[0][0], rot[0][1], rot[0][2],
               rot[1][0], rot[1][1], rot[1][2],
               rot[2][0], rot[2][1], rot[2][2];
  tranformation.block<3,3>(0,0) = upleft3x3;
  tranformation.col(3) = Eigen::Vector4f(trans[0],trans[1],trans[2],1);
  return transformation;
}

When I try to use this method, I get the following error:

Lookup would require extrapolation into the past.  Requested time 1406560524.442721448 but the earliest data is at time 1406560524.444821575, when looking up transform from frame [wrist_3] to frame [base_link]

I tried the solution suggested by Martin Günther on this page, but that just resulted in an infinite while loop.

Adding a ros::Duration(1) to the requested time worked, but obviously that isn't ideal. Any other solutions?

edit retag flag offensive close merge delete

Comments

When does this happen? Once at the start or all the time?

dornhege gravatar image dornhege  ( 2014-07-28 10:59:26 -0500 )edit

I get the error whenever the function is called.

rkeatin3 gravatar image rkeatin3  ( 2014-07-28 11:23:10 -0500 )edit

2 Answers

Sort by » oldest newest most voted
12

answered 2014-07-28 12:22:05 -0500

courrier gravatar image

You should ask for the last known transform with Time(0) instead of Time::now()

  ros::Time t = ros::Time(0);
edit flag offensive delete link more

Comments

That worked. Thanks!

rkeatin3 gravatar image rkeatin3  ( 2014-07-28 13:23:14 -0500 )edit

Check out this tuto http://wiki.ros.org/tf/Tutorials/tf%20and%20Time%20%28C%2B%2B%29 for details about tf and times

courrier gravatar image courrier  ( 2014-07-28 16:27:03 -0500 )edit
-1

answered 2020-02-28 15:35:19 -0500

Joy16 gravatar image

There is a typo while the variable transformation..

edit flag offensive delete link more

Comments

1

Although your remark is correct, it is not really an answer to the question. Maybe you can put it as a comment, instead of an answer.

Wilco Bonestroo gravatar image Wilco Bonestroo  ( 2020-02-29 06:27:19 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2014-07-28 10:56:03 -0500

Seen: 23,590 times

Last updated: Feb 28 '20