Plane: Send landing messages
This commit is contained in:
parent
16bd7a091e
commit
19a5475195
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user