mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: correct slowing down of waypoint re-requests
These re-requests shouldn't be slowed down by a factor of 20. This was a left-over from when we did these in terms of 20ms intervals (50Hz loop rate)
This commit is contained in:
parent
ca7fcc093c
commit
55d37e5d0e
|
@ -349,7 +349,7 @@ void MissionItemProtocol::update()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// resend request if we haven't gotten one:
|
// resend request if we haven't gotten one:
|
||||||
const uint32_t wp_recv_timeout_ms = 1000U + (link->get_stream_slowdown_ms()*20);
|
const uint32_t wp_recv_timeout_ms = 1000U + link->get_stream_slowdown_ms();
|
||||||
if (tnow - timelast_request_ms > wp_recv_timeout_ms) {
|
if (tnow - timelast_request_ms > wp_recv_timeout_ms) {
|
||||||
timelast_request_ms = tnow;
|
timelast_request_ms = tnow;
|
||||||
link->send_message(next_item_ap_message_id());
|
link->send_message(next_item_ap_message_id());
|
||||||
|
|
Loading…
Reference in New Issue