ACM: support 16 character parameter names

This commit is contained in:
Andrew Tridgell 2012-11-20 21:38:58 +11:00
parent a600ccece5
commit bcf740a82f
2 changed files with 5 additions and 7 deletions

View File

@ -1365,7 +1365,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
gcs_send_text_fmt(PSTR("Unknown parameter %s"), packet.param_id);
break;
}
char param_name[ONBOARD_PARAM_NAME_LENGTH];
char param_name[AP_MAX_NAME_SIZE];
vp->copy_name(param_name, sizeof(param_name), true);
float value = vp->cast_to_float(p_type);
@ -1646,9 +1646,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// set parameter
char key[ONBOARD_PARAM_NAME_LENGTH+1];
strncpy(key, (char *)packet.param_id, ONBOARD_PARAM_NAME_LENGTH);
key[ONBOARD_PARAM_NAME_LENGTH] = 0;
char key[AP_MAX_NAME_SIZE+1];
strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
key[AP_MAX_NAME_SIZE] = 0;
// find the requested parameter
vp = AP_Param::find(key, &var_type);
@ -1991,7 +1991,7 @@ GCS_MAVLINK::queued_param_send()
// if the parameter can be cast to float, report it here and break out of the loop
value = vp->cast_to_float(_queued_parameter_type);
char param_name[ONBOARD_PARAM_NAME_LENGTH];
char param_name[AP_MAX_NAME_SIZE];
vp->copy_name(param_name, sizeof(param_name), true);
mavlink_msg_param_value_send(

View File

@ -453,8 +453,6 @@ enum gcs_severity {
// WP
#define WP_SIZE 15
#define ONBOARD_PARAM_NAME_LENGTH 15
// fence points are stored at the end of the EEPROM
#define MAX_FENCEPOINTS 6
#define FENCE_WP_SIZE sizeof(Vector2l)