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

IMU message definition

asked 2015-01-06 16:18:30 -0600

Alex Brown gravatar image

updated 2015-01-07 01:42:57 -0600

gvdhoorn gravatar image

Hi all,

I am working on a driver for the CH Robotics UM7 Inertial Measuring Unit. It is becoming apparent that there are some differences of opinion on how IMU data is to be interpreted for the ROS system.

Following is my opinion on how it should be done, hoping for some discussion confirming or correcting my understanding.

  1. An IMU is mounted in a fixed location and orientation relative to the vehicle. It uses a body axes coordinate system. REP –103 defines these axes as: x = forward, y = left, and z = up.

    Forward should be interpreted as being pointed in the “forward” vehicle direction of motion.

    Left is lateral motion perpendicular to the X axis and pointed toward the left.

    Up is directly away from the Earth’s center.

  2. Only the Z axis has a relationship to the outside world and is usually determined using accelerometers that measure the direction of gravity during unaccelerated motion. The X and Y axes, being orthogonal to the Z axis, are tangent to an idealized Earth’s surface but have no specified direction relative to the Earth.

  3. If the vehicle is level on the Earth’s surface, the X and Y accelerometers should report about 0 m/sec^2 and the Z axis accel should be approx +9.8 m/sec^2 reflecting an apparent upward acceleration away from gravity force.

  4. The rate gyros should be in accordance with the right hand rule as stated in REP –103.

    Rotation about the Y axis (pitch motion) should be positive in the nose down direction.

    Rotation about the X axis (roll motion) should be positive for right side down motion.

    Rotation about the Z axis (yaw) should be positive for CCW rotation looking down on the vehicle.

  5. An IMU will commonly calculate attitude information using its rate gyro and accelerometer data. Such attitude data, whether in the form of Euler angles, Quaternions or other means should be with respect to the body axes and polarities are the same as for the rate gyros above. Data values should vary over the range of +/- pi radians.

  6. IMUs also commonly provide magnetometer and/or compass information. For ROS, such data should reflect the direction of North relative to X axis. I.e. if the robot is pointed northeast, a compass reading should be –pi/4. (note: the preceding is a strawman since I don’t have a firm opinion) Range should be +/- pi. Magnetometer data should also indicate North with respect to the body axes.
    An IMU often provides an optional feature in which the zero angle of yaw is set and maintained at the North direction as indicated by the magnetometer. This is a convenience to the user since it provides long term stability of the yaw angle as opposed to continuous integrator drift. It does not convert the IMU into an NED (or ENU) system. A driver should allow selection of this option or not. .

  7. Use of either NED or ENU navigation coordinates has no effect on ...

(more)
edit retag flag offensive close merge delete

Comments

1

I missed one of the most important issues: Most IMU sensors provide data in an X (forward), Y(right) and Z(down) coordinates. The proper transformation to ROS coordinates is a 180 degree rotation about the X axis, or more simply, negate (change sign) of Y and Z.

Alex Brown gravatar image Alex Brown  ( 2015-01-07 08:44:23 -0600 )edit

Agree, but as long as it's a right-handed coordinate system, it doesn't matter. Where "up" is is defined by the IMU output and not where the screws are. If you mount the IMU "upside down" on a robot, you can reflect that in the robot's URDF.

Martin Günther gravatar image Martin Günther  ( 2015-01-08 10:56:03 -0600 )edit

Ah, but for we people who build simpler robots, we use the data directly with no URDF transformations. So it only works one way.

Alex Brown gravatar image Alex Brown  ( 2015-01-09 15:41:15 -0600 )edit

Due to different mounting positions the IMU message should have no concept of "forward vehicle direction of motion" or any other vehicle characteristics. That would imply that the source code would have to be modified if the IMU was mounted in any position other than that assumed by the driver.

Thomas D gravatar image Thomas D  ( 2015-01-12 10:23:45 -0600 )edit

I think I agree. The IMU itself has no concept of mounting. But the robot has to know the transform between an arbitrary mounting orientation and the robot. Specifying/suggesting a standard location eliminates the need for a transform. Or correct it in the URDF as martin suggests

