SITL: make abs() 16 bit in SITL

this will help us find abs() bugs in autotest
This commit is contained in:
Andrew Tridgell 2012-08-16 15:18:17 +10:00
parent 50e2458df0
commit faeb206239
2 changed files with 11 additions and 1 deletions

View File

@ -74,7 +74,6 @@ extern "C"{
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x))
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
//#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
#define radians(deg) ((deg)*DEG_TO_RAD)
@ -124,6 +123,8 @@ uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder);
void attachInterrupt(uint8_t, void (*)(void), int mode);
void detachInterrupt(uint8_t);
int abs(int v);
#ifdef __cplusplus
} // extern "C"
#endif

View File

@ -208,3 +208,12 @@ void runInterrupt(uint8_t inum)
interrupt_table[inum].call();
}
}
// this version of abs() is here to ensure it is 16 bit
// which allows us to find abs() bugs in SITL
int abs(int v)
{
int16_t v16 = (int16_t)v;
if (v16 >= 0) return v16;
return -v16;
}