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

robot_localization how to handle accelerations when tilted

asked 2015-08-12 16:22:26 -0500

dan gravatar image

I have robot_localization working nicely (thanks to help from Tom Moore), feeding X velocity from wheel odometry and z angular velocity from a gyro. I also have a 3 axis accelerometer so I would like to add accelerations to the filter. However, I do not have an absolute orientation measurement, so I am having difficulty when the robot is slightly tilted, say when it is on a ramp. In that case, the X acceleration value has a gravity component which makes the filter's position output move even when the robot is just standing still on the ramp. Setting the "imu0_remove_gravitational_acceleration" to true does not help because I am not providing orientation data for the filter to use. Also, when setting that to true, even a small drift in the z accelerometer's gain (for example, due to a temperature change) causes the filter output Z position to fly off. I think that setting "two_d_mode" to true could stop that, but then it seems I will be unable to deal with the original problem of X acceleration due to gravity when sitting on a ramp?

I could provide full orientation data, but then I will be sending an absolute yaw component that is misleading, as it would simply be a derived value from the gyro and odometry velocity components. I could also provide just roll and pitch (from the base_link frame), but I don't know how this will work or even the best way to do that, e.g., set true for those values and false for the yaw value in robot_localization's sensor selection filter?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2015-08-13 08:58:53 -0500

Tom Moore gravatar image

You are correct in that you can't use the _remove_gravitational_acceleration parameter if your IMU doesn't provide orientation. However, note that yaw is not used in the calculation of the gravity vector correction. Imagine your robot is on a ramp and facing north. The gravity vector will be split into two components: X (forward) and Z (downward). Now imagine the ramp is facing east. The gravity vector still only comprises X and Z components of linear acceleration. Only your roll and pitch angles will make any difference in removing the gravity vector, so if you have orientation data, I'd include it in your IMU message.

A few notes:

  1. If your IMU is mounted in a non-neutral orientation (i.e., +X doesn't face the front of the robot, or +Y doesn't face the left), then you need to make sure you capture that orientation in the base_link->imu static transform.
  2. Make sure your IMU conforms to the standards laid out in the wiki.
  3. For your case, your robot can only attain +/- X velocity in the body frame (disregarding slippage or sudden drops do to, e.g., a curb). This is also true for linear acceleration. There's no sense in fusing Z or Y acceleration if the robot isn't going to be able to move instantaneously in those directions.
edit flag offensive delete link more

Comments

I could put in roll and pitch, but those would be derived from the acceleration values, so pitch would only be correct when we are not accelerating. When we accelerate forward, the pitch value would incorrectly increase. Is it still better to have those values incorporated into the filter?

dan gravatar image dan  ( 2015-08-13 14:19:40 -0500 )edit

One solution is to use the odometry vx to calculate X acceleration and subtract that component from the IMU total X acceleration to get the gravity component and calculate pitch from that. However, that introduces odometry noise into the pitch value, which impacts the filter's net IMU acceleration.

dan gravatar image dan  ( 2015-08-13 14:33:37 -0500 )edit

Acceleration data is typically pretty noisy anyway. As long as you properly handle your covariances, your solution may work. You do introduce a dependency on odometry data for the IMU by going that route, which you may or may not want to do.

Tom Moore gravatar image Tom Moore  ( 2015-08-13 14:39:26 -0500 )edit

In any case, since you're already measuring X velocity (and presumably with a small variance), your acceleration data shouldn't have too strong an effect on the state estimate. Any false velocity that you get from the acceleration integration will be corrected by direct velocity measurements.

Tom Moore gravatar image Tom Moore  ( 2015-08-13 14:41:55 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-08-12 16:22:26 -0500

Seen: 1,180 times

Last updated: Aug 13 '15