mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_Math: added equality operator for VectorN
This commit is contained in:
parent
e5e04d65ee
commit
0d174db05b
@ -46,6 +46,14 @@ public:
|
|||||||
return _v[i];
|
return _v[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// test for equality
|
||||||
|
bool operator ==(const VectorN<T,N> &v) const {
|
||||||
|
for (uint8_t i=0; i<N; i++) {
|
||||||
|
if (_v[i] != v[i]) return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// zero the vector
|
// zero the vector
|
||||||
inline void zero()
|
inline void zero()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user