Skip to content

Commit

Permalink
SCALED_IMUn: x,y,zmag units from mT to mgauss
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee authored and LorenzMeier committed Aug 8, 2019
1 parent 167f9ef commit 1b9c3d9
Showing 1 changed file with 9 additions and 9 deletions.
18 changes: 9 additions & 9 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3845,9 +3845,9 @@
<field type="int16_t" name="xgyro" units="mrad/s">Angular speed around X axis</field>
<field type="int16_t" name="ygyro" units="mrad/s">Angular speed around Y axis</field>
<field type="int16_t" name="zgyro" units="mrad/s">Angular speed around Z axis</field>
<field type="int16_t" name="xmag" units="mT">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mT">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mT">Z Magnetic field</field>
<field type="int16_t" name="xmag" units="mgauss">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mgauss">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mgauss">Z Magnetic field</field>
</message>
<message id="27" name="RAW_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
Expand Down Expand Up @@ -4716,9 +4716,9 @@
<field type="int16_t" name="xgyro" units="mrad/s">Angular speed around X axis</field>
<field type="int16_t" name="ygyro" units="mrad/s">Angular speed around Y axis</field>
<field type="int16_t" name="zgyro" units="mrad/s">Angular speed around Z axis</field>
<field type="int16_t" name="xmag" units="mT">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mT">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mT">Z Magnetic field</field>
<field type="int16_t" name="xmag" units="mgauss">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mgauss">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mgauss">Z Magnetic field</field>
</message>
<message id="117" name="LOG_REQUEST_LIST">
<description>Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called.</description>
Expand Down Expand Up @@ -4838,9 +4838,9 @@
<field type="int16_t" name="xgyro" units="mrad/s">Angular speed around X axis</field>
<field type="int16_t" name="ygyro" units="mrad/s">Angular speed around Y axis</field>
<field type="int16_t" name="zgyro" units="mrad/s">Angular speed around Z axis</field>
<field type="int16_t" name="xmag" units="mT">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mT">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mT">Z Magnetic field</field>
<field type="int16_t" name="xmag" units="mgauss">X Magnetic field</field>
<field type="int16_t" name="ymag" units="mgauss">Y Magnetic field</field>
<field type="int16_t" name="zmag" units="mgauss">Z Magnetic field</field>
</message>
<message id="130" name="DATA_TRANSMISSION_HANDSHAKE">
<description>Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.</description>
Expand Down

0 comments on commit 1b9c3d9

Please sign in to comment.