mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
GCS_MAVLink: don't recalculate max parameter count if not streaming params
This commit is contained in:
parent
4ee17aea3d
commit
87a31c6409
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user