mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Math: Add float cast to float version of fabsF to get rid of compiler warnings about demoting doubles to floats
This commit is contained in:
parent
aec7cc24d1
commit
0b2421ba75
@ -28,7 +28,6 @@ typedef double ftype;
|
|||||||
#define ceilF(x) ceil(x)
|
#define ceilF(x) ceil(x)
|
||||||
#define fminF(x,y) fmin(x,y)
|
#define fminF(x,y) fmin(x,y)
|
||||||
#define fmodF(x,y) fmod(x,y)
|
#define fmodF(x,y) fmod(x,y)
|
||||||
#define fabsF(x) fabs(x)
|
|
||||||
#define toftype todouble
|
#define toftype todouble
|
||||||
#else
|
#else
|
||||||
typedef float ftype;
|
typedef float ftype;
|
||||||
@ -43,11 +42,10 @@ typedef float ftype;
|
|||||||
#define fmaxF(x,y) fmaxf(x,y)
|
#define fmaxF(x,y) fmaxf(x,y)
|
||||||
#define powF(x,y) powf(x,y)
|
#define powF(x,y) powf(x,y)
|
||||||
#define logF(x) logf(x)
|
#define logF(x) logf(x)
|
||||||
#define fabsF(x) fabsf(x)
|
#define fabsF(x) fabsf((float)(x))
|
||||||
#define ceilF(x) ceilf(x)
|
#define ceilF(x) ceilf(x)
|
||||||
#define fminF(x,y) fminf(x,y)
|
#define fminF(x,y) fminf(x,y)
|
||||||
#define fmodF(x,y) fmodf(x,y)
|
#define fmodF(x,y) fmodf(x,y)
|
||||||
#define fabsF(x) fabsf(x)
|
|
||||||
#define toftype tofloat
|
#define toftype tofloat
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user