Browse Source

APM: much faster parameter fetching

allow up to 30% of bandwidth to be used for parameter send
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
3077de0d33
  1. 1
      ArduPlane/GCS.h
  2. 20
      ArduPlane/GCS_Mavlink.pde

1
ArduPlane/GCS.h

@ -153,6 +153,7 @@ private: @@ -153,6 +153,7 @@ private:
uint16_t _queued_parameter_count; ///< saved count of
// parameters for
// queued send
uint32_t _queued_parameter_send_time_ms;
/// Count the number of reportable parameters.
///

20
ArduPlane/GCS_Mavlink.pde

@ -1989,9 +1989,23 @@ GCS_MAVLINK::_count_parameters() @@ -1989,9 +1989,23 @@ GCS_MAVLINK::_count_parameters()
void
GCS_MAVLINK::queued_param_send()
{
// Check to see if we are sending parameters
if (NULL == _queued_parameter) return;
if (_queued_parameter == NULL) {
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;
float value;
@ -2015,6 +2029,8 @@ GCS_MAVLINK::queued_param_send() @@ -2015,6 +2029,8 @@ GCS_MAVLINK::queued_param_send()
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
_queued_parameter_index++;
}
_queued_parameter_send_time_ms = tnow;
}
/**
* @brief Send the next pending waypoint, called from deferred message

Loading…
Cancel
Save