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

tf2 transform error: Lookup would require extrapolation into the past

asked 2019-06-12 08:06:23 -0500

GabrielBagon44 gravatar image

updated 2019-06-12 08:11:29 -0500

Hi, I am currently trying to simulate a quadcopter in gazebo using mavros and px4 sitl. In this simulation, the quadcopter will identify an aruco marker, then attempt to center itself with that marker. To do so, I needed to transform the marker frame (on the ground) to the frame of the quadcopter itself (map). I have checked to see if all the frames I am working with are from the same tf but when I run the code, I get the error pictured below.

Using ROS kinetic, on ubuntu 16.04.

tf tree

these are two separate trees.

  • local_origin]-->[local_origin_ned]-->[fcu_frd]-->[fcu]
  • [map]-->[base_link]-->[marker_frame] (This is the tf I am working with)

Code

#include <ros/ros.h>
#include <tf2_ros/transform_listener.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <tf2_ros/buffer_interface.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
geometry_msgs::PoseStamped poseIn;
geometry_msgs::PoseStamped poseOut;
bool received; 

ros::Duration timeout; 
void callback(const geometry_msgs::PoseStamped& msg){
    poseIn = msg; 
    received= true; 
}

int main(int argc, char** argv){
    ros::init(argc, argv, "listener_test");
    ros::NodeHandle nh;
    ros::Subscriber sub = nh.subscribe("aruco_single/pose", 100, &callback); 
    tf2_ros::Buffer tfBuffer;
    tf2_ros::TransformListener tfListener(tfBuffer);

    ros::Rate rate(10.0); //rate 10 
    sleep(1);

    while (nh.ok()){
        try{
            if(received){poseOut = tfBuffer.transform(poseIn, "map", ros::Duration(0.0));}
        }
        catch (tf2::TransformException &ex) {
            ROS_WARN("%s",ex.what());
            ros::Duration(1.0).sleep();
                continue;
        }
    rate.sleep();
    ros::spinOnce();
    }
    return 0;
}

Error

[ WARN] [1560275941.431970740, 1406.020000000]: Lookup would require extrapolation into the past.  Requested time 1405.716000000 but the earliest data is at time 1560275940.551247808, when looking up transform from frame [base_link] to frame [map]
edit retag flag offensive close merge delete

Comments

hmm I have it enabled in my gazebo launch file as shown, however it doesn't seem to be doing any good. From what I read it shouldn't have to be enabled more than once correct?

<param name="/use_sim_time" value="true"/>

Going to try and see what happens if I enable it in as many launch files as I can.

GabrielBagon44 gravatar image GabrielBagon44  ( 2019-06-13 12:31:22 -0500 )edit

ok so, it seems to be working when I enable it in multiple launch files. The only problem now is that the same error occurs but it requires extrapolation into the future instead of past,

[ WARN] [1560785140.962946054, 106.796000000]: Lookup would require extrapolation into the future.  Requested time 106.788000000 but the latest data is at time 106.760932372, when looking up transform from frame [base_link] to frame [map]
GabrielBagon44 gravatar image GabrielBagon44  ( 2019-06-17 10:33:57 -0500 )edit
1

Okay we're very close now. If you look at the times, the tf buffer is less than 0.02 seconds behind. You're currently calling transform with no timeout (i.e. Duration(0.0)) if you change this to Duration(0.1) then this should start working. This will give the transform call enough time to wait for the most recent TF data to arrive allowing it to successfully transform the pose.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-06-17 10:57:43 -0500 )edit
1

Awesome everything seems to be functioning now! Thank you very much for sticking with me through this, I have learned a lot. I really appreciated the help.

GabrielBagon44 gravatar image GabrielBagon44  ( 2019-06-17 12:01:51 -0500 )edit

You're welcome. Glad you got it working.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-06-17 20:05:11 -0500 )edit

hello encountered the same problem and i don't where to change the tf buffer.

mgrallos gravatar image mgrallos  ( 2023-01-24 00:26:37 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-06-12 09:43:18 -0500

This looks as though some of your nodes are using gazebo sim time while some other are using machine time given the difference between them is so large. Have you set the use_sim_time to true in the launch files for your nodes? This problem and the solution is described in this answer here.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-06-12 08:06:23 -0500

Seen: 7,210 times

Last updated: Jun 12 '19