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

odometry from fusing odomtry and imu is not good

asked 2020-09-25 04:32:31 -0500

Fanny-one gravatar image

updated 2020-10-27 04:08:28 -0500

Hi, I'm trying use robot_localization to fuse odometry and imu of epson g365, But I meet some issues .I will provide my paramera here.

TF tree

image description

image description

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_timeout: 0.0
  print_diagnostics: true
  debug: false

  map_frame: map
  odom_frame: odom
  base_link_frame: base_link
  world_frame: odom

# -------------------------------------
# Wheel odometry:

  # odom0: /odom
  odom0: /wheel_odom
  odom0_config: [false, false, false,
                 false, false, false,
                 true,  true,  true,
                 false, false, true,
                 false, false, false]
  odom0_queue_size: 5
  odom0_nodelay: true
  odom0_differential: true
  odom0_relative: false
  #odom0_pose_rejection_threshold: 5
  #odom0_angular_velocity_rejection_threshold: 0.05
  #odom0_twist_rejection_threshold: 0.3

# --------------------------------------
# imu configure:

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

  # use_control: true
  # control_config: [true,true,false,false,false,true]

  process_noise_covariance: [0.05, 0,  0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,

0, 0.05, 0, 0, 0, 0, 0, 0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0.05, 0, 0, 0, 0, 0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0.03, 0, 0, 0, 0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0, 0.03, 0, 0, 0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0, 0, 0.06, 0, 0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0, 0, 0, 0.025,0, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0, 0, 0, 0, 0.0255, 0,  0, 0, 0, 0, 0, 0,

0, 0, 0, 0, 0, 0, 0, 0, 0.04, 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.01, 0, 0, 0, 0,

0, 0, 0, 0, 0, 0, 0, 0, 0,  0, 0, 0.02, 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.01, 0,

0, 0, 0, 0, 0, 0, 0, 0, 0,  0, 0, 0, 0, 0, 0.005]
  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, 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, 1e-9 , 0, 0, 0,    0, 0, 0, 0, 0 ...
(more)
edit retag flag offensive close merge delete

Comments

2

Please post your full config here (don't link to it) and also one sample sensor message from every sensor input.

Tom Moore gravatar image Tom Moore  ( 2020-10-02 05:04:01 -0500 )edit

Any update on this?

Tom Moore gravatar image Tom Moore  ( 2020-10-07 04:34:31 -0500 )edit

I have updated it, thank you very much.

Fanny-one gravatar image Fanny-one  ( 2020-10-26 00:31:01 -0500 )edit

Could you also post your TF tree as well as the frames that the imu and wheel_odom publish in? You can get a ascii representation of the tree from ros-blessed.

chfritz gravatar image chfritz  ( 2020-10-26 21:05:50 -0500 )edit

link text This is my tf tree. I'm sorry I added the link because I cannot successfully add a picture. thanks.

Fanny-one gravatar image Fanny-one  ( 2020-10-27 04:09:20 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-10-27 04:22:36 -0500

Tom Moore gravatar image

Issue 1

when the robot stands still, position x an y of odometry from robot_localization will still move a bit.

That's because you are fusing X and Y linear acceleration from your IMU, and that data will be very noisy and (in this case) strongly non-zero:

linear_acceleration: 
  x: 0.209036067128
  y: -0.0059831100516
  z: 9.8041009903

Issue 2

In my bag, I make the robot move forward 8m, but the result is about 7.91m. I think the error is too big and the imu has little effect. So I think my covariance maybe is not fit.

A couple responses here:

  1. All of your IMU covariances are invalid. A covariance matrix must be positive semidefinite, and therefore invertible. You cannot invert, for example, your angular velocity covariance:

    angular_velocity_covariance: [4e-08, 4e-08, 4e-08, 4e-08, 4e-08, 4e-08, 4e-08, 4e-08, 4e-08]
    

    I would make the diagonal values non-zero, and the rest zero. The values also seem a little _too_ low. Are they based on a spec?

  2. I think you might be expecting too much from the filter in this case. It's not magic, so if you feed it bad data, it will spit out bad data. Your IMU, even at rest, is reporting incorrect linear acceleration (assuming you posted an IMU message showing the robot at rest).

    Having said that, I think you could tune your covariances a bit and get some better results, even if you continue to fuse linear acceleration. You need to get accurate (and mathematically sound) covariance values for your IMU data and your wheel encoders. Just as a test, you can try increasing the IMU linear acceleration covariance (just the diagonals - put the rest to 0) and decreasing the wheel velocity covariance. You might also want to play with the filter's process noise covariance. Those values look pretty large to me.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2020-09-25 04:32:31 -0500

Seen: 347 times

Last updated: Oct 27 '20