Help with robot_localization warnings: "Transform from A to odom was unavailable for the time requested. Using latest instead."

asked 2020-08-24 18:09:31 -0500

Equaltrace gravatar image

updated 2020-08-26 12:37:59 -0500

Hello all,

I have been trying to troubleshoot this for a while, but haven't gotten far with it.

The SETUP:

I am trying to fuse pose with odometry data from two cameras zed and realsense (rs). The pose comes from zed in map frame (zed_map) and the odom from realsense in odom frame (camera_odom_frame). Both have their own tf trees as both run their own estimation algorithms. The final output TF tree is present in the attachment: frames

In order to link the rs camera_odom_frame to the robot base_link, I have written a custom tf broadcaster. Basically I know the tf between the base_link --> camera_link and the rs generates camera_link --> camera_odom_frame. Using this information I am able to derive the tf base_link --> camera_link. Below is the code that I use to broadcast the new generated tf. A very identical node is written to generate base_link --> zed_map tf.

int main(int argc, char** argv){
    ros::init(argc, argv, "rs_tf_broadcaster");
    ros::NodeHandle node;

    tf::TransformListener listener;

    ros::Rate rate(200.0);
    while (node.ok()){

        tf::StampedTransform lu_tf;
        try{
            listener.waitForTransform("camera_link", "camera_odom_frame",ros::Time::now(), ros::Duration(4.0));
            listener.lookupTransform("camera_link","camera_odom_frame",
                                    ros::Time(0), lu_tf);
        }

        catch (tf::TransformException ex){
            ROS_ERROR("%s",ex.what());
            //ros::Duration(1.0).sleep();
        }
        tf::Transform base_to_rsbase_tf;
        tf::Quaternion q_rs;
        q_rs.setRPY(0, 0.83, 0);
        tf::Vector3 vec3_rs(0.265, 0.12, 1.0);

        base_to_rsbase_tf.setOrigin(vec3_rs);
        base_to_rsbase_tf.setRotation(q_rs);

        tf::Transform rsbase_to_rsodom_tf;
        rsbase_to_rsodom_tf.setOrigin(lu_tf.getOrigin());
        rsbase_to_rsodom_tf.setBasis(lu_tf.getBasis());

        tf::Transform base_to_rsodom_tf;
        base_to_rsodom_tf = base_to_rsbase_tf * rsbase_to_rsodom_tf; //VERIFIED

        static tf::TransformBroadcaster br_rs;
        br_rs.sendTransform(tf::StampedTransform(base_to_rsodom_tf, ros::Time::now(), "base_link", "camera_odom_frame"));

        rate.sleep();
    }
  return 0;
};

The launch file used to launch robot_loclaization is simple:

<launch>

<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization">
<rosparam command="load" file="$(find cognimo)/config/ekf_localization.yaml"/>
</node>

</launch>

The yaml file for localization is linked here.

Now I come to the ISSUE at hand: I am able to run the robot_localization node i.e. ekf_localization. Upon running I get the following error message and the repeated warnings:

[ WARN] [1598303517.049491085]: Could not obtain transform from camera_pose_frame to base_link. Error was Lookup would require extrapolation into the past.  Requested time 1598303517.048263512 but the earliest data is at time 1598303517.052134514, when looking up transform from frame [camera_pose_frame] to frame [base_link]

[ WARN] [1598303517.054181358]: Transform from camera_pose_frame to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1598303519.076994401]: Transform from camera_pose_frame to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1598303521.077250369]: Transform from camera_pose_frame to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1598303523.097323886]: Transform from camera_pose_frame to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1598303525.123948904]: Transform from zed_map to odom was unavailable for the time requested. Using latest instead.

[ WARN] [1598303527.161387025]: Transform from camera_pose_frame to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1598303529.191298926]: Transform from zed_map to odom ...
(more)
edit retag flag offensive close merge delete

Comments

tf can be slow "ros::Rate rate(200.0);" might be on the high side, does the rest of the system update this fast? Quick try with rate(50) might give a clue. I cant access your google drive links. Also the warn is about camera_POSE_frame, the zed I assume? But all the code is about camera_odom_frame, the rs I assume? In the end its just a warn does it work at all? Would like to see your ekf configuration yaml. Did you set transform_timeout: X.X ?

