mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: warn user via text message of mission upload failure
This commit is contained in:
parent
57d3a4fb5f
commit
686abb5e61
|
@ -1005,6 +1005,7 @@ GCS_MAVLINK::update(uint32_t max_time_us)
|
||||||
// stop waypoint receiving if timeout
|
// stop waypoint receiving if timeout
|
||||||
if (tnow - waypoint_timelast_receive > wp_recv_time+waypoint_receive_timeout) {
|
if (tnow - waypoint_timelast_receive > wp_recv_time+waypoint_receive_timeout) {
|
||||||
waypoint_receiving = false;
|
waypoint_receiving = false;
|
||||||
|
gcs().send_text(MAV_SEVERITY_WARNING, "Mission upload timeout");
|
||||||
} else if (tnow - waypoint_timelast_request > wp_recv_time) {
|
} else if (tnow - waypoint_timelast_request > wp_recv_time) {
|
||||||
waypoint_timelast_request = tnow;
|
waypoint_timelast_request = tnow;
|
||||||
send_message(MSG_NEXT_WAYPOINT);
|
send_message(MSG_NEXT_WAYPOINT);
|
||||||
|
|
Loading…
Reference in New Issue