Copter: fixed mavlink fetch of 16 character parameter

This commit is contained in:
Andrew Tridgell 2013-01-21 16:52:01 +11:00
parent 6fa5837f71
commit ae5f46abc9

View File

@ -1468,7 +1468,7 @@ 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];
char param_name[AP_MAX_NAME_SIZE+1];
if (packet.param_index != -1) {
AP_Param::ParamToken token;
vp = AP_Param::find_by_index(packet.param_index, &p_type, &token);
@ -1476,14 +1476,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
gcs_send_text_fmt(PSTR("Unknown parameter index %d"), packet.param_index);
break;
}
vp->copy_name_token(&token, param_name, sizeof(param_name), true);
vp->copy_name_token(&token, param_name, AP_MAX_NAME_SIZE, true);
param_name[AP_MAX_NAME_SIZE] = 0;
} else {
vp = AP_Param::find(packet.param_id, &p_type);
strncpy(param_name, packet.param_id, AP_MAX_NAME_SIZE);
param_name[AP_MAX_NAME_SIZE] = 0;
vp = AP_Param::find(param_name, &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);
}
float value = vp->cast_to_float(p_type);