Dragonslayer gravatar image Dragonslayer  ( 2020-08-25 10:10:29 -0500 )edit

Hello Dragonslayer: I have updated the links. They should be visible publicly now. I can drop the rate to 50 and try. I kept the rate to 200 to match the rate at which camera_odom_frame-->camera_pose_frame is published by the rs camera. The rates should be visible in frames png linked now. The warn is for both camera_pose_frame (realsense "rs" camera) and the zed_map (zed camera). Yes, I only posted the code for the rs camera as the code for zed is identical. The only difference is that I kept the rate for zed to 20 Hz for the zed node. Initially I had set both zed and rs to 200 Hz, but later changed zed to 20 Hz while testing/experimenting. Also, I am running robot_localization at 5 Hz, but I have also experimented with 50, 100 Hz and I still get the same warnings. I have not tried tansform_timeout ...(more)

Equaltrace gravatar image Equaltrace  ( 2020-08-25 10:51:31 -0500 )edit

I think its the different frequencies then. The ekf has some functionallity to take this into account, transform_timeout is part of that (might also help for little latencies, except for simulation and very specialized hardware I didnt ever see realtime like behaviour), on top of my head Iam not sure what else there is in this regard, but there for sure are parameters to take care of fusing different hz publishing sources/latencies.

Dragonslayer gravatar image Dragonslayer  ( 2020-08-25 11:22:04 -0500 )edit

@Dragonslayer: Thanks for the reply. I tried out different frequencies and played around with the parameters yesterday , but little has helped. I am trying to understand why this issue would be coming up in the first place. The way timing works is a bit hazy on my end. As I would understand, as long as my robot_loclaization frequency is <= less my slowest tf, I should be good? But maybe I am wrong and there are things I need to understand. I will keep on trudging. Let me know if you any more tips for me.

Equaltrace gravatar image Equaltrace  ( 2020-08-26 08:22:21 -0500 )edit

@Dragonslayer: I have posted an update with a bit more information. At this point, I am begining to doubt my approach of generating the dynamic tf by multiplying a dynamic tf with a static tf. Still stumped at this -_-

Equaltrace gravatar image Equaltrace  ( 2020-08-26 12:39:58 -0500 )edit

As far as I understand it the alghorythm is made for a perfect system, but in reallity via usb connected sensors you almost never get hard realtime. This is why ekf has functionallity to handle non syncronized topic publishing. Your first poostet error (camera_pose_frame to base_link) it complains about ca 3ms delay, thats not a unheard of delay for a usb-OS-PC system. I would asume the permanent warns you get are in the same scale. ROS was made with wheeled indoor service robots in mind, at that speeds such latencies arent a big thing. Now your saying your problem is "absurd values" in the output? I dont think those are related to the warn messages nessesarily. You could try predit_to_current_time: false and use a sensor_timeout. What exactly is zed-map for a frame? to have it in the tf tree behind base_link seems strange.

Dragonslayer gravatar image Dragonslayer  ( 2020-08-27 09:45:07 -0500 )edit

By the way ekf also has a transform_timeout setting (mot just sensor_timeout) you might want to check it out. link text

Dragonslayer gravatar image Dragonslayer  ( 2020-08-27 10:07:23 -0500 )edit

@Dragonslayer Yes. The absurd output is also an issue that i found subsequently. I experimented with the values as you advised. Regardless of the timing, the absurdity might be coming from my approach. The tree generated by the zed camera is zed_map->zed_odom->zed_base_link->...and so on. Since zed_base_link already has a parent, I cannot directly connect it my robot base_link in the fashion base_link->zed_base_link. I can connect it as zed_base_link->base_link i.e. as a child but then it starts messing up the rs camera tree connection. As you can see in the frames png, there are two trees, one for rs (starting from camera_odom_frame) and one for zed (starting from zed_map). Since I cannot connect robot base_link to the camera_link and the zed_base_link as a parent, I decided to connect base_link to the top most link of each tree i.e. base_link->zed_map and base_link->camera_odom_frame. I described the approach in beginning. Now ...(more)

Equaltrace gravatar image Equaltrace  ( 2020-08-29 22:00:16 -0500 )edit