Ask Your Question
0

robot_localization IMU yaw velocity causes vertical drift

asked 2021-03-06 12:52:44 -0500

anonymous user

Anonymous

Hi,

I am using robot_localization's EKF node with my robot's wheel odometry and an IMU. My configuration file is the following:

odom_frame: odom
base_link_frame: base_link
world_frame: odom

two_d_mode: false
publish_tf: true

frequency: 50

odom0: /velocity_controller/odom
odom0_config: [false, false, false,
               false, false, false,
               true, true, false,
               false, false, true,
               false, false, false]
odom0_differential: false
odom0_queue_size: 10

imu0: /imu/data
imu0_config: [false, false, false,
              false, false, false,
              false, false, false,
              false, false, true,
              false, false, false]
imu0_differential: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: false

The wheel odometry data is in 2D, so I only use it's linear X and Y data along with it's yaw. For the IMU right now I only want to use the yaw velocity data.

The problem is that although I am only using 2D data, the filtered odometry's Z position accumulates drift over time. I have also noticed that it seems to accumulate drift in it's roll and pitch aswell. This is strange since they are supposed to be ignored according to my configuration file.

I have tried setting imu0_remove_gravitational_acceleration to both true and false but the result is the same.

I have not calibrated my IMU but since I am only using the yaw velocity it should not matter much.

Also, I realize that setting two_d_mode to true would solve the problem, but I feel like it should be working either way since I am only using 2D data. Is this a bug or is this a problem with my IMU data?

Another thing I have tried is to use the yaw position instead of the yaw velocity and it did not cause any drift problem

Thanks for the help

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-03-25 05:07:38 -0500

Tom Moore gravatar image

This is just how Kalman filters work.

In order for the filter to produce stable output, it needs a reference (measurement) for every pose variable, or at least the velocity for every pose variable. Otherwise, the covariance for the non-measured variables will explode, and the state estimate will become wildly unstable.

When you enable two_d_mode, the filter is internally generating 0 measurements with tiny covariances for all the 3D pose/velocity variables. This is admittedly a bit of a hack; we should really have a separate filter for the 2D case. But if you zero out all the 3D variables in the kinematic model, it ends up being the 2D unicycle model anyway. We just waste a lot of math.

In any case, the answer to your problem is to use 2D mode, or find a way to measure the 3D variables. If your robot needs to work on outdoor (non-planar) terrain, you can fuse the Z velocity from the wheel encoders, since it reports 0, which is true. Then you'd also need to fuse the 3D variables for your orientation from your IMU.

edit flag offensive delete link more

Your Answer

Please start posting anonymously - your entry will be published after you log in or create a new account.

Add Answer

Question Tools

2 followers

Stats

Asked: 2021-03-06 12:52:44 -0500

Seen: 66 times

Last updated: Mar 25