mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: rename is_bounded() to is_bounded_int32() and make inclusive
we will probably want float versions in future, and inclusive is better for the RC_Channel case
This commit is contained in:
parent
e1b608d56d
commit
090c02e6bd
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user