GCS: fixed timeout loading waypoints

while loading waypoints we could saturate the link
This commit is contained in:
Andrew Tridgell 2011-10-31 21:25:35 +11:00
parent beab1500c1
commit 9eb27c2573
2 changed files with 11 additions and 1 deletions

View File

@ -152,6 +152,7 @@ private:
uint16_t waypoint_count;
uint32_t waypoint_timelast_send; // milliseconds
uint32_t waypoint_timelast_receive; // milliseconds
uint32_t waypoint_timelast_request; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds

View File

@ -777,8 +777,15 @@ GCS_MAVLINK::update(void)
send_message(MSG_NEXT_PARAM);
}
if (!waypoint_receiving && !waypoint_sending) {
return;
}
uint32_t tnow = millis();
if (waypoint_receiving &&
waypoint_request_i <= (unsigned)g.command_total) {
waypoint_request_i <= (unsigned)g.command_total &&
tnow > waypoint_timelast_request + 500) {
send_message(MSG_NEXT_WAYPOINT);
}
@ -1413,6 +1420,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
g.command_total.set_and_save(packet.count - 1);
waypoint_timelast_receive = millis();
waypoint_timelast_request = 0;
waypoint_receiving = true;
waypoint_sending = false;
waypoint_request_i = 0;
@ -1589,6 +1597,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
waypoint_timelast_request = 0;
waypoint_request_i++;
if (waypoint_request_i > (uint16_t)g.command_total){