Alex Brown gravatar image Alex Brown  ( 2015-01-12 14:14:33 -0600 )edit

Was #6 ever solved? What is the usual best practice for IMUs with magnetometers? My IMU orientation vector is relative to earth, but angular velocity and acceleration are relative to the IMU frame. How do I rectify this in a single message, which obviously can't live in two frames?

natejgardner gravatar image natejgardner  ( 2017-05-23 23:43:55 -0600 )edit

4 Answers

Sort by » oldest newest most voted
0

answered 2015-03-09 17:23:04 -0600

tfoote gravatar image

ROS REP 145 is under review to try to resolve some of these issues: PR discussion https://github.com/ros-infrastructure...

Future URL: http://www.ros.org/reps/rep-0145.html

edit flag offensive delete link more
4

answered 2015-01-07 08:29:45 -0600

updated 2015-02-11 06:53:08 -0600

Fully agree with all of your points.

Perhaps you could also have a look at the imu_tools/imu_filter_madgwick package. You only need to provide the angular velocity and linear acceleration values from your device (optionally also magnetometer readings), and they will be fused to arrive at an orientation that follows the standards you outlined above.

Edit in response to Alex's comment:

I guess there's something wrong with what you visualize, but to be sure, I first tested that the IMU I use (Phidgets Spatial 3/3/3) actually follows the conventions you outlined, and it does (all on the imu/data_raw topic):

angular_velcocity:

  • Rotation about the Y axis (pitch motion) is positive in the nose down direction.
  • Rotation about the X axis (roll motion) is positive for right side down motion.
  • Rotation about the Z axis (yaw) is positive for CCW rotation looking down on the vehicle.

linear_acceleration:

  • When stationary, x and y are around 0, z is around +9.8. All increase when jerked into the direction of their respective axis.

This leaves the visualization part. What I do is:

  1. Launch this imu.launch file. The file contains both the IMU driver and the imu filter node. Note that I set publish_tf to false, since IIRC it was either wrong or at least misleading, and that I set the fixed frame to imu.
  2. Run rviz, set the fixed frame to imu and add a visualization of type rviz_imu_plugin (part of the imu_tools package). Set imu/data as the input topic.
  3. Run rqt_plot and plot imu/data_raw/angular_velocity and imu/data_raw/linear_acceleration.

Hope this helps!

edit flag offensive delete link more

Comments

I installed the filter and remapped my driver output to imu/data_raw. The orientation on the filter's imu/data topic closely tracks my drivers output, but all opposite polarity. Does this make any sense to you? I verified that topics are coming from driver & filter respectively.

Alex Brown gravatar image Alex Brown  ( 2015-01-07 14:26:52 -0600 )edit

See update.

Martin Günther gravatar image Martin Günther  ( 2015-01-08 10:57:07 -0600 )edit

Can't get RVIZ to work, not even rqt_plot which won't accept topics in command line or gui. It used to! But, for some reason, the imu/data from the filter is now in agreement with the imu/data_raw from my driver. rates, accels & orientation. I don't know what happened before.

Alex Brown gravatar image Alex Brown  ( 2015-01-10 10:20:47 -0600 )edit

hey Martin, I'm also using the Phidgets Spatial 3/3/3 1042 , and I'm a little bit confused regarding the expected variations in accelerations and velocities when moving it as you described. (0 1 2) are respectively (x y z) ? what neutral position you are using?

Jasmin gravatar image Jasmin  ( 2017-02-27 04:18:26 -0600 )edit
4

answered 2015-01-07 07:38:25 -0600

Tom Moore gravatar image

I think I agree on all your points, but let's use an example to test: consider the case where we roll the IMU in the positive direction (so roll is +90 degrees), and then, while it is on its side, rotate it counter-clockwise 90 degrees. In other words, I want to do an extrinsic rotation of the IMU of +90 degrees of roll, then +90 degrees of yaw (with the intrinsic, IMU-frame rotation being +90 degrees roll, +90 degrees pitch). What do you expect the IMU to read for (a) orientation and (b) rotation rate? For (a), I expect the IMU to read +90 degrees roll, and +90 degrees yaw. For (b), while we are rolling it, I expect to see positive roll rate, and then when we carry out the second rotation, I expect to see positive pitch rate.

