GCS_MAVLink: don't recalculate max parameter count if not streaming params

This commit is contained in:
Peter Barker 2020-02-15 22:20:54 +11:00 committed by Andrew Tridgell
parent 4ee17aea3d
commit 87a31c6409
1 changed files with 6 additions and 4 deletions

View File

@ -37,6 +37,12 @@ GCS_MAVLINK::queued_param_send()
// send parameter async replies
uint8_t async_replies_sent_count = send_parameter_async_replies();
// now send the streaming parameters (from PARAM_REQUEST_LIST)
if (_queued_parameter == nullptr) {
// .... or not....
return;
}
const uint32_t tnow = AP_HAL::millis();
const uint32_t tstart = AP_HAL::micros();
@ -64,10 +70,6 @@ GCS_MAVLINK::queued_param_send()
}
count -= async_replies_sent_count;
if (_queued_parameter == nullptr) {
return;
}
while (count && _queued_parameter != nullptr) {
char param_name[AP_MAX_NAME_SIZE];
_queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);