GCS_MAVLink: slow down telemetry during ftp
This commit is contained in:
parent
5047eb88e2
commit
8a84dbc19e
@ -707,6 +707,7 @@ private:
|
||||
int fd = -1;
|
||||
FTP_FILE_MODE mode; // work around AP_Filesystem not supporting file modes
|
||||
int16_t current_session;
|
||||
uint32_t last_send_ms;
|
||||
};
|
||||
static struct ftp_state ftp;
|
||||
|
||||
|
@ -847,6 +847,12 @@ uint16_t GCS_MAVLINK::get_reschedule_interval_ms(const deferred_message_bucket_t
|
||||
// we are sending requests for waypoints, penalize streams:
|
||||
interval_ms *= 4;
|
||||
}
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
if (ftp.replies && AP_HAL::millis() - ftp.last_send_ms < 500) {
|
||||
// we are sending ftp replies
|
||||
interval_ms *= 4;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (interval_ms > 60000) {
|
||||
return 60000;
|
||||
|
@ -114,6 +114,7 @@ void GCS_MAVLINK::send_ftp_replies(void) {
|
||||
0, reply.sysid, reply.compid,
|
||||
payload);
|
||||
ftp.replies->pop(reply);
|
||||
ftp.last_send_ms = AP_HAL::millis();
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user