From a6bbfca44e71af3d0b72a7ab31e5f52a48df44db Mon Sep 17 00:00:00 2001 From: murata Date: Wed, 19 Jan 2022 23:57:30 +0900 Subject: [PATCH] AP_Param: Change from a direct value to a defined name --- libraries/AP_Param/AP_Param.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 5ce751e34a..1bbba058aa 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -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); } }