diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index c9b6a38a9cb..45ffb081a3d 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -944,6 +944,39 @@
Force reboot/shutdown of the autopilot/component regardless of system state.
+
+ Action for the magnetometer (param2) of MAV_CMD_PREFLIGHT_CALIBRATION.
+
+ No action.
+
+
+ Start magnetometer calibration.
+
+
+ Force-accept the existing compass calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags.
+
+
+
+ Action for the accelerometer (param5) of MAV_CMD_PREFLIGHT_CALIBRATION.
+
+ No action.
+
+
+ Full 6-position accelerometer calibration.
+
+
+ Board level (trim) calibration.
+
+
+ Accelerometer temperature calibration.
+
+
+ Simple accelerometer calibration.
+
+
+ Force-accept the existing accelerometer calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags.
+
+
Accept the command even if the autopilot does not have control over its horizontal position (note that it might not have altitude control either).
@@ -1747,10 +1780,10 @@
Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero.
1: gyro calibration, 3: gyro temperature calibration
- Magnetometer calibration. Values not equal to 0 or 1 are invalid.
+ Magnetometer calibration action.
Ground pressure calibration. Values not equal to 0 or 1 are invalid.
1: radio RC calibration, 2: RC trim calibration
- 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration
+ Accelerometer calibration action.
1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration
1: ESC calibration, 3: barometer temperature calibration