Potential new messages for IMUs

444 views
Skip to first unread message

Tully Foote

unread,
Feb 27, 2015, 4:26:24 AM2/27/15
to ros-sig...@googlegroups.com, William Woodall
Hi everyone,

(tldr; See sketch of proposed messages to replace sensor_msgs/Ium at the bottom. )

After watching the discussions on REP 145 I think the underlying issue we're running into is that the Imu message is actually not clearly defined.

I spent quite a while with @wjwwood on the whiteboard and here's a summary of what we discussed.

We identified that we have several things which are being conflated currently. A lot of this is because the most common devices which have similar interfaces are mostly integrated IMU systems, and the current design built off of using the integrated sensors.

However stepping back there are actually two things contained in the current IMU message. There is an estimate of the current attitude, as well as the current accelerometer and gyro measurements.

These two forms of data are causing one of our problems in that one is world/semi-globally referenced and one is referenced to the sensor.

As we've talked earlier on the mailing list we could add a coordinate frame to the message to avoid some of this ambiguity. But we had preferred to not change the message and focus on building the standard with the message as is. However as we can't build a consensus of what the message represents among the people who use it the most, I think we should reconsider the overall message design.


Looking at the core conflict with the reference frames there are really two measurements which have been coupled, a AHRS position estimate and inertial measurements.

Thinking about these two messages, they are really only coupled when you have an integrated sensor, (which are commonly used) but are certainly not the only use case. And we already realized that they are separately referenced, so we suggest splitting the AHRS estimate be separated from the inertial measurements.

So looking specifically at the inertial measurements, there are two components, one angular velocities, and one linear accelerations. The are both functions of the sensor body, have xyz and covariance. The current message requires them both to be in the same coordinate frame, and published at the same frequency.

However except for the common integrated IMUs they may actually have different sensor frames, thus making each of them a stand alone message makes sense, with their own header. This also will enable discrete gyros or accelerometers to be integrated more easily. There is still a choice whether to couple the gyro and accelerations into the same message or separate messages in the default API. This is a question I think we can discuss subsequently. There are no problems of NED vs ENU here as everything is sensor referenced.

Returning to the AHRS fix. Overall there is the basic data representation, which I think the existing representation of orientation + covariance covers adequately. However for an AHRS fix there are actually two important coordinate frames. The most obvious one is the sensor_frame. This is where the sensor is located on the robot. The other important coordinate frame is the frame against which the orientation is being reported. I've drawn a small graphic below.


Overview of frames for AHRS

/map # semi-global reference
|
---> AHRF_fix_ned/enu
|
---> odom
       | ---> base_link
                 |------> imu_link(the frame in which the ahrs sensor is mounted, possibly anywere)


The data is relevant ot the semi-global frame. But when you want to render the data you want to know where the sensor is. And if the vehicle is very big you could do some tricks like triangulating between two ahrs sensors far apart to get an absolute position estimate. At this point we run into the NED vs ENU frames. Depending on whether the AHRS system has a absolute reference such as a magnetometer or not is important information as it will determine if the fix may drift like the odom coordinate frame (requiring a separate correlation estimation like localization), or should stay more or less fixed. It seems that although conventions for the frame_ids used in this case makes sense, also capturing the type of information in the AHRS message in a confirmed format would be valuable, which is why we added a reference_frame_type enum. It can capture both NED vs ENU and floating(relative to turn on) vs absolute.


Resultant proposed strawman:

**Default topic /imu/orientation
AHRS.msg
--------
Header header # world reference frame (NED or ENU)
Quaternion orientation
Float64[9] covariance  # xyz ypr
uint8 reference_frame_type # NED, ENU, NED_FLOATING, ENU_FLOATING (whether or not)
string sensor_frame # What coordinate frame the sensor/estimate is attached to on the robot. Useful for rendering etc.

** Default topic /imu/inertia
InertialMeasurements.msg
--------------------------------------
->AccelerationMeasuremt.msg
-->Header header
-->x,y.z + covariance
->GyroMeasurement.msg
--> Header
--> x,y,z + covariance


I haven't fully fleshed this out to have formal message definitions, but I wanted to get people's feedback on the idea of actually redoing the datatypes.

Tully

Martin Günther

unread,
Feb 27, 2015, 6:21:19 AM2/27/15
to ros-sig...@googlegroups.com
Hi Tully and William,

+100!

