mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Rover: support 16 character parameter names
This commit is contained in:
parent
bcf740a82f
commit
39836eabb2
@ -1505,9 +1505,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);
|
||||
@ -1793,7 +1793,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(
|
||||
|
@ -240,8 +240,6 @@ enum gcs_severity {
|
||||
|
||||
#define MAX_WAYPOINTS ((EEPROM_MAX_ADDR - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
|
||||
// convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps to -1)
|
||||
#define BOOL_TO_SIGN(bvalue) ((bvalue)?-1:1)
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user