mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Math: compiler warning: is_zero special case for vector3.h in a template
This commit is contained in:
parent
878eb88c3a
commit
bdda11b327
@ -51,8 +51,10 @@
|
|||||||
#define VECTOR3_H
|
#define VECTOR3_H
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <float.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
|
|
||||||
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
|
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#endif
|
#endif
|
||||||
@ -154,7 +156,8 @@ public:
|
|||||||
bool is_inf(void) const;
|
bool is_inf(void) const;
|
||||||
|
|
||||||
// check if all elements are zero
|
// check if all elements are zero
|
||||||
bool is_zero(void) const { return x==0 && y == 0 && z == 0; }
|
bool is_zero(void) const { return (fabsf(x) < FLT_EPSILON) && (fabsf(y) < FLT_EPSILON) && (fabsf(z) < FLT_EPSILON); }
|
||||||
|
|
||||||
|
|
||||||
// rotate by a standard rotation
|
// rotate by a standard rotation
|
||||||
void rotate(enum Rotation rotation);
|
void rotate(enum Rotation rotation);
|
||||||
|
Loading…
Reference in New Issue
Block a user