common.xml: add and use ENGINE_CONTROL_OPTIONS (#2390)

bitmask of options from ardupilot/mavlink/master
This commit is contained in:
Peter Barker
2026-01-02 14:09:41 +11:00
committed by GitHub
parent aa205402c9
commit b1fb5a1a32
+7 -1
View File
@@ -1853,7 +1853,7 @@
<param index="1" label="Start Engine" enum="MAV_BOOL">Start engine (MAV_BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid.</param>
<param index="2" label="Cold Start" enum="MAV_BOOL">Cold start engine (MAV_BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable</param>
<param index="3" label="Height Delay" units="m" minValue="0">Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.</param>
<param index="4">Empty</param>
<param index="4" label="Options" enum="ENGINE_CONTROL_OPTIONS">A bitmask of options for engine control</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
@@ -4033,6 +4033,12 @@
<description>Spektrum DSMX8</description>
</entry>
</enum>
<enum name="ENGINE_CONTROL_OPTIONS" bitmask="true">
<description>Engine control options</description>
<entry value="1" name="ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED">
<description>Allow starting the engine while disarmed (without changing the vehicle's armed state). This effectively arms just the ICE, without arming the vehicle to start other motors or propellers.</description>
</entry>
</enum>
<enum name="POSITION_TARGET_TYPEMASK" bitmask="true">
<description>Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration.</description>
<entry value="1" name="POSITION_TARGET_TYPEMASK_X_IGNORE">