|
944 | 944 | <description>Force reboot/shutdown of the autopilot/component regardless of system state.</description> |
945 | 945 | </entry> |
946 | 946 | </enum> |
| 947 | + <enum name="PREFLIGHT_CALIBRATION_MAGNETOMETER"> |
| 948 | + <description>Action for the magnetometer (param2) of MAV_CMD_PREFLIGHT_CALIBRATION.</description> |
| 949 | + <entry value="0" name="PREFLIGHT_CALIBRATION_MAGNETOMETER_NONE"> |
| 950 | + <description>No action.</description> |
| 951 | + </entry> |
| 952 | + <entry value="1" name="PREFLIGHT_CALIBRATION_MAGNETOMETER_START"> |
| 953 | + <description>Start magnetometer calibration.</description> |
| 954 | + </entry> |
| 955 | + <entry value="76" name="PREFLIGHT_CALIBRATION_MAGNETOMETER_FORCE_SAVE"> |
| 956 | + <description>Force-accept the existing compass calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags.</description> |
| 957 | + </entry> |
| 958 | + </enum> |
| 959 | + <enum name="PREFLIGHT_CALIBRATION_ACCELEROMETER"> |
| 960 | + <description>Action for the accelerometer (param5) of MAV_CMD_PREFLIGHT_CALIBRATION.</description> |
| 961 | + <entry value="0" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_NONE"> |
| 962 | + <description>No action.</description> |
| 963 | + </entry> |
| 964 | + <entry value="1" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_FULL"> |
| 965 | + <description>Full 6-position accelerometer calibration.</description> |
| 966 | + </entry> |
| 967 | + <entry value="2" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_TRIM"> |
| 968 | + <description>Board level (trim) calibration.</description> |
| 969 | + </entry> |
| 970 | + <entry value="3" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_TEMPERATURE"> |
| 971 | + <description>Accelerometer temperature calibration.</description> |
| 972 | + </entry> |
| 973 | + <entry value="4" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_SIMPLE"> |
| 974 | + <description>Simple accelerometer calibration.</description> |
| 975 | + </entry> |
| 976 | + <entry value="76" name="PREFLIGHT_CALIBRATION_ACCELEROMETER_FORCE_SAVE"> |
| 977 | + <description>Force-accept the existing accelerometer calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags.</description> |
| 978 | + </entry> |
| 979 | + </enum> |
947 | 980 | <enum name="NAV_TAKEOFF_FLAGS" bitmask="true"> |
948 | 981 | <entry value="1" name="NAV_TAKEOFF_FLAGS_HORIZONTAL_POSITION_NOT_REQUIRED"> |
949 | 982 | <description>Accept the command even if the autopilot does not have control over its horizontal position (note that it might not have altitude control either).</description> |
|
1747 | 1780 | <entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION" hasLocation="false" isDestination="false"> |
1748 | 1781 | <description>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.</description> |
1749 | 1782 | <param index="1" label="Gyro Temperature" minValue="0" maxValue="3" increment="1">1: gyro calibration, 3: gyro temperature calibration</param> |
1750 | | - <param index="2" label="Magnetometer" enum="MAV_BOOL">Magnetometer calibration. Values not equal to 0 or 1 are invalid.</param> |
| 1783 | + <param index="2" label="Magnetometer" enum="PREFLIGHT_CALIBRATION_MAGNETOMETER">Magnetometer calibration action.</param> |
1751 | 1784 | <param index="3" label="Ground Pressure" enum="MAV_BOOL">Ground pressure calibration. Values not equal to 0 or 1 are invalid.</param> |
1752 | 1785 | <param index="4" label="Remote Control" minValue="0" maxValue="1" increment="1">1: radio RC calibration, 2: RC trim calibration</param> |
1753 | | - <param index="5" label="Accelerometer" minValue="0" maxValue="4" increment="1">1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration</param> |
| 1786 | + <param index="5" label="Accelerometer" enum="PREFLIGHT_CALIBRATION_ACCELEROMETER">Accelerometer calibration action.</param> |
1754 | 1787 | <param index="6" label="Compmot or Airspeed" minValue="0" maxValue="2" increment="1">1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration</param> |
1755 | 1788 | <param index="7" label="ESC or Baro" minValue="0" maxValue="3" increment="1">1: ESC calibration, 3: barometer temperature calibration</param> |
1756 | 1789 | </entry> |
|
0 commit comments