AP_Math: Changes to fix the warnings in rover sitl build.

We are starting the process of resolving all the warnings in the
ardupilot builds of all vehicles and platforms.
This commit is contained in:
Grant Morphett 2015-02-05 17:33:39 +11:00 committed by Andrew Tridgell
parent b511410b48
commit 300a02f4e4
4 changed files with 11 additions and 11 deletions

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 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<T> & operator[](uint8_t i) const {
const Vector3<T> *_v = &a;
#if MATH_CHECK_INDEXES
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
assert(i >= 0 && i < 3);
#endif
return _v[i];

View File

@ -21,7 +21,7 @@
#define QUATERNION_H
#include <math.h>
#if MATH_CHECK_INDEXES
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#include <assert.h>
#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];

View File

@ -53,7 +53,7 @@
#include <math.h>
#include <string.h>
#if MATH_CHECK_INDEXES
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#include <assert.h>
#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];

View File

@ -19,7 +19,7 @@
#include <math.h>
#include <string.h>
#if MATH_CHECK_INDEXES
#if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
#include <assert.h>
#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];