robot_localization Transform from base_link to map was unavailable for the time requested. Using latest instead.
Hi to Tom and everybody,
I’m currently configuring the robotlocalization package in having two ekfnodes and one navsatnode for fusing GPS, IMU and odom. The problem is that I’m getting the following warning which I’ve seen is a recurring problem in the localizationpackage:
Transform from base_link to map was unavailable for the time requested. Using latest instead.
. If you want to help me to troubleshoot this problem, I’m posting my configuration files for the EKF and the navsat nodes here. I’m also posting the tftree of the system in which you can see there is no delay in the transformation between the map to odom and odom to baselink. Finally, the rate of the IMU, GPS, odom is 50, 40 and 50 respectively. Moreover, It is not a real robot; I’m simulating everything in Gazebo.
I’ve tried the following:
• Setting the variable transform_time_offset: 0.05 in the ekf_se_odom node. I don’t really see the point of this because there is no offset in both transformations.
• Setting the variable predict_to_current_time: true in the ekf_se_odom node
At this moment, I’m running out of ideas and that’s why I’m asking for help.
The bag file for about 10 seconds of simulation, you can find it here:
ekf params
# For parameter descriptions, please refer to the template parameter files for each node.
ekf_se_odom: # Used only for broadcasting odom to base_link transforms
frequency: 30
sensor_timeout: 0.1
two_d_mode: true
transform_time_offset: 0.0
# transform_time_offset: 0.05
# predict_to_current_time: true
transform_timeout: 0.0
print_diagnostics: true
debug: false
odom_frame: odom
base_link_frame: base_link
world_frame: odom
# -------------------------------------
# Wheel odometry:
odom0: /wolverine_velocity_controller/odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, false,
false, false, false]
odom0_queue_size: 10
odom0_nodelay: true
odom0_differential: false
odom0_relative: false
# -------------------------------------
# Laser scanmatching odometry:
# odom1: scanmatch_odom
# odom1_config: [false, false, false,
# false, false, false,
# true, true, true,
# false, false, true,
# false, false, false]
# odom1_queue_size: 10
# odom1_nodelay: true
# odom1_differential: false
# odom1_relative: false
# --------------------------------------
# imu configure:
imu0: /imu/data
imu0_config: [false, false, false,
true, true, false,
false, false, false,
true, true, true,
true, true, true]
imu0_nodelay: false
imu0_differential: false
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true
use_control: false
process_noise_covariance: [1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3]
initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0]
ekf_se_map:
frequency: 30
sensor_timeout: 0.1
two_d_mode: true
transform_time_offset: 0.0
transform_timeout: 0.0
print_diagnostics: true
debug: false
# predict_to_current_time: true
odom_frame: odom
base_link_frame: base_link
world_frame: map
# -------------------------------------
# Wheel odometry:
odom0: /wolverine_velocity_controller/odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]
odom0_queue_size: 10
odom0_nodelay: true
odom0_differential: false
odom0_relative: false
# -------------------------------------
# GPS odometry:
odom1: /outdoor_waypoint_nav/odometry/gps
odom1_config: [true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
odom1_queue_size: 10
odom1_nodelay: true
odom1_differential: false
odom1_relative: false
# -------------------------------------
# Laser scanmatching odometry:
# odom2: scanmatch_odom
# odom2_config: [false, false, false,
# false, false, false,
# true, true, true,
# false, false, true,
# false, false, false]
# odom2_queue_size: 10
# odom2_nodelay: true
# odom2_differential: false
# odom2_relative: false
# --------------------------------------
# imu configure:
imu0: /imu/data
imu0_config: [false, false, false,
true, true, false,
false, false, false,
true, true, true,
true, true, true]
imu0_nodelay: true
imu0_differential: false
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true
use_control: false
process_noise_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3]
initial_estimate_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0]
navsat params
navsat_transform:
frequency: 30
delay: 3.0
magnetic_declination_radians: 0.00 #0.168285 # For lat/long 43.500718, -80.546638 on Jun 1 2017
yaw_offset: 1.570796327 # IMU reads 0 facing magnetic north, not east
zero_altitude: true
# broadcast_utm_transform: false
broadcast_utm_transform: true
publish_filtered_gps: true
use_odometry_yaw: false
wait_for_datum: false
tree tf
P.S. This problem have been posted numerous time but none of the answers provided worked for me.
Robot Localization Package: Transform was unavailable for the time requested. Using latest instead.
robot_localization asking for map to odom transform
navsattransformnode - no transform from base_link to map
Problem while integrating GPS data into robot_localization
Asked by andrestoga on 2019-08-05 01:56:36 UTC
Answers
I'm assuming, based on the frames reported, that this message
Transform from base_link to map was unavailable for the time requested. Using latest instead.
is coming from this line in navsat_transform_node
.
The root of the issue is that the map->base_link transform is not available as of the requested transform_time
.
That value was passed as a parameter here.
That call came from here, and so the stamp in question is gps_odom.header.stamp
.
That value got set when we called this, specifically, here.
So we're setting the value to gps_update_time_
, which, in turn, is set here.
That stamp is just the time stamp of your most recent GPS message.
So then the problem is that navsat_transform_node
is receiving a GPS message, and it wants to convert it to an odometry message (in this case, one that can be consumed by the EKF itself). In order to do that, it needs to look up the robot's pose in the map frame at that moment, but the ekf_se_map
EKF hasn't produced it yet.
Your proposed solutions involved modifying parameters for the ekf_se_odom
node, but that won't produce the map->base_link transform; it's producing odom->base_link. So you really want to change those settings for ekf_se_map
so that navsat_transform_node
can get the transform it needs at the time it needs it.
Asked by Tom Moore on 2019-09-23 04:27:04 UTC
Comments
@andrestoga Hi. Were you able to get a fix for this ? I am running into the same issue and setting predict_to_current_time: true
or transform_time_offset: 0.05
did not fix it for me.
Asked by Equaltrace on 2020-09-15 23:50:23 UTC
Thank you for the detailed explanation, @Tom Moore. Did you find a fix based on this answer, and if yes, what was the fix?
Asked by maxpolzin on 2021-12-11 15:14:20 UTC
It's not really a fix, per se. You need to make sure that your EKF is outputting a transform before the timestamp of the first GPS message. Also, this warning should only print out once or twice. If it's a problem, I recommend finding a way to delay your GPS from publishing. ROS 1 doesn't handle lifecycle management very well, so it's probably not straightforward.
Asked by Tom Moore on 2021-12-15 03:15:02 UTC
Comments