|
|
@ -1989,31 +1989,47 @@ 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(); |
|
|
|
|
|
|
|
|
|
|
|
AP_Param *vp; |
|
|
|
// use at most 30% of bandwidth on parameters. The constant 26 is |
|
|
|
float value; |
|
|
|
// 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); |
|
|
|
|
|
|
|
|
|
|
|
// copy the current parameter and prepare to move to the next |
|
|
|
while (_queued_parameter != NULL && count--) { |
|
|
|
vp = _queued_parameter; |
|
|
|
AP_Param *vp; |
|
|
|
|
|
|
|
float value; |
|
|
|
|
|
|
|
|
|
|
|
// if the parameter can be cast to float, report it here and break out of the loop |
|
|
|
// copy the current parameter and prepare to move to the next |
|
|
|
value = vp->cast_to_float(_queued_parameter_type); |
|
|
|
vp = _queued_parameter; |
|
|
|
|
|
|
|
|
|
|
|
char param_name[ONBOARD_PARAM_NAME_LENGTH]; |
|
|
|
// if the parameter can be cast to float, report it here and break out of the loop |
|
|
|
vp->copy_name(param_name, sizeof(param_name), true); |
|
|
|
value = vp->cast_to_float(_queued_parameter_type); |
|
|
|
|
|
|
|
|
|
|
|
mavlink_msg_param_value_send( |
|
|
|
char param_name[ONBOARD_PARAM_NAME_LENGTH]; |
|
|
|
chan, |
|
|
|
vp->copy_name(param_name, sizeof(param_name), true); |
|
|
|
param_name, |
|
|
|
|
|
|
|
value, |
|
|
|
mavlink_msg_param_value_send( |
|
|
|
mav_var_type(_queued_parameter_type), |
|
|
|
chan, |
|
|
|
_queued_parameter_count, |
|
|
|
param_name, |
|
|
|
_queued_parameter_index); |
|
|
|
value, |
|
|
|
|
|
|
|
mav_var_type(_queued_parameter_type), |
|
|
|
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type); |
|
|
|
_queued_parameter_count, |
|
|
|
_queued_parameter_index++; |
|
|
|
_queued_parameter_index); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type); |
|
|
|
|
|
|
|
_queued_parameter_index++; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
_queued_parameter_send_time_ms = tnow; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/** |
|
|
|
/** |
|
|
|