GCS_MAVLink: added MAV_CMD_DO_LAND_START
see discussion on drones-discuss
This commit is contained in:
parent
7636cc6971
commit
e1a88a13a7
@ -772,7 +772,17 @@
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
</entry>
|
||||
<entry value="189" name="MAV_CMD_DO_LAND_START">
|
||||
<description>Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.</description>
|
||||
<param index="1">Empty</param>
|
||||
<param index="2">Empty</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Latitude</param>
|
||||
<param index="6">Longitude</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="190" name="MAV_CMD_DO_RALLY_LAND">
|
||||
<description>Mission command to perform a landing from a rally point.</description>
|
||||
<param index="1">Break altitude (meters)</param>
|
||||
|
Loading…
Reference in New Issue
Block a user