mirror of https://github.com/ArduPilot/ardupilot
MAVLink: fixed link flood on waypoint upload
This commit is contained in:
parent
7e30aa51c9
commit
b0aa1deac2
|
@ -787,6 +787,7 @@ GCS_MAVLINK::update(void)
|
||||||
if (waypoint_receiving &&
|
if (waypoint_receiving &&
|
||||||
waypoint_request_i <= (unsigned)g.command_total &&
|
waypoint_request_i <= (unsigned)g.command_total &&
|
||||||
tnow > waypoint_timelast_request + 500) {
|
tnow > waypoint_timelast_request + 500) {
|
||||||
|
waypoint_timelast_request = tnow;
|
||||||
send_message(MSG_NEXT_WAYPOINT);
|
send_message(MSG_NEXT_WAYPOINT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue