diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 7707a63ad3..0717d8fcb5 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -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( diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index d5f74d8e52..4bb0238fb7 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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)