Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update Rep 145 (P II) #372

Open
wants to merge 17 commits into
base: master
Choose a base branch
from
Open
40 changes: 32 additions & 8 deletions rep-0145.rst
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ Data Reporting

* All data from a sensor should be published with respect to a single consistent sensor frame. If any data is reported in an inconsistent frame of reference relative to the other data, the driver must transform it into the sensor frame before publishing.

* Otherwise, all data should be published by the driver as it is reported by the device. Any subsequent modifications to the data (e.g. filtering, transformations) should be delegated to a downstream consumer of the data [3]_.
* Otherwise, all data should be published by the driver as it is reported by the device. Any subsequent modifications apart from vendor-specific SDK functionality to the data (e.g. filtering, transformations) should be delegated to a downstream consumer of the data [3]_.

* A prominent note should be made in the driver documentation regarding any internal data manipulation that does not comply with the requirements in this document.

Expand Down Expand Up @@ -93,26 +93,50 @@ Topics

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

#186 (comment) still applies here and hasn't been resolved:

Applying a transformation to IMU data requires transforming both the body and the world frames.

I still don't think transforming the world frame is correct here.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't see that sentence in this document or in the previous discussion. I'm not sure what change or issue you have is 😦

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The previous discussion:

@peci1

I never understood the idea of this paragraph. If I transform both the sensor frame and the reference frame, isn't the resulting data transform always identity? I imagine applying a transform to IMU data is like taking the IMU and rotating its body. I.e. only changing the sensor frame transform regarding the same reference frame. How would I rotate ENU by 90 degrees yaw?

@mintar

I agree this could be phrased better.

Here's a relevant email by @paulbovbel (the original author of REP 145) that probably explains his thinking when he wrote that paragraph: https://groups.google.com/g/ros-sig-drivers/c/Fb4cxdRqjlU/m/MwS3uZDyfkoJ

I suspect this paragraph is mixing two things, but I'm not 100% certain:

NED -> ENU conversion: You have to change body and world frames and the orientation.
transformation into a different body frame (e.g., from imu_link to base_link): You only have to change body frame and orientation; the world frame stays the same.

The following topics are expected to be common to many devices - an IMU device driver is expected to publish at least one. Note that some of these topics may be also published by support libraries, rather than the base driver implementation. All message types below are supplemented with a std_msgs/Header, containing time and coordinate frame information.

* `imu/data` (sensor_msgs/Imu)

* `imu/data_raw` (sensor_msgs/Imu)
- General consolidated sensor data containing `AngularVelocity`, `Attitude`, and `LinearAcceleration` published at the natural frequency of attitude estimation.

- Sensor output grouping accelerometer (`linear_acceleration`) and gyroscope (`angular_velocity`) data.
* `imu/angular_velocity` (sensor_msgs/AngularVelocity)

* `imu/data` (sensor_msgs/Imu)
- Sensor output containing gyroscope data.

* `imu/attitude` (sensor_msgs/Attitude)

- Sensor output containing information about the attitude estimation.

- Same as `imu/data_raw`, with an included quaternion orientation estimate (`orientation`).
* `imu/linear_acceleration` (sensor_msgs/LinearAcceleration)

- The sensor output of the measured linear acceleration.

* `imu/mag` (sensor_msgs/MagneticField)

- Sensor output containing magnetometer data.


All message types provide a covariance matrix (see REP 103 [1]_) alongside the data field (`*_covariance`). If the data's covariance is unknown, all elements of the covariance matrix should be set to 0, unless overridden by a parameter. If a data field is unreported, the first element (`0`) of the covariance matrix should be set to `-1`.
All message types provide a covariance matrix (see REP 103 [1]_) alongside the data field (`*_covariance`). If the data's covariance is unknown, all elements of the covariance matrix should be set to 0, unless overridden by a parameter. If a data field is unreported, the first element (`0`) of the covariance matrix should be set to `NaN`.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't quite get this. Should I imagine for example a sensor that can measure only in x-y, but not in z? The last sentence says I should set _covariance[0] to NaN, but the sensor could actually have a covariance for the x axis, which corresponds to _covariance[0].

Copy link
Contributor Author

@SteveMacenski SteveMacenski Mar 18, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This was language from the original one - I completely agree on closer examination I don't think this makes sense either.

I think we should change this to be:

  • Numbers reported if they got'm (current behavior)
  • If no information is known about anything covariance related, the first element (or all elements) set to NaN (new behavior - in case we have nothing, so we don't even try)
  • If a particular piece of information is not known, but others are known, set to 0 (current behavior)

Thoughts?

Copy link
Contributor

@peci1 peci1 Mar 24, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
All message types provide a covariance matrix (see REP 103 [1]_) alongside the data field (`*_covariance`). If the data's covariance is unknown, all elements of the covariance matrix should be set to 0, unless overridden by a parameter. If a data field is unreported, the first element (`0`) of the covariance matrix should be set to `NaN`.
All message types provide a 9-element (3x3 row-major) covariance matrix (see REP 103 [1]_) alongside the data field (`*_covariance`). If the covariance of some dimension is unknown, the corresponding diagonal element of the covariance matrix should be set to 0 (unless overridden by a parameter). If a dimension is unreported (i.e. the sensor only measures in one axis), the corresponding diagonal element of the covariance matrix should be set to `NaN`. Thus any algorithm processing the covariance should first check if the 3 diagonal terms are different from 0 and are not `NaN`.

What about this wording? Does it sound clearer?

The timestamp for these messages should reflect the best estimate of when the observation was made.
It is expected that downstream users may want to use data from multiple of these topics.

Namespacing
'''''''''''

By convention, IMU output topics are pushed down to a local namespace. The primary source of IMU data for a system is published in the `imu` namespace. Additional sources, such as secondary IMUs or unprocessed raw data should be published in alternative `imu_...` local namespaces. IMU driver implementations should take care to allow convenient remapping of the local namespace through a single remap argument (e.g. imu:=imu_raw), rather than separate remap calls for each topic.
By convention, IMU output topics are pushed down to a local namespace. The primary source of IMU data for a system is published in the `imu` namespace. Additional sources, such as secondary IMUs or unprocessed raw data should be published in alternative `imu_...` local namespaces. IMU driver implementations should take care to allow convenient remapping of the local namespace through a single remap argument (e.g. imu:=imu_raw), rather than separate remap calls for each topic. The following are some standard namespaces to represent certain types of data:

* `imu_raw`

- Containing topics of raw data

* `imu_unbiased`

- Containing topics of unbiased data

* `imu_biased`

- Containing topics of biased data

* `imu_compensated`

- Containing topics of gravity compensated data

Common Parameters
-----------------
Expand Down