Thanks a lot for putting together that proposal, I think it finally
gives a clear definition of what those orientations really mean. The
main drawback of the current Imu message is that there is no way to
specify the AHRS reference frame and type.

Perhaps once this proposal is fleshed out and written down in a REP, we
could also add a standard way of mapping the new messages to the old
Imu message for backwards compatibility, by prescribing some default
assumptions that should be made for the fields that the Imu message is
missing?

Cheers,
Martin

Martin Günther

unread,
Feb 27, 2015, 7:12:29 AM2/27/15
to ros-sig...@googlegroups.com
On Fri, 27 Feb 2015 12:21:16 +0100
Martin Günther <martin.gu...@gmail.com> wrote:

> Perhaps once this proposal is fleshed out and written down in a REP,
> we could also add a standard way of mapping the new messages to the
> old Imu message for backwards compatibility, by prescribing some
> default assumptions that should be made for the fields that the Imu
> message is missing?

Perhaps to make this more concrete: The orientation field of an Imu
message should be interpreted with a reference_frame_type of
ENU_FLOATING and a reference frame of ahrs_fix_enu, or equivalently any
fixed frame with z pointing up (map/odom).

This is exactly the assumption about Imu messages that current
implementations make (e.g., robot_pose_ekf).

Note that this is also consistent with how I read the current proposal
of REP 145, which allows publishing in NED, but since we cannot specify
a true NED reference frame in the old Imu messages, it is required to
compensate for this by not publishing NED orientations in the true
sensor frame, but in one that's flipped on its head (imu_link_ned).

Of course, in the long run, the Imu message should be abandoned in
favor of the new proposal. The new proposal is much cleaner and
provides the option of drift-corrected IMU orientations.

Cheers,
Martin

Dereck Wonnacott

unread,
Feb 27, 2015, 8:41:50 AM2/27/15
to ros-sig...@googlegroups.com

With a few of the imus that I've worked with, the gyro has had an update rate that was significantly faster than the accelerometer.

Some of the imus that I have used also had magnetometers and barrometers. 

For these reasons I think it is best to publish individual messages for each sensor type rather than a combined message.

The downside is that if a particular sensor has all four sensor types, then there is unessisary duplication of the header data. However, it would provide more flexibility for the general case.

It would also allow users to use discreet sensors which all publish individual messages which could be read by some filtering node without the need to have an intermediate node to pack all of the data into one message at fixed intervals.

Just my two cents.

Regards,
Dereck Wonnacott

--
You received this message because you are subscribed to the Google Groups "ROS Drivers Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drive...@googlegroups.com.
To post to this group, send email to ros-sig...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ros-sig-drivers/CAM7qi7URh8qN1FRwNqOWrizkmVsn5ujzSMKZUBrYCLSvL6Cjag%40mail.gmail.com.
For more options, visit https://groups.google.com/d/optout.

Jack O'Quin

unread,
Feb 27, 2015, 11:24:57 AM2/27/15
to ros-sig...@googlegroups.com, William Woodall
On Fri, Feb 27, 2015 at 3:26 AM, Tully Foote <tfo...@osrfoundation.org> wrote:
Hi everyone,

(tldr; See sketch of proposed messages to replace sensor_msgs/Ium at the bottom. )

After watching the discussions on REP 145 I think the underlying issue we're running into is that the Imu message is actually not clearly defined.

I spent quite a while with @wjwwood on the whiteboard and here's a summary of what we discussed.

+1 to pursuing this new proposal
--
 joq

rbi...@cox.net

unread,
Feb 28, 2015, 6:53:56 PM2/28/15
to ros-sig...@googlegroups.com
 
Hi all,
 
Re Tully's suggestion,  separating the inertial and world frame data messages makes some sense.  However, I think separating accelerometers and gyros is overkill.  We are talking about an Inertial Measuring "Unit" here. All the definitions of IMU that I have found on the net say that a minimal IMU combines at least the accels and rate gyros in a single package.  If we are to consider separate accelerometer packages and gyro packages, we should just as well consider 3 separate accels and 3 separate gyros each of which could have its own frame.  It seems as if such rare cases could be left to custom drivers that might combine all the data into a common frame.
 
 
 

Mike Purvis

unread,
Feb 28, 2015, 8:33:23 PM2/28/15
to ros-sig...@googlegroups.com
I don't really feel qualified to speak to the technical merits of this, but I don't think it would be fair to ratify such a proposal without some upfront investment in tooling around it. For example, I feel it would be essential to have an interoperability node/library/package which can provide a transparent, bidirectional shim, as well as an Indigo- or even Hydro-compatible Gazebo plugin which publishes the new messages and can simulate the different operational modes the messages support.

