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

What frame is sensor_msgs::Imu.orientation relative to?

asked 2012-12-20 04:09:34 -0600

Thomas D gravatar image

updated 2012-12-20 06:30:45 -0600

I have been looking at REP 103 and REP 105 along with nav_msgs::Odometry and sensor_msgs::Imu and I would like to know if there is a standard convention for the frame that sensor_msgs::Imu.orientation is relative to? It seems clear that nav_msgs::Odometry.pose.pose.orientation goes from header.frame_id to child_frame_id (or parent to child), but there is no child_frame_id in the sensor_msgs::Imu message and I do not see that described in either of the REPs. The two obvious choices are map and odom, but I don't know if one is preferred over the other.

I can make all of my own code consistent by picking either map or odom, but I worry about when I try to integrate third party packages. I would like to be able to simply subscribe to sensor_msgs::Imu messages and handle them in a generic way, but if there is no consistency then it's likely I would have to add extra code to look at the frame_id to find the source of the data and handle it differently based on the data source.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
16

answered 2012-12-20 13:28:27 -0600

Chad Rockey gravatar image

updated 2012-12-20 13:33:09 -0600

The ultimate answer to this is that the frame_id of the imu must be the frame in which it is mounted.


The followup is, of course, the problem and that is that IMUs have much more variety than say laser scanners. An example would be if a laser scanner did not scan in a regular angular increment, but instead varied the angle between beams. However, almost every laser scanner fits the LaserScan message. Every IMU fits the IMU message, but there are a few cases that are not made clear:

1) Orientation not provided. This is just some gyros and accelerometers, no fusion yet. Setting msg.orientation_covariance[0] = -1, will tell other software to not use the orientation.

2) Orientation integrated with drift from where the IMU started. This IMU doesn't even guarantee a known reference position. It's possible for the ROS software to startup after the IMU calibrated, so the reference position is completely unknown due to drift. These IMUs are uncommon, but essentially only integrate the gyros for orientation and do not use a gravity reference. This a purely inertial output and the best you could do in empty space. The issue using this type in ROS is that the message itself does not let you know that the orientation is relative rather than absolute.

This is the case that ROS handles today and is a form of dead reckoning/Odometry. Turtlebot and robot_pose_ekf all use the IMU only for the change in orientation, not the absolute orientation. This is ultimately safest, as any orientation can be fused in this manner. Unfortunately you lose the ability to remove drift, so more complicated approaches exist.

3) Orientation integrated with drift but pitch and roll referenced to gravity. This IMU is the most common. It uses the gyros to determine angle from startup, but references pitch and roll to gravity. The assumption here is that you will have to re-reference before you travel far enough for the Earth's gravity vector to not aligned down in your Cartesian frame. In this case, 'yaw' or 'heading' still drifts since the gravity component for yaw is 0, so you cannot determine absolute heading with only those 6 measurements.

This is shown in the following image. Initially (x, y, z), the cartesian coordinate frame is tangential to the Earth's surface. As the IMU travels very, very far (x', y', z'), the gravity reference drifts and no longer aligns with the z-axis. Where this becomes a problem depends on the specific application.

image description

4) Orientation reference to gravity and magnetic north. This is another very common sensor and typically adds two or more magnetometers to reference the heading to magnetic north. The problem using this method is that the frame must still be tangential to the Earth's surface and that the magnetic field has 'declination' that varies based on where the IMU is located on the Earth's surface. The message has no indicator of this at all.

5) Orientation fused ... (more)

edit flag offensive delete link more

Comments

I like D as the option. Could we use (semantic) topic conventions for this? Currently some sensors publish on /imu/raw for case 1 (no orientation, only ang. vel. and accelerations). Once it's fused, we can publish on /imu/data_XXX for the different use cases. Applications can remap if needed.

Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2012-12-20 13:48:01 -0600 )edit

That would be a good idea. Do you want to send an email on ros-sig-drivers? https://groups.google.com/forum/?fromgroups#!forum/ros-sig-drivers I've always wanted to publish android's linear_acceleration excluding gravity: http://developer.android.com/guide/topics/sensors/sensors_overview.html

Chad Rockey gravatar image Chad Rockey  ( 2012-12-20 18:04:15 -0600 )edit
3

answered 2012-12-20 06:19:33 -0600

There was some discussion about this on the mailing list. Tha API is a little unclear about this at the moment, but this seemed to be the consensus:

For an Imu message with frame_id = X:

  • the acceleration and velocities are measured in the frame X
  • the orientation is between a fixed inertial frame and X

Typically, X would be something like imu or imu_link.

The "fixed inertial frame" is implicitly assumed to be oriented in the same way as odom, map, or whatever top-level other fixed frame your application uses.

edit flag offensive delete link more

Comments

That's where my confusion lies. What if there is a rotation between odom and map? Then you have to be very careful about whether you say Imu orientation is relative to odom or map because they will give you different values. I see a lot of conditional statements for specific sensors resulting.

Thomas D gravatar image Thomas D  ( 2012-12-20 06:26:16 -0600 )edit

I agree. I'm guessing the assumption is that the inertial frame is oriented the same as your highest-level, truly "fixed" frame. So if you have both map and odom, that should be map. It's not very clear or elegant. Would you consider participating in the conversation I linked in the answer?

Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2012-12-20 07:00:23 -0600 )edit

That other link seems to be the appropriate place to continue this discussion. Thanks.

Thomas D gravatar image Thomas D  ( 2012-12-20 10:14:20 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2012-12-20 04:09:34 -0600

Seen: 8,088 times

Last updated: Dec 20 '12