GCS_MAVLink: use bw_in_bytes_per-scond()

avoid division by zero in FTP, and correct wrong calculus in Param which made it ineffective
This commit is contained in:
olliw42 2023-01-18 08:46:46 +01:00 committed by Peter Barker
parent 866db281a6
commit d570f67420
2 changed files with 5 additions and 7 deletions

View File

@ -499,13 +499,12 @@ void GCS_MAVLINK::ftp_worker(void) {
if (valid_channel(request.chan)) {
auto *port = mavlink_comm_port[request.chan];
if (port != nullptr && port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_ENABLE) {
const uint32_t bw = port->bw_in_kilobytes_per_second();
const uint32_t bw = port->bw_in_bytes_per_second();
const uint16_t pkt_size = PAYLOAD_SIZE(request.chan, FILE_TRANSFER_PROTOCOL) - (sizeof(reply.data) - max_read);
burst_delay_ms = 3 * pkt_size / bw;
burst_delay_ms = 3000 * pkt_size / bw;
}
}
// this transfer size is enough for a full parameter file with max parameters
const uint32_t transfer_size = 500;
for (uint32_t i = 0; (i < transfer_size); i++) {

View File

@ -47,11 +47,10 @@ GCS_MAVLINK::queued_param_send()
const uint32_t tnow = AP_HAL::millis();
const uint32_t tstart = AP_HAL::micros();
// use at most 30% of bandwidth on parameters. The constant 26 is
// 1/(1000 * 1/8 * 0.001 * 0.3)
const uint32_t link_bw = _port->bw_in_kilobytes_per_second();
// use at most 30% of bandwidth on parameters
const uint32_t link_bw = _port->bw_in_bytes_per_second();
uint32_t bytes_allowed = link_bw * (tnow - _queued_parameter_send_time_ms) * 26;
uint32_t bytes_allowed = link_bw * (tnow - _queued_parameter_send_time_ms) / 3333;
const uint16_t size_for_one_param_value_msg = MAVLINK_MSG_ID_PARAM_VALUE_LEN + packet_overhead();
if (bytes_allowed < size_for_one_param_value_msg) {
bytes_allowed = size_for_one_param_value_msg;