FWIW, we have never found the IMU plugin from gazebo_ros_plugins usable— our standard robot simulators use the one from Hector. Maybe that could be the basis for the new implementation, rather than the current one?

Mike


On 27 February 2015 at 16:59, <rbi...@cox.net> wrote:
 
Hi all,
 
Re Tully's suggestion,  separating the inertial and world frame data messages makes some sense.  However, I think separating accelerometers and gyros is overkill.  We are talking about an Inertial Measuring "Unit" here. All the definitions of IMU that I have found on the net say that a minimal IMU combines at least the accels and rate gyros in a single package.  If we are to consider separate accelerometer packages and gyro packages, we should just as well consider 3 separate accels and 3 separate gyros each of which could have its own frame.  It seems as if such rare cases could be left to custom drivers that might combine all the data into a common frame.
 
 
 

--
You received this message because you are subscribed to the Google Groups "ROS Drivers Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drive...@googlegroups.com.
To post to this group, send email to ros-sig...@googlegroups.com.

Tom Moore

unread,
Mar 1, 2015, 1:52:54 PM3/1/15
to ros-sig...@googlegroups.com, wil...@osrfoundation.org
+1. I think this all looks great.

pbo...@clearpathrobotics.com

unread,
Mar 1, 2015, 2:18:20 PM3/1/15
to ros-sig...@googlegroups.com, wil...@osrfoundation.org
+1 for splitting out the sensor information from the attitude estimate. Why not break out accel, mag, and gyro data into three separate topics, each with type Vector3WithCovarianceStamped? Consumers interested in a subset of the data would receive information at the fastest rate possible, and consumers interested in all the data can still use the synchronization mechanisms in message_filters.

---

Martin, I would argue that for NED IMUs, the 'flipped' imu_link_ned IS the true sensor frame, since that is also the frame in which the internal device components are reporting. Otherwise there is no way to consistently agree on which 'side' of the sensor is the front, the right, etc.

---

I'm not 100% on the additional information. Including reference_frame_type (NED/ENU) information makes sense, though I feel breaking out a bool yaw_fixed/floating flag would make more sense for downstream consumers than having 4 different reference frame types.

Creating a separate transform frame for enu/ned reference in TF seems problematic. Who would be the authority on the tf? Probably not the hardware driver. If the user is required to configure the frame, this approach adds a lot of integration overhead for essentially redundant information.

---

On the issue of backwards compatibility and tooling, perhaps a change of this magnitude would be better suited to be included in ROS 2?

Tully Foote

unread,
Mar 2, 2015, 3:02:28 AM3/2/15
to ros-sig...@googlegroups.com
Thanks for the feedback.

@Martin, I've tried to roll your feedback into the backwards compatibility.

@Dereck, I've fully separated the messages to allow for different update rates and potentially discrete units.

@rbirac I think that having the separate messages will support multiple instances of any sensor.

@Mike I agree backwards compatiblity is important. I've added a section at the bottom that there would be two nodes for doing this and a first spec of their behavior.

@Paul The datatypes will be very similar but should actually be different types, as they are not interchangeable. The reason for calling out ENU vs NED is that it's a propery of the data reported, and the frame_id names are conventions and we do not want people doing conditional logic based on the substrings in frame_ids. I could consider splitting the NED/ENU vs Floating Yaw out, but chose the single enum for compactness. If we can come up with more things we need to capture we can definitely extend it, but if we only have 4 I'd suggest keeping it as a single enum. Re: ROS2.0 although it will be a change in API the core concepts will stay the same and ROS 1.0 and ROS 2.0 systems or subsystems will need to interoperate so we will face the same problems.


Here's a slightly more concrete proposal bringing in the comments. There is still a bunch of documentation/comments needed. And if we document the interface fully in a REP it can provide a much clearer picture of how we expect to use it. Also it was good to find the MagneticField message which is appropriate for a magnetometer to use already is already reviewed and follows the same approach.

Please take some time to also think about use cases where this will not be enough.

Tully

Messages
========

The existing message:

Imu.msg
-------

Header header

geometry_msgs/Quaternion orientation
float64[9] orientation_covariance # Row major about x, y, z axes

