mirror of
https://github.com/mavlink/mavlink.git
synced 2026-06-19 07:35:34 +00:00
common: document NAV_TAKEOFF param3 autopilot-nav requirement (#2429)
When param3 bit 0 is not set, the vehicle must reject the command if it will not automatically manage horizontal position. Documents existing ArduPilot behaviour (ArduCopter GCS_MAVLink_Copter.cpp). Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
This commit is contained in:
@@ -1117,6 +1117,11 @@
|
||||
<description>Force-accept the existing accelerometer calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="NAV_TAKEOFF_FLAGS" bitmask="true">
|
||||
<entry value="1" name="NAV_TAKEOFF_FLAGS_HORIZONTAL_POSITION_NOT_REQUIRED">
|
||||
<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>
|
||||
</entry>
|
||||
</enum>
|
||||
<!-- The MAV_CMD enum entries describe either: -->
|
||||
<!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) -->
|
||||
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
|
||||
@@ -1187,7 +1192,7 @@
|
||||
<description>Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.</description>
|
||||
<param index="1" label="Pitch" units="deg">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
|
||||
<param index="2">Empty</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="3" label="Flags" enum="NAV_TAKEOFF_FLAGS">Bitmask of options flags.</param>
|
||||
<param index="4" label="Yaw" units="deg">Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).</param>
|
||||
<param index="5" label="Latitude">Latitude</param>
|
||||
<param index="6" label="Longitude">Longitude</param>
|
||||
|
||||
Reference in New Issue
Block a user