mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Param: replaced set_param_by_name with set_float
read for bugfix in GCS_MAVLink
This commit is contained in:
parent
ffefe425df
commit
cb8356a290
@ -1200,25 +1200,12 @@ void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_ta
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set a parameter by name
|
set a parameter to a float value
|
||||||
*/
|
*/
|
||||||
AP_Param *AP_Param::set_param_by_name(const char *pname, float value, enum ap_var_type *ptype)
|
void AP_Param::set_float(float value, enum ap_var_type var_type)
|
||||||
{
|
{
|
||||||
AP_Param *vp;
|
|
||||||
enum ap_var_type var_type;
|
|
||||||
|
|
||||||
if (isnan(value) || isinf(value)) {
|
if (isnan(value) || isinf(value)) {
|
||||||
return NULL;
|
return;
|
||||||
}
|
|
||||||
|
|
||||||
// find the requested parameter
|
|
||||||
vp = AP_Param::find(pname, &var_type);
|
|
||||||
if (vp == NULL) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ptype != NULL) {
|
|
||||||
*ptype = var_type;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// add a small amount before casting parameter values
|
// add a small amount before casting parameter values
|
||||||
@ -1228,27 +1215,23 @@ AP_Param *AP_Param::set_param_by_name(const char *pname, float value, enum ap_va
|
|||||||
|
|
||||||
// handle variables with standard type IDs
|
// handle variables with standard type IDs
|
||||||
if (var_type == AP_PARAM_FLOAT) {
|
if (var_type == AP_PARAM_FLOAT) {
|
||||||
((AP_Float *)vp)->set(value);
|
((AP_Float *)this)->set(value);
|
||||||
} else if (var_type == AP_PARAM_INT32) {
|
} else if (var_type == AP_PARAM_INT32) {
|
||||||
if (value < 0) rounding_addition = -rounding_addition;
|
if (value < 0) rounding_addition = -rounding_addition;
|
||||||
float v = value+rounding_addition;
|
float v = value+rounding_addition;
|
||||||
v = constrain_float(v, -2147483648.0, 2147483647.0);
|
v = constrain_float(v, -2147483648.0, 2147483647.0);
|
||||||
((AP_Int32 *)vp)->set(v);
|
((AP_Int32 *)this)->set(v);
|
||||||
} else if (var_type == AP_PARAM_INT16) {
|
} else if (var_type == AP_PARAM_INT16) {
|
||||||
if (value < 0) rounding_addition = -rounding_addition;
|
if (value < 0) rounding_addition = -rounding_addition;
|
||||||
float v = value+rounding_addition;
|
float v = value+rounding_addition;
|
||||||
v = constrain_float(v, -32768, 32767);
|
v = constrain_float(v, -32768, 32767);
|
||||||
((AP_Int16 *)vp)->set(v);
|
((AP_Int16 *)this)->set(v);
|
||||||
} else if (var_type == AP_PARAM_INT8) {
|
} else if (var_type == AP_PARAM_INT8) {
|
||||||
if (value < 0) rounding_addition = -rounding_addition;
|
if (value < 0) rounding_addition = -rounding_addition;
|
||||||
float v = value+rounding_addition;
|
float v = value+rounding_addition;
|
||||||
v = constrain_float(v, -128, 127);
|
v = constrain_float(v, -128, 127);
|
||||||
((AP_Int8 *)vp)->set(v);
|
((AP_Int8 *)this)->set(v);
|
||||||
} else {
|
|
||||||
// we don't support mavlink set on this parameter
|
|
||||||
return NULL;
|
|
||||||
}
|
}
|
||||||
return vp;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -1342,10 +1325,13 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
param_overrides[idx].def_value_ptr = def_value_ptr;
|
param_overrides[idx].def_value_ptr = def_value_ptr;
|
||||||
param_overrides[idx].value = value;
|
param_overrides[idx].value = value;
|
||||||
idx++;
|
idx++;
|
||||||
if (!set_param_by_name(pname, value, NULL)) {
|
enum ap_var_type var_type;
|
||||||
|
AP_Param *vp = AP_Param::find(pname, &var_type);
|
||||||
|
if (!vp) {
|
||||||
fclose(f);
|
fclose(f);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
vp->set_float(value, var_type);
|
||||||
}
|
}
|
||||||
fclose(f);
|
fclose(f);
|
||||||
|
|
||||||
|
@ -198,13 +198,10 @@ public:
|
|||||||
// set a AP_Param variable to a specified value
|
// set a AP_Param variable to a specified value
|
||||||
static void set_value(enum ap_var_type type, void *ptr, float def_value);
|
static void set_value(enum ap_var_type type, void *ptr, float def_value);
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set a parameter by name
|
set a parameter to a float
|
||||||
|
|
||||||
The parameter pointer is returned on success
|
|
||||||
*/
|
*/
|
||||||
static AP_Param *set_param_by_name(const char *pname, float value, enum ap_var_type *ptype);
|
void set_float(float value, enum ap_var_type var_type);
|
||||||
|
|
||||||
// load default values for scalars in a group
|
// load default values for scalars in a group
|
||||||
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
|
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
|
||||||
|
Loading…
Reference in New Issue
Block a user