geometry_msgs/Vector3 angular_velocity
float64[9] angular_velocity_covariance # Row major about x, y, z axes

geometry_msgs/Vector3 linear_acceleration
float64[9] linear_acceleration_covariance # Row major x, y z


Proposed new messages:


Ahrs.msg
--------

int8 ENU=1
int8 NED=2
int8 ENU_FLOATING=3
int8 NED_FLOATING=4

std_msgs/Header header

geometry_msgs/Quaternion orientation
float64[9] orientation_covariance # Row major about x, y, z axes

uint8 reference_frame_type # NED, ENU, NED_FLOATING, ENU_FLOATING
string sensor_frame # The coordinate frame in the system of the observation. (Alternative PoseStamped)

LinearAcceleration.msg
----------------------
std_msgs/Header header
geometry_msgs/Vector3 linear_acceleration
float64[9] linear_acceleration_covariance # Row major x, y z

AngularVelocity.msg
---------------

std_msgs/Header header

geometry_msgs/Vector3 angular_velocity
float64[9] angular_velocity_covariance # Row major about x, y, z axes


sensor_msgs/MagneticField.msg (Already exists, parallel to above. http://docs.ros.org/api/sensor_msgs/html/msg/MagneticField.html)



Standard Interface:

/imu/ahrs sensor_msgs/Ahrs
/imu/linear_acceleration sensor_msgs/LinearAcceleration
/imu/angular_velocity sensor_msgs/AngularVelocity
/imu/magnetic_field sensor_msgs/MagneticField



Backwards compatibility.

For backwards compatibility two nodes will be provided which can map forwards or backwards. Between the new and old formats.

The forwards node will autofill in the extra headers with the example header, and have parameters to override the fields. Default would be ENU_FLOATING
The backwards node will collect the 3 messages with a MessageFilter  (configurable approximate or exact) and build the Imu Message. Using the acceleration header by default, available for parameterization.

The Imu message will remain in the package, but deprecated and recommended to use the new format.




--
You received this message because you are subscribed to the Google Groups "ROS Drivers Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drive...@googlegroups.com.
To post to this group, send email to ros-sig...@googlegroups.com.

Chad Rockey

unread,
Mar 2, 2015, 6:08:36 PM3/2/15
to ros-sig...@googlegroups.com
Splitting the messages is really quite tricky.  The topic synchronizers are not necessarily the easiest things to use.  The default TCP nodelay value also hurts IMUs since it batches up transmission.

If the messages are to be split up, I'd highly recommend an imu_transport library (with simple nodes as Tully described that simply launch thin wrappers of the library) with an ImuSubscriber that does all of the hard work of approximate or exact time synchronizing and has end user focused callback signatures (accel + gyro, gyro + mag, accel + mag, and accel + gyro + mag).  I'd had pretty rubbish luck in the past synchronizing topics, so we should aim to make this as easy as possible.  This would also be a good place to implement the backwards compatibility conversions -> a publisher for sensor_msgs/Imu (with optional mag topic) that publishes the accel + gyro + ahrs messages) and a subscriber callback that combines some set of ahrs, accel, and gyro into sensor_msgs/Imu.

laser_proc is probably a good reference.  It has a similar use case (aggregating conversions of multi echo laserscans into single echo scans), is used as a library by urg_node, but also includes nodelet and node versions:
https://github.com/ros-perception/laser_proc  (In addition to the synchronization similar to image_transport)

+1 to the AHRS message, the ambiguity of the previous message stopped a lot of previous efforts.

+0 to splitting the messages, the advantages are good: separate sensor streams, varying rates, data efficiency.

---------

One other question, what does the sensor_frame_id in the AHRS message represent?  It could be possible to generate an AHRS from multiple sensor frames (accel needs to be biased based on turning, gyro can be anywhere in the system, magnetometers need to be away from interference).  What does the frame_id in the header represent?  Will it most commonly be either base_link (if computed from transformed data) or imu_link?

Jack O'Quin

unread,
Mar 2, 2015, 7:02:09 PM3/2/15
to ros-sig...@googlegroups.com
Overall, I really like this proposal.

But, I seriously dislike naming a message type "Ahrs". "Imu" was bad enough, but was at least a fairly widely-known acronym. "InertialMeasurement" would have been clearer.

While AHRS is probably descriptive and might be recognizable to the avionics community, it is *not* a widely-known acronym.

I suggest something a bit more human-readable, maybe AttitudeAndHeading, to describe the meaning of the message and not the device that produces it. 

