diff --git a/libraries/AP_Common/AP_Common.cpp b/libraries/AP_Common/AP_Common.cpp index eb29870f7c..b56838efa3 100644 --- a/libraries/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/AP_Common.cpp @@ -24,12 +24,13 @@ extern const AP_HAL::HAL& hal; /* - Return true if value is between lower and upper bound. False otherwise. + Return true if value is between lower and upper bound inclusive. + False otherwise. */ -bool is_bounded(int32_t value, int32_t lower_bound, int32_t upper_bound) +bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound) { - if ((lower_bound < upper_bound) && - (value > lower_bound) && (value < upper_bound)) { + if ((lower_bound <= upper_bound) && + (value >= lower_bound) && (value <= upper_bound)) { return true; } diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index ea17cd1a75..8bbaf914f1 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -155,7 +155,10 @@ enum HomeState { #define AP_PRODUCT_ID_MPU9250 0x103 // MPU9250 #define AP_PRODUCT_ID_VRBRAIN 0x150 // VRBRAIN on NuttX - -bool is_bounded(int32_t value, int32_t lower_bound, int32_t upper_bound); +/* + Return true if value is between lower and upper bound inclusive. + False otherwise. +*/ +bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound); #endif // _AP_COMMON_H