Browse Source

AP_Common: Added a new is_bounded global function.

master
Grant Morphett 9 years ago committed by Andrew Tridgell
parent
commit
ba8dbf6696
  1. 13
      libraries/AP_Common/AP_Common.cpp
  2. 3
      libraries/AP_Common/AP_Common.h

13
libraries/AP_Common/AP_Common.cpp

@ -23,3 +23,16 @@ @@ -23,3 +23,16 @@
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;
}

3
libraries/AP_Common/AP_Common.h

@ -155,4 +155,7 @@ enum HomeState { @@ -155,4 +155,7 @@ 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);
#endif // _AP_COMMON_H

Loading…
Cancel
Save