pbo...@clearpathrobotics.com

unread,
Mar 3, 2015, 2:54:40 PM3/3/15
to ros-sig...@googlegroups.com
@Tully, what about the additional fix_enu/ned frame required with header.frame? 

Since the ground reference frame is also encoded in the AHRS data with 'reference_frame_type', one piece of information seems redundant. Also it seems to break the fixed vs. floating IMU idea, since the orientation wouldn't represent header.frame->sensor_frame for floating type IMUs.

pbo...@clearpathrobotics.com

unread,
Mar 3, 2015, 3:00:04 PM3/3/15
to ros-sig...@googlegroups.com
In principle, what the downstream consumers are probably interested in is an orientation estimate between one frame and another coming out of the IMU pipeline.

Would it make sense to delegate this to a downstream node, which takes in Ahrs.msg, processes the ENU/NED/floating params, and spits out an OrientationWithCovarianceStamped type message? There would have to be some logic built in to determine if the header.frame is bound to map/map_ned, or only gravity-fixed to map/map_ned and obtain a yaw orientation from a power-on position (odom).

Tully Foote

unread,
Mar 6, 2015, 2:10:11 PM3/6/15
to ros-sig...@googlegroups.com
Hi Paul,

As you mention the reference_frame_type can be redundant with the ground_reference_frame. However in the case of a floating reference frame, I can see several use cases where the parent coordinate frame is not attached to the same tf tree(probably to anything).

If you want to ground a floating estimate, as you mention, a separate process can be started which will estimate the drift in the ground_reference_frame. This is exactly the same approach we use with localization to estimate the transform between odom and map. In this case the data is not redundant but is information which is important for the estimator to have available to accurately do it's job.

@Jack

I agree Ahrs is a little odd to reference the device. AttitudeAndHeading seems to be pretty good, it's long but specific. Depending on your definition of attitude it's redundant and we could truncate it to just Attitude using the definition which includes all three axes.

Tully


--
You received this message because you are subscribed to the Google Groups "ROS Drivers Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drive...@googlegroups.com.
To post to this group, send email to ros-sig...@googlegroups.com.

Jack O'Quin

unread,
Mar 6, 2015, 3:05:08 PM3/6/15
to ros-sig...@googlegroups.com
On Fri, Mar 6, 2015 at 1:09 PM, Tully Foote <tfo...@osrfoundation.org> wrote:
Hi Paul,

As you mention the reference_frame_type can be redundant with the ground_reference_frame. However in the case of a floating reference frame, I can see several use cases where the parent coordinate frame is not attached to the same tf tree(probably to anything).

If you want to ground a floating estimate, as you mention, a separate process can be started which will estimate the drift in the ground_reference_frame. This is exactly the same approach we use with localization to estimate the transform between odom and map. In this case the data is not redundant but is information which is important for the estimator to have available to accurately do it's job.

I am unclear about this concept of a floating reference frame. I understand the map -> odom example, where localization periodically publishes updates.

Are you thinking of similar periodic adjustments for a Cartesian system aligned with local gravity? Robots travelling long distances need to adjust for the curvature of the Earth, eventually.
 
@Jack

I agree Ahrs is a little odd to reference the device. AttitudeAndHeading seems to be pretty good, it's long but specific. Depending on your definition of attitude it's redundant and we could truncate it to just Attitude using the definition which includes all three axes. 

+1 for "Attitude". 

The definition will clearly be three-dimensional, which should eliminate any ambiguity. 
--
 joq

Tully Foote

unread,
Mar 6, 2015, 7:57:03 PM3/6/15
to ros-sig...@googlegroups.com
On Fri, Mar 6, 2015 at 12:05 PM, Jack O'Quin <jack....@gmail.com> wrote:

On Fri, Mar 6, 2015 at 1:09 PM, Tully Foote <tfo...@osrfoundation.org> wrote:
Hi Paul,

As you mention the reference_frame_type can be redundant with the ground_reference_frame. However in the case of a floating reference frame, I can see several use cases where the parent coordinate frame is not attached to the same tf tree(probably to anything).

If you want to ground a floating estimate, as you mention, a separate process can be started which will estimate the drift in the ground_reference_frame. This is exactly the same approach we use with localization to estimate the transform between odom and map. In this case the data is not redundant but is information which is important for the estimator to have available to accurately do it's job.

I am unclear about this concept of a floating reference frame. I understand the map -> odom example, where localization periodically publishes updates.

