mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
APM: much faster parameter fetching
allow up to 30% of bandwidth to be used for parameter send
This commit is contained in:
parent
728b3a133e
commit
3077de0d33
@ -153,6 +153,7 @@ private:
|
|||||||
uint16_t _queued_parameter_count; ///< saved count of
|
uint16_t _queued_parameter_count; ///< saved count of
|
||||||
// parameters for
|
// parameters for
|
||||||
// queued send
|
// queued send
|
||||||
|
uint32_t _queued_parameter_send_time_ms;
|
||||||
|
|
||||||
/// Count the number of reportable parameters.
|
/// Count the number of reportable parameters.
|
||||||
///
|
///
|
||||||
|
@ -1989,9 +1989,23 @@ GCS_MAVLINK::_count_parameters()
|
|||||||
void
|
void
|
||||||
GCS_MAVLINK::queued_param_send()
|
GCS_MAVLINK::queued_param_send()
|
||||||
{
|
{
|
||||||
// Check to see if we are sending parameters
|
if (_queued_parameter == NULL) {
|
||||||
if (NULL == _queued_parameter) return;
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t bytes_allowed;
|
||||||
|
uint8_t count;
|
||||||
|
uint32_t tnow = millis();
|
||||||
|
|
||||||
|
// use at most 30% of bandwidth on parameters. The constant 26 is
|
||||||
|
// 1/(1000 * 1/8 * 0.001 * 0.3)
|
||||||
|
bytes_allowed = g.serial3_baud * (tnow - _queued_parameter_send_time_ms) * 26;
|
||||||
|
if (bytes_allowed > comm_get_txspace(chan)) {
|
||||||
|
bytes_allowed = comm_get_txspace(chan);
|
||||||
|
}
|
||||||
|
count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES);
|
||||||
|
|
||||||
|
while (_queued_parameter != NULL && count--) {
|
||||||
AP_Param *vp;
|
AP_Param *vp;
|
||||||
float value;
|
float value;
|
||||||
|
|
||||||
@ -2014,6 +2028,8 @@ GCS_MAVLINK::queued_param_send()
|
|||||||
|
|
||||||
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
|
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
|
||||||
_queued_parameter_index++;
|
_queued_parameter_index++;
|
||||||
|
}
|
||||||
|
_queued_parameter_send_time_ms = tnow;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
Loading…
Reference in New Issue
Block a user