|
|
|
@ -1228,21 +1228,23 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1228,21 +1228,23 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
if (mavlink_check_target(packet.target_system,packet.target_component)) break; |
|
|
|
|
enum ap_var_type p_type; |
|
|
|
|
AP_Param *vp; |
|
|
|
|
char param_name[AP_MAX_NAME_SIZE]; |
|
|
|
|
if (packet.param_index != -1) { |
|
|
|
|
vp = AP_Param::find_by_index(packet.param_index, &p_type); |
|
|
|
|
AP_Param::ParamToken token; |
|
|
|
|
vp = AP_Param::find_by_index(packet.param_index, &p_type, &token); |
|
|
|
|
if (vp == NULL) { |
|
|
|
|
gcs_send_text_fmt(PSTR("Unknown parameter index %d"), packet.param_index); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
vp->copy_name_token(&token, param_name, sizeof(param_name), true); |
|
|
|
|
} else { |
|
|
|
|
vp = AP_Param::find(packet.param_id, &p_type); |
|
|
|
|
if (vp == NULL) { |
|
|
|
|
gcs_send_text_fmt(PSTR("Unknown parameter %.16s"), packet.param_id); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
strncpy(param_name, packet.param_id, AP_MAX_NAME_SIZE); |
|
|
|
|
} |
|
|
|
|
char param_name[AP_MAX_NAME_SIZE]; |
|
|
|
|
vp->copy_name(param_name, sizeof(param_name), true); |
|
|
|
|
|
|
|
|
|
float value = vp->cast_to_float(p_type); |
|
|
|
|
mavlink_msg_param_value_send( |
|
|
|
@ -1773,7 +1775,7 @@ GCS_MAVLINK::queued_param_send()
@@ -1773,7 +1775,7 @@ GCS_MAVLINK::queued_param_send()
|
|
|
|
|
value = vp->cast_to_float(_queued_parameter_type); |
|
|
|
|
|
|
|
|
|
char param_name[AP_MAX_NAME_SIZE]; |
|
|
|
|
vp->copy_name(param_name, sizeof(param_name), true); |
|
|
|
|
vp->copy_name_token(&_queued_parameter_token, param_name, sizeof(param_name), true); |
|
|
|
|
|
|
|
|
|
mavlink_msg_param_value_send( |
|
|
|
|
chan, |
|
|
|
|