Robot Localization repeatability
Hi all,
I am using robot_localization and navsat_transform to fuse RTK gps (dual antenna so we have orientation) and imu data. The issue that I am seeing is that when I run a bagfile twice with the same recorded input topics, I get slightly different outputs. Since the inputs are the same and the parameters for the EKF are the same, I would expect the output being exactly the same. Does anyone have any idea why might this be happening?
Thanks so much!
Results
I am attaching 3 images that show this behavior. The position in x and y are the odometry components from the output (/odometry/filtered/global) of the EKF. I use it for an application that requires cm level accuracy so accurate repeatability is really important. I am seeing difference of +-1cm average between 2 reprocessed sessions. Note that the robot starts moving at around sequence=10000, where the error increases. Even the timestamps of the messages are slightly different. I have tried to use f=50 and predict_to_current_time = false but same result. IMU is publishing at 50Hz, gps at 10Hz, heading at 5Hz.
Launch file
I use use_sime_time = true and --clock arg when using rosbag play.
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="map_odom" args="0 0 0 0 0 0 map odom" />
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_global_localization">
<rosparam command="load" file="$(find earth_rover_localization)/cfg/ekf_global_rover_localization.yaml" />
<remap from="/odometry/filtered" to="/odometry/filtered/global"/>
</node>
<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform" respawn="true" output="screen">
<param name="frequency" value="30"/>
<param name="delay" value="3.0"/>
<param name="magnetic_declination_radians" value="0.0"/>
<param name="yaw_offset" value="0"/>
<param name="zero_altitude" value="false"/>
<param name="broadcast_utm_transform" value="true"/>
<param name="publish_filtered_gps" value="true"/>
<param name="use_odometry_yaw" value="false"/>
<param name="wait_for_datum" value="true"/>
<rosparam command="load" file="$(find earth_rover_localization)/cfg/datum.yaml" />
<remap from="/odometry/filtered" to="/odometry/filtered/global"/>
<remap from="/gps/fix" to="/piksi_receiver/navsatfix_best_fix"/>
</node>
</launch>
cfg file:
The /heading
topic comes from having a dual antenna RTK GPS.
frequency: 60
sensor_timeout: 0.1
two_d_mode: true
transform_time_offset: 0.0
transform_timeout: 0.0
print_diagnostics: true
map_frame: map
odom_frame: odom
base_link_frame: scouting_base_link
world_frame: odom
predict_to_current_time: true
odom0: /odometry/gps
odom0_config: [true, true, true,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
odom0_queue_size: 0
odom0_nodelay: false
odom0_differential: false
odom0_relative: false
imu0: /imu
imu0_config: [false, false, false,
true, true, false,
false, false, false,
true, true, true,
true, false, false]
imu0_nodelay: false
imu0_differential: false
imu0_relative: false
imu0_queue_size: 5
imu0_remove_gravitational_acceleration: true
imu1: /heading
false, false, true,
false, false, false,
false, false, false,
false, false, false]
imu1_nodelay: false
imu1_differential: false
imu1_relative: false
imu1_queue_size: 0
imu1_remove_gravitational_acceleration: true
use_control: false
process_noise_covariance: [0.05, 0.05, 0.06, 0.03, 0.03, 0.06, 0.025, 0.025, 0.04, 0.01, 0.01, 0.02, 0.01, 0.01, 0.015] #diagonal
initial_estimate_covariance: [1e-6, 1e-6 ...
Also, I'm forgetting: does a queue size of 0 mean infinite for ROS subs? I'd just set those to a reasonable value (as many messages as you'd expect from that sensor in the time delta between updates).
Okay, I will do that. The EKF frequency is 60Hz and the highest sensor frequency is 50Hz so I think with a value of 2, it should be more than enough.