mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Param: Change from a direct value to a defined name
This commit is contained in:
parent
45e8cdea70
commit
a6bbfca44e
@ -2040,17 +2040,17 @@ void AP_Param::set_float(float value, enum ap_var_type var_type)
|
||||
} else if (var_type == AP_PARAM_INT32) {
|
||||
if (value < 0) rounding_addition = -rounding_addition;
|
||||
float v = value+rounding_addition;
|
||||
v = constrain_float(v, -2147483648.0, 2147483647.0);
|
||||
v = constrain_float(v, INT32_MIN, INT32_MAX);
|
||||
((AP_Int32 *)this)->set(v);
|
||||
} else if (var_type == AP_PARAM_INT16) {
|
||||
if (value < 0) rounding_addition = -rounding_addition;
|
||||
float v = value+rounding_addition;
|
||||
v = constrain_float(v, -32768, 32767);
|
||||
v = constrain_float(v, INT16_MIN, INT16_MAX);
|
||||
((AP_Int16 *)this)->set(v);
|
||||
} else if (var_type == AP_PARAM_INT8) {
|
||||
if (value < 0) rounding_addition = -rounding_addition;
|
||||
float v = value+rounding_addition;
|
||||
v = constrain_float(v, -128, 127);
|
||||
v = constrain_float(v, INT8_MIN, INT8_MAX);
|
||||
((AP_Int8 *)this)->set(v);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user