mirror of https://github.com/ArduPilot/ardupilot
AP_Common: Added a new is_bounded global function.
This commit is contained in:
parent
3636b53313
commit
ba8dbf6696
|
@ -23,3 +23,16 @@
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
/*
|
||||||
|
Return true if value is between lower and upper bound. False otherwise.
|
||||||
|
*/
|
||||||
|
bool is_bounded(int32_t value, int32_t lower_bound, int32_t upper_bound)
|
||||||
|
{
|
||||||
|
if ((lower_bound < upper_bound) &&
|
||||||
|
(value > lower_bound) && (value < upper_bound)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
|
@ -155,4 +155,7 @@ enum HomeState {
|
||||||
#define AP_PRODUCT_ID_MPU9250 0x103 // MPU9250
|
#define AP_PRODUCT_ID_MPU9250 0x103 // MPU9250
|
||||||
#define AP_PRODUCT_ID_VRBRAIN 0x150 // VRBRAIN on NuttX
|
#define AP_PRODUCT_ID_VRBRAIN 0x150 // VRBRAIN on NuttX
|
||||||
|
|
||||||
|
|
||||||
|
bool is_bounded(int32_t value, int32_t lower_bound, int32_t upper_bound);
|
||||||
|
|
||||||
#endif // _AP_COMMON_H
|
#endif // _AP_COMMON_H
|
||||||
|
|
Loading…
Reference in New Issue