Are you thinking of similar periodic adjustments for a Cartesian system aligned with local gravity? Robots travelling long distances need to adjust for the curvature of the Earth, eventually.

If you do not have an absolute reference for heading(such as a magnetometery) your heading according to the integrated imu/gyros will slowly drift, just like your odometry drifts over time. Pitch and roll can use logic on the accelerometer's gravity vector to correct most of the time, but yaw cannot do that without another data source. So in the same way that localization provides a low frequency estimate of the drift in odom vs map as well as estimate the initial orientation at turn on, since without a magnetometer(or high precision gyro capaible of auto-gyroing) at turn on the heading is unknown. There could be a similar process which corrects for the drift in yaw angle, based on externally referenced landmarks or systems without requiring the AHRS to take another input, or update past estimates.

I hadn't thought of this correcting for curvature of the earth, but it's possible that this could be used that way as well.

Tully
 
 
@Jack

I agree Ahrs is a little odd to reference the device. AttitudeAndHeading seems to be pretty good, it's long but specific. Depending on your definition of attitude it's redundant and we could truncate it to just Attitude using the definition which includes all three axes. 

+1 for "Attitude". 

The definition will clearly be three-dimensional, which should eliminate any ambiguity. 
--
 joq

--
You received this message because you are subscribed to the Google Groups "ROS Drivers Special Interest Group" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drive...@googlegroups.com.
To post to this group, send email to ros-sig...@googlegroups.com.

Paul Bovbel

unread,
Mar 9, 2015, 10:05:55 PM3/9/15
to ros-sig...@googlegroups.com
Thank you, while having a disconnected frame seems a little strange, the odometry/localization analogy makes it more clear.

What's the connection between this proposal and my draft for REP 145? Would you want to roll these message changes into it? How much of the tooling would have to be in place before the REP could go into effect?

Tully Foote

unread,
Mar 9, 2015, 11:19:19 PM3/9/15
to ros-sig...@googlegroups.com
On Mon, Mar 9, 2015 at 7:05 PM, Paul Bovbel <pa...@bovbel.com> wrote:
Thank you, while having a disconnected frame seems a little strange, the odometry/localization analogy makes it more clear.

What's the connection between this proposal and my draft for REP 145? Would you want to roll these message changes into it? How much of the tooling would have to be in place before the REP could go into effect?

I think that rolling this into REP 145 would be good. That way we can have one canonical reference for inertial measurements.

The minimum toolchain for this to be finalized would be to have python scripts which could convert from the old format to the new format, and one to go the other way. There's a little bit of syncronnization required but otherwise I'd hope they would be a few dozen lines of python each, or possibly one script with arguments to map either way.

That would only be needed for it to be finalized. we could approve the draft before fully implementing the solution.

Tully
 

Tully Foote

unread,
Mar 10, 2017, 7:24:47 PM3/10/17
to ROS Drivers Special Interest Group
There's been a little bit of traffic on REP 145 proposal and I've created a PR with the proposed new messages. 

To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-drivers+unsubscribe@googlegroups.com.
To post to this group, send email to ros-sig-drivers@googlegroups.com.

Tony Baltovski

unread,
Jul 27, 2017, 4:27:34 PM7/27/17
to ROS Drivers Special Interest Group
Could we add a raw IMU message that combines the magnetometer, gyroscope and accelerometer?  I believe these messages would generally be used together. All readings would be about the sensor frame.

Martin Günther

unread,
Aug 8, 2017, 6:35:21 AM8/8/17
to ROS Drivers Special Interest Group
Hi Tony,

I think the reason for splitting this into separate messages was that the messages can come in at a different rate:

https://groups.google.com/d/msg/ros-sig-drivers/2NvgNBOjcFQ/iXVKGv0PlFMJ

So there are two ways to handle this:

1. Publish each message separately
2. Publish a combined message, with some flags that specify which fields are valid or not.

Both have their ups and downs: (1) creates a headache trying to synchronize the different topics, *especially* when they don't arrive at the same rate; (2) is ugly and prone to bugs (you always have to remember to check whether a field is valid before reading it).

The current PR (https://github.com/ros/common_msgs/pull/101) chose variant (1). No matter which variant we pick, I strongly believe there should be only one canonical way.

Perhaps this discussion should continue on the GitHub PR?

Cheers,
Martin
Reply all
Reply to author
Forward
0 new messages