mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: fixed warnings on bounds checking in quaternion
This commit is contained in:
parent
3d46680348
commit
fefdc37a4d
@ -91,7 +91,7 @@ public:
|
||||
float & operator[](uint8_t i) {
|
||||
float *_v = &q1;
|
||||
#if MATH_CHECK_INDEXES
|
||||
assert(i >= 0 && i < 4);
|
||||
assert(i < 4);
|
||||
#endif
|
||||
return _v[i];
|
||||
}
|
||||
@ -99,7 +99,7 @@ public:
|
||||
const float & operator[](uint8_t i) const {
|
||||
const float *_v = &q1;
|
||||
#if MATH_CHECK_INDEXES
|
||||
assert(i >= 0 && i < 4);
|
||||
assert(i < 4);
|
||||
#endif
|
||||
return _v[i];
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user