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

Transform from ____ to ____ was unavailable for the time requested. Using latest instead.

asked 2020-09-06 14:04:22 -0500

blaine141 gravatar image

When I run robot_localization in simulation I get the following warning every 2 seconds

[ WARN] [1599417511.143838658, 4.002000000]: Transform from puddles/imu_link to puddles/base_link was unavailable for the time requested. Using latest instead.

While this warning does not cause any immediate issues, I am concerned it means I have poorly implemented tf or simulated time somewhere. This occurs in simulation but I have been unable to test it on our actual system. I have use_sim_time set to true, all of my tf publishers are publishing very frequently, and the only way I can get the warning to go away is to set a transform_timeout in robot_localization, which causes failed to update warnings. The systems I have tested this on have been Ubuntu 18.04 ROS Melodic.

This is an underwater application, so I only have 3 sensors, IMU, depth, and DVL. IMU is the only sensor that has ever been referred to in this warning. Here are some more information about my system.

view_frames

node_graph

EKF_localization_node params

frequency: 30
silent_tf_failure: false
two_d_mode: false
transform_time_offset: 0.0
transform_timeout: 0.0
print_diagnostics: true
debug: false
debug_out_file: /path/to/debug/file.txt
publish_tf: true
publish_acceleration: false

imu0: imu/data
imu0_config: [false, false, false,
              true,  true,  true,
              false, false, false,
              true,  true,  true,
              true,  true,  true]
imu0_queue_size: 5
imu0_remove_gravitational_acceleration: true
gravitational_acceleration: 9.81604

twist0: dvl/twist
twist0_config: [false, false, false,
                false, false, false,
                true,  true,  true,
                false, false, false,
                false, false, false]

pose0: depth/pose
pose0_config: [false, false, true,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]

IMU message published at 100 Hz:

header: 
  seq: 1953
  stamp: 
    secs: 19
    nsecs: 716000000
  frame_id: "puddles/imu_link"
orientation: 
  x: 0.0523333914357
  y: -0.35588218556
  z: 0.0330905279149
  w: 0.932477400854
orientation_covariance: [0.0001, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.0001]
angular_velocity: 
  x: -3.59392461073e-11
  y: 8.47498014701e-12
  z: -2.18380955198e-11
angular_velocity_covariance: [1.1519236000000001e-07, 0.0, 0.0, 0.0, 1.1519236000000001e-07, 0.0, 0.0, 0.0, 1.1519236000000001e-07]
linear_acceleration: 
  x: 6.53786067743
  y: 0.726375271311
  z: 7.26436473382
linear_acceleration_covariance: [1.6e-05, 0.0, 0.0, 0.0, 1.6e-05, 0.0, 0.0, 0.0, 1.6e-05]

If you know anything about what this warning is referring to, how to fix it, or how to suppress it, please let me know

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-09-29 04:46:21 -0500

Tom Moore gravatar image

updated 2020-09-29 10:18:54 -0500

The reason you see that warning is that you are using a state_publisher node that isn't publishing the static transforms on the latched /tf_static topic. It's publishing them at a fixed frequency, so once in a while, the state estimation node asks for a transform that hasn't been published yet.

You can safely ignore the warning, since the latest transform that it falls back to is always the same. However, if it bothers you, you can set the use_tf_static to true on your state_publisher node. See this wiki page for details:

http://wiki.ros.org/robot_state_publi...

EDIT in response to comments:

Some of your links are using static transforms when you do that (they show up as 10000 Hz), but your IMU link is not (same for a few others). It still shows up as being published at 93 Hz, as do a bunch of your other links. Any chance your URDF doesn't have your imu_link as a fixed joint? image description

edit flag offensive delete link more

Comments

I have used static before and it didn't work. I tried it again and the warning kept coming every 2 seconds. I should also note no matter the state publisher frequency, the warning comes every 2 seconds

blaine141 gravatar image blaine141  ( 2020-09-29 09:19:51 -0500 )edit

Can you show me the transform graph with static enabled?

Tom Moore gravatar image Tom Moore  ( 2020-09-29 09:21:35 -0500 )edit
blaine141 gravatar image blaine141  ( 2020-09-29 09:47:35 -0500 )edit

Yes, some of my joints are not fixed and they have to be to simulate in gazebo properly.

blaine141 gravatar image blaine141  ( 2020-09-29 10:39:25 -0500 )edit

Understood, but that is going to be the the source of that warning. In order for robot_state_publisher to publish a joint using tf2's static transform publication, it needs to be a fixed joint. If it's a floating joint, then it will publish non-static messages as some fixed frequency. No matter what the frequency is, if you get an IMU message with a newer timestamp than the latest imu_link transform publication, you will get that warning.

Tom Moore gravatar image Tom Moore  ( 2020-09-29 10:51:38 -0500 )edit

Ok. I will try to make fixed copies of the joints and map the sensor msgs to the static joint.

blaine141 gravatar image blaine141  ( 2020-09-29 10:53:32 -0500 )edit

It works. I use revolute joints for the sim in gazebo, make a node that remaps it to a fixed joint, then pass that to the EKF. Thank you

blaine141 gravatar image blaine141  ( 2020-09-29 12:20:40 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-09-06 14:04:22 -0500

Seen: 434 times

Last updated: Sep 29 '20