GCS_MAVLink: tidy waypoint receiving part of update

This is NFC.  The early-return here is confusing, and there were
redundant checks going on.
This commit is contained in:
Peter Barker 2018-05-25 21:53:36 +10:00 committed by Francisco Ferreira
parent 5665feb29e
commit cad7f9d9c0
1 changed files with 9 additions and 13 deletions

View File

@ -951,21 +951,17 @@ GCS_MAVLINK::update(uint32_t max_time_us)
}
}
if (!waypoint_receiving) {
hal.util->perf_end(_perf_update);
return;
}
uint32_t wp_recv_time = 1000U + (stream_slowdown*20);
if (waypoint_receiving) {
const uint32_t wp_recv_time = 1000U + (stream_slowdown*20);
// stop waypoint receiving if timeout
if (waypoint_receiving && (tnow - waypoint_timelast_receive) > wp_recv_time+waypoint_receive_timeout) {
if (tnow - waypoint_timelast_receive > wp_recv_time+waypoint_receive_timeout) {
waypoint_receiving = false;
} else if (waypoint_receiving &&
(tnow - waypoint_timelast_request) > wp_recv_time) {
} else if (tnow - waypoint_timelast_request > wp_recv_time) {
waypoint_timelast_request = tnow;
send_message(MSG_NEXT_WAYPOINT);
}
}
hal.util->perf_end(_perf_update);
}