diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4dcf5ddad9..caec2cfa76 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -699,6 +699,8 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) case MSG_AOA_SSA: CHECK_PAYLOAD_SIZE(AOA_SSA); plane.send_aoa_ssa(chan); + case MSG_LANDING: + plane.landing.send_landing_message(chan); break; } return true; @@ -884,6 +886,7 @@ GCS_MAVLINK_Plane::data_stream_send(void) if (plane.control_mode != MANUAL) { send_message(MSG_PID_TUNING); } + send_message(MSG_LANDING); } if (plane.gcs_out_of_time) return;