diff --git a/dev/source/docs/mavlink-commands.rst b/dev/source/docs/mavlink-commands.rst index 5d2672b6b7..f65d6c6885 100644 --- a/dev/source/docs/mavlink-commands.rst +++ b/dev/source/docs/mavlink-commands.rst @@ -23,6 +23,7 @@ ArduPilot supports the MAVLink protocol for communication with Ground Stations a Mission Upload/Download Move a Servo Non-GPS Position Estimation + Precision Landing Winch Commands MAVLink Routing Other Commands diff --git a/dev/source/docs/mavlink-precision-landing.rst b/dev/source/docs/mavlink-precision-landing.rst new file mode 100644 index 0000000000..4904110b60 --- /dev/null +++ b/dev/source/docs/mavlink-precision-landing.rst @@ -0,0 +1,103 @@ +.. _mavlink-precision-landing: + +================= +Precision Landing +================= + +Copter, QuadPlane and Rover support precision landing using the `LANDING_TARGET `__ mavlink message + +References: + +- :ref:`Copter's user wiki for precision landing ` +- `QuadPlane discussion of precision landing `__ +- `MAVLink's Landing Target documentation `__ +- :ref:`Testing Precision Landing in SITL ` + +Users should follow the :ref:`user precision landing wiki page ` including setting :ref:`PLND_TYPE ` = 1 (MAVLink) + +The external camera system should send the `LANDING_TARGET `__ message to the autopilot at no less than 1hz (a higher rate is better). + +If the x (e.g. forward), y (e.g. right) and z (e.g. down) distance to the target is known (in body frame) then "x", "y" and "z" fields should be populated, and "position_valid" should be set to "1". + +If only the body-frame angle to the target is known then "angle_x" and "angle_y" fields should be populated and "position_valid" should be set to "0". + +.. raw:: html + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Field NameTypeDescription
time_usecuint64_tTimestamp since system boot. This does not need to be syncronised with the autopilot's time
target_numuint8_tnot used
frameuint8_tMAV_FRAME_BODY_FRD (12)
angle_xfloatX-axis angular offset (in radians) of the target from the center of the image
angle_yfloatY-axis angular offset (in radians) of the target from the center of the image
distancefloatDistance (in m) to the target from the vehicle or 0 if unknown
size_xfloatnot used
size_yfloatnot used
xfloatx position of the landing target in meters (e.g. forward in vehicle body-frame)
yfloaty position of the landing target in meters (e.g. right in vehicle body-frame)
zfloatz position of the landing target in meters (e.g down in vehicle body-frame)
qfloat[4]not used
typeuint8_tnot used
position_validuint8_t0 if angle_x, angle_y should be used. 1 if x, y, z fields contain position information