diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index f6494b56b9..e19bf2a158 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -128,7 +128,7 @@ public: // allow a Matrix3 to be used as an array of vectors, 0 indexed Vector3 & operator[](uint8_t i) { Vector3 *_v = &a; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < 3); #endif return _v[i]; @@ -136,7 +136,7 @@ public: const Vector3 & operator[](uint8_t i) const { const Vector3 *_v = &a; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < 3); #endif return _v[i]; diff --git a/libraries/AP_Math/quaternion.h b/libraries/AP_Math/quaternion.h index faa0361b46..2786149a00 100644 --- a/libraries/AP_Math/quaternion.h +++ b/libraries/AP_Math/quaternion.h @@ -21,7 +21,7 @@ #define QUATERNION_H #include -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) #include #endif @@ -90,7 +90,7 @@ public: // allow a quaternion to be used as an array, 0 indexed float & operator[](uint8_t i) { float *_v = &q1; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i < 4); #endif return _v[i]; @@ -98,7 +98,7 @@ public: const float & operator[](uint8_t i) const { const float *_v = &q1; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i < 4); #endif return _v[i]; diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index c7cc7b36da..cafa60adff 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -53,7 +53,7 @@ #include #include -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) #include #endif @@ -118,7 +118,7 @@ public: // allow a vector3 to be used as an array, 0 indexed T & operator[](uint8_t i) { T *_v = &x; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < 3); #endif return _v[i]; @@ -126,7 +126,7 @@ public: const T & operator[](uint8_t i) const { const T *_v = &x; -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < 3); #endif return _v[i]; diff --git a/libraries/AP_Math/vectorN.h b/libraries/AP_Math/vectorN.h index cfd4bb4def..9bd051446c 100644 --- a/libraries/AP_Math/vectorN.h +++ b/libraries/AP_Math/vectorN.h @@ -19,7 +19,7 @@ #include #include -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) #include #endif @@ -33,14 +33,14 @@ public: } inline T & operator[](uint8_t i) { -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < N); #endif return _v[i]; } inline const T & operator[](uint8_t i) const { -#if MATH_CHECK_INDEXES +#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1) assert(i >= 0 && i < N); #endif return _v[i];