GCS_MAVLink: warn user via text message of mission upload failure

This commit is contained in:
Peter Barker 2018-11-17 10:16:05 +11:00 committed by Tom Pittenger
parent 57d3a4fb5f
commit 686abb5e61
1 changed files with 1 additions and 0 deletions

View File

@ -1005,6 +1005,7 @@ GCS_MAVLINK::update(uint32_t max_time_us)
// stop waypoint receiving if timeout
if (tnow - waypoint_timelast_receive > wp_recv_time+waypoint_receive_timeout) {
waypoint_receiving = false;
gcs().send_text(MAV_SEVERITY_WARNING, "Mission upload timeout");
} else if (tnow - waypoint_timelast_request > wp_recv_time) {
waypoint_timelast_request = tnow;
send_message(MSG_NEXT_WAYPOINT);