AP_Math: define MATH_CHECK_INDEXES

Wrapped in ifndefs so the top-level Makefile can override

Assume MATH_CHECK_INDEXES is always defined
This commit is contained in:
Peter Barker 2016-02-15 09:22:23 +11:00 committed by Lucas De Marchi
parent ca4017d093
commit 80bc7a50d7
5 changed files with 20 additions and 11 deletions

View File

@ -3,6 +3,15 @@
#ifndef AP_MATH_H
#define AP_MATH_H
// MATH_CHECK_INDEXES modifies some objects (e.g. SoloGimbalEKF) to
// include more debug information. It is also used by some functions
// to add extra code for debugging purposes. If you wish to activate
// this, do it here or as part of the top-level Makefile -
// e.g. Tools/Replay/Makefile
#ifndef MATH_CHECK_INDEXES
#define MATH_CHECK_INDEXES 0
#endif
// Assorted useful math operations for ArduPilot(Mega)
#include <AP_Common/AP_Common.h>

View File

@ -128,7 +128,7 @@ public:
// allow a Matrix3 to be used as an array of vectors, 0 indexed
Vector3<T> & operator[](uint8_t i) {
Vector3<T> *_v = &a;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < 3);
#endif
return _v[i];
@ -136,7 +136,7 @@ public:
const Vector3<T> & operator[](uint8_t i) const {
const Vector3<T> *_v = &a;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < 3);
#endif
return _v[i];

View File

@ -21,7 +21,7 @@
#define QUATERNION_H
#include <math.h>
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
#include <assert.h>
#endif
@ -106,7 +106,7 @@ public:
// allow a quaternion to be used as an array, 0 indexed
float & operator[](uint8_t i) {
float *_v = &q1;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i < 4);
#endif
return _v[i];
@ -114,7 +114,7 @@ public:
const float & operator[](uint8_t i) const {
const float *_v = &q1;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i < 4);
#endif
return _v[i];

View File

@ -55,7 +55,7 @@
#include <string.h>
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
#include <assert.h>
#endif
@ -120,7 +120,7 @@ public:
// allow a vector3 to be used as an array, 0 indexed
T & operator[](uint8_t i) {
T *_v = &x;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < 3);
#endif
return _v[i];
@ -128,7 +128,7 @@ public:
const T & operator[](uint8_t i) const {
const T *_v = &x;
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < 3);
#endif
return _v[i];

View File

@ -19,7 +19,7 @@
#include <math.h>
#include <string.h>
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
#include <assert.h>
#endif
@ -33,14 +33,14 @@ public:
}
inline T & operator[](uint8_t i) {
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < N);
#endif
return _v[i];
}
inline const T & operator[](uint8_t i) const {
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#if MATH_CHECK_INDEXES
assert(i >= 0 && i < N);
#endif
return _v[i];