Skip to content

Commit 5373281

Browse files
build: patches: Move more calibration messages to common
Signed-off-by: Patrick José Pereira <[email protected]>
1 parent 291fc5b commit 5373281

File tree

1 file changed

+72
-0
lines changed

1 file changed

+72
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
2+
index 1ccad646..ed6ba5f9 100644
3+
--- a/message_definitions/v1.0/common.xml
4+
+++ b/message_definitions/v1.0/common.xml
5+
@@ -2702,6 +2702,67 @@
6+
<param index="6">User defined</param>
7+
<param index="7">User defined</param>
8+
</entry>
9+
+ <entry value="42004" name="MAV_CMD_FIXED_MAG_CAL">
10+
+ <description>Magnetometer calibration based on fixed position
11+
+ in earth field given by inclination, declination and intensity.</description>
12+
+ <param index="1">MagDeclinationDegrees.</param>
13+
+ <param index="2">MagInclinationDegrees.</param>
14+
+ <param index="3">MagIntensityMilliGauss.</param>
15+
+ <param index="4">YawDegrees.</param>
16+
+ <param index="5">Empty.</param>
17+
+ <param index="6">Empty.</param>
18+
+ <param index="7">Empty.</param>
19+
+ </entry>
20+
+ <entry value="42005" name="MAV_CMD_FIXED_MAG_CAL_FIELD">
21+
+ <description>Magnetometer calibration based on fixed expected field values in milliGauss.</description>
22+
+ <param index="1">FieldX.</param>
23+
+ <param index="2">FieldY.</param>
24+
+ <param index="3">FieldZ.</param>
25+
+ <param index="4">Empty.</param>
26+
+ <param index="5">Empty.</param>
27+
+ <param index="6">Empty.</param>
28+
+ <param index="7">Empty.</param>
29+
+ </entry>
30+
+ <entry value="42424" name="MAV_CMD_DO_START_MAG_CAL">
31+
+ <description>Initiate a magnetometer calibration.</description>
32+
+ <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
33+
+ <param index="2">Automatically retry on failure (0=no retry, 1=retry).</param>
34+
+ <param index="3">Save without user input (0=require input, 1=autosave).</param>
35+
+ <param index="4">Delay (seconds).</param>
36+
+ <param index="5">Autoreboot (0=user reboot, 1=autoreboot).</param>
37+
+ <param index="6">Empty.</param>
38+
+ <param index="7">Empty.</param>
39+
+ </entry>
40+
+ <entry value="42425" name="MAV_CMD_DO_ACCEPT_MAG_CAL">
41+
+ <description>Initiate a magnetometer calibration.</description>
42+
+ <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
43+
+ <param index="2">Empty.</param>
44+
+ <param index="3">Empty.</param>
45+
+ <param index="4">Empty.</param>
46+
+ <param index="5">Empty.</param>
47+
+ <param index="6">Empty.</param>
48+
+ <param index="7">Empty.</param>
49+
+ </entry>
50+
+ <entry value="42426" name="MAV_CMD_DO_CANCEL_MAG_CAL">
51+
+ <description>Cancel a running magnetometer calibration.</description>
52+
+ <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
53+
+ <param index="2">Empty.</param>
54+
+ <param index="3">Empty.</param>
55+
+ <param index="4">Empty.</param>
56+
+ <param index="5">Empty.</param>
57+
+ <param index="6">Empty.</param>
58+
+ <param index="7">Empty.</param>
59+
+ </entry>
60+
+ <entry value="42429" name="MAV_CMD_ACCELCAL_VEHICLE_POS">
61+
+ <description>Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in.</description>
62+
+ <param index="1">Position, one of the ACCELCAL_VEHICLE_POS enum values.</param>
63+
+ <param index="2">Empty.</param>
64+
+ <param index="3">Empty.</param>
65+
+ <param index="4">Empty.</param>
66+
+ <param index="5">Empty.</param>
67+
+ <param index="6">Empty.</param>
68+
+ <param index="7">Empty.</param>
69+
+ </entry>
70+
<!-- END of user range (31000 to 31999) -->
71+
</enum>
72+
<enum name="MAV_DATA_STREAM">

0 commit comments

Comments
 (0)