edit flag offensive delete link more

Comments

+1. Have you found any drivers (or simulated IMUs) where this does not take place?

paulbovbel gravatar image paulbovbel  ( 2015-01-09 14:09:31 -0600 )edit

I'm pretty sure there's an issue with the hector_gazebo_plugins simulated IMU.

Tom Moore gravatar image Tom Moore  ( 2015-01-12 14:01:15 -0600 )edit
4

answered 2015-01-07 12:31:24 -0600

paulbovbel gravatar image

updated 2015-01-09 14:14:13 -0600

On board with all of the above.

Regarding your comment: many/most IMUs have a reference orientation shown on the device (e.g. http://www.ecnmag.com/sites/ecnmag.co... ). I think it would make sense to output the orientation in terms of the 'orientation of the reference frame in the world frame'. Correspondingly, we should output the angular_velocity and acceleration in this reference frame as well.

Counterintuitively, the um6 driver manipulates the data internally ( https://github.com/ros-drivers/um6/bl... ), with the goal of providing a more intuitive IMU orientation (ENU instead of NED). I think this kind of hidden-transformation adds confusion instead - the data frame no longer matches the reference image on the device.

I think it makes sense to leave setting up a proper base_link->imu_link transform to whoever is integrating the IMU on the robot. The only time it would be appropriate to do a driver-side transform would be to convert from left-handed to right-handed.

--- EDIT

I think a REP (amendment) would go a long way to reinforcing standards for IMU output, particularly regarding orientation data in the world-fixed and rotation/acceleration data in the device's reference frame, the adherence to right-handedness in the rotations, and the orientation of the device's acceleration vector due to gravity (up not down).

edit flag offensive delete link more

Comments

In my experience designing commercial aircraft autopilots, acceleration and angular rate signals were always in the aircraft body axis. I think your suggestion perhaps makes more sense for a navigation device using the data; which could make the transform itself.

Alex Brown gravatar image Alex Brown  ( 2015-01-07 14:50:07 -0600 )edit

I'd prefer to see the orientation reported in a world-fixed frame, and the angular velocity and acceleration reported in the IMU's body frame. The Odometry message handles its orientation and angular velocity this way (pose in one frame, twist in another).

Tom Moore gravatar image Tom Moore  ( 2015-01-08 08:06:34 -0600 )edit

I think that if you chose to use the mag update option, which slaves the yaw axis to magnetic north, you pretty much have a world-fixed frame. Does this work for you?

Alex Brown gravatar image Alex Brown  ( 2015-01-08 10:12:45 -0600 )edit

Sorry, I'm referring not to the UM7 specifically, but to the interpretation of IMU data within ROS.

Tom Moore gravatar image Tom Moore  ( 2015-01-08 11:43:51 -0600 )edit

Tom, that makes sense, and I think what I stated lines up with that. My point was to reinforce that the velocity and acceleration data should be output in the reference frame of the device, and not in an arbitrary 'ROS friendly' frame such as 'device is right side up'.

paulbovbel gravatar image paulbovbel  ( 2015-01-09 14:10:53 -0600 )edit

This has only been an issue in the UM6. The microstrain issues you have found seem to be related to programmer error, or perhaps incompatibilities between sensors. I'm still waiting to get a GX2 from out of our PR2.

paulbovbel gravatar image paulbovbel  ( 2015-01-09 14:12:14 -0600 )edit

Perhaps I'm confused. Are you proposing that the IMU driver receive additional data so that it knows the IMU orientation with respect to an external world frame?

Alex Brown gravatar image Alex Brown  ( 2015-01-09 15:45:08 -0600 )edit

Tom, I just got it , I think. Your last comment about not referring to the UM7 meant that its implementation is satisfactory; and that other IMUs should have the same. I'd agree, but it should be optional. My indoor use requires that mag update be off to avoid magnetic influences..

Alex Brown gravatar image Alex Brown  ( 2015-01-10 09:01:05 -0600 )edit

Question Tools

4 followers

Stats

Asked: 2015-01-06 16:18:30 -0600

Seen: 8,293 times

Last updated: Mar 09 '15