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

robot_localization drift when using simulated roll and pitch

asked 2021-02-24 15:15:07 -0500

prarobo gravatar image

I am seeing a large drift in the position output (from local pose) of the robot when using a setup with a simulated imu and wheel encoder. I am using the robot_localization package to generate the local pose. In this same setup, if I set two_d_mode provided by robot_localization, I do not see this drift anymore. I would like to not zero out the roll and pitch by setting it to 2d mode. Any advice on how to fix this will be of great help to me. I have added the information corresponding to my setup below.

This is my robot_localization EKF config

map_frame: map 
odom_frame: odom
base_link_frame: base_footprint
world_frame: odom

debug: true
debug_out_file: localization_log.txt
reset_on_time_jump: true
dynamic_process_noise_covariance: true
print_diagnostics: true
publish_acceleration: false
transform_timeout: 0.0
two_d_mode: false
publish_tf: true
frequency: 30
predict_to_current_time: true
transform_time_offset: 0.1

odom0: $(arg wheel_odom_topic)
odom0_config: [false, false, true,  # X, Y, Z
               false, false, false,  # roll, pitch, yaw
               true,  true, false,  # X_dot, Y_dot, Z_dot
               false, false, false,  # roll_dot, pitch_dot, yaw_dot
               false, false, false]  # X_ddot, Y_ddot, Z_ddot
odom0_relative: false
odom0_nodelay: true

imu0: /$(arg robot_name)/filter_kvh_imu
imu0_config: [false, false, false,  # X, Y, Z
              true, true, true,   # roll, pitch, yaw
              false, false, false,  # X_dot, Y_dot, Z_dot
              false, false, false,  # roll_dot, pitch_dot, yaw_dot
              false, false, false]  # X_ddot, Y_ddot, Z_ddot
imu0_nodelay: true
imu0_relative: true
imu0_differential: false
imu0_remove_gravitational_acceleration: true

Example IMU message

header: 
  seq: 765
  stamp: 
    secs: 18
    nsecs: 100000000
  frame_id: "recbot0/imu_link"
orientation: 
  x: 0.000235189927955
  y: 0.00639060403184
  z: 2.23457272268e-06
  w: 0.999979552221
orientation_covariance: [1.0412328196584754e-10, 0.0, 0.0, 0.0, 1.0412328196584754e-10, 0.0, 0.0, 0.0, 1e-08]
angular_velocity: 
  x: 0.0
  y: 0.0
  z: 0.0
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration: 
  x: -0.125464739637
  y: 0.0044842163957
  z: 9.79935998913
linear_acceleration_covariance: [1e-08, 0.0, 0.0, 0.0, 1e-08, 0.0, 0.0, 0.0, 1e-08]

Example wheel odom message

header: 
  seq: 2086
  stamp: 
    secs: 114
    nsecs: 234000000
  frame_id: "recbot0/base_footprint"
child_frame_id: "recbot0/base_footprint"
pose: 
  pose: 
    position: 
      x: 0.0
      y: 0.0
      z: 0.0
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0
  covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
twist: 
  twist: 
    linear: 
      x: 1.49129708582e-10
      y: 0.0
      z: 0.0
    angular: 
      x: 0.0
      y: 0.0
      z: 0.0
  covariance: [0.001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 ...
(more)
edit retag flag offensive close merge delete

Comments

why do you even want to include roll and pitch? Does your robot drive on an uneven surface?

Other than that you are only giving data to roll and pitch from the imu and no other sensor. If you want to have roll and pitch in there i would assume that you need at least two sensors to measure the same. Then you could use the differential option so you can remove the noise.

I have never done this myself but i would probably mount two imu's in opposite orientations and map them to apply to rep 105 afterwards. This could help you with removing mounting errors like a crooked base plate.

Tristan9497 gravatar image Tristan9497  ( 2021-02-24 16:13:10 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-03-25 04:59:07 -0500

Tom Moore gravatar image

Thanks for including sensor messages. I'm assuming your application is a ground robot that works on outdoor terrain (or non-planar terrain, anyway).

In order for the filter's output pose to be stable, you need to be measuring either the pose or velocity (or both) for every pose variable. In your case, you are doing full 3D estimation, so you need a reference (measurement source) for X, Y, Z, roll, pitch, yaw, and/or their velocities.

In this case, you'll note that you are not measuring Z or Z velocity. Since the filter has no reference for Z, its Z variance (and its covariance with any correlated variables) will start to explode. This will cause horrible things to happen to your pose estimate, such as flying off into the sky.

The fix, in this case, should be straightforward. Your robot cannot instantly move upwards in Z, I assume (i.e., it can't fly) so your Z velocity is 0. Your wheel encoders are already reporting a Z velocity of 0, so:

  1. Fix your wheel encoder covariance so it contains non-zero variance for Y and Z velocity (this is kind of optional; the filter will handle the 0s and replace them with tiny values).
  2. Fuse Z velocity in your odom0_config.

Note that your Z position will slowly drift over time in this setup. For example, if you go up a big hill, turn around, and go back to the start point, your Z position will be near 0, but probably not exactly 0. That's just an expected side effect of only providing velocity.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-02-24 15:15:07 -0500

Seen: 266 times

Last updated: Mar 25 '21