mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: remove trailing whitespace on headers
This commit is contained in:
parent
ab1fa4b435
commit
1dbffef7ea
@ -63,7 +63,7 @@ public:
|
|||||||
VectorN<T,N> v2;
|
VectorN<T,N> v2;
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
v2[i] = - _v[i];
|
v2[i] = - _v[i];
|
||||||
}
|
}
|
||||||
return v2;
|
return v2;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -72,7 +72,7 @@ public:
|
|||||||
VectorN<T,N> v2;
|
VectorN<T,N> v2;
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
v2[i] = _v[i] + v[i];
|
v2[i] = _v[i] + v[i];
|
||||||
}
|
}
|
||||||
return v2;
|
return v2;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -81,7 +81,7 @@ public:
|
|||||||
VectorN<T,N> v2;
|
VectorN<T,N> v2;
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
v2[i] = _v[i] - v[i];
|
v2[i] = _v[i] - v[i];
|
||||||
}
|
}
|
||||||
return v2;
|
return v2;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -90,7 +90,7 @@ public:
|
|||||||
VectorN<T,N> v2;
|
VectorN<T,N> v2;
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
v2[i] = _v[i] * num;
|
v2[i] = _v[i] * num;
|
||||||
}
|
}
|
||||||
return v2;
|
return v2;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -99,7 +99,7 @@ public:
|
|||||||
VectorN<T,N> v2;
|
VectorN<T,N> v2;
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
v2[i] = _v[i] / num;
|
v2[i] = _v[i] / num;
|
||||||
}
|
}
|
||||||
return v2;
|
return v2;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -107,7 +107,7 @@ public:
|
|||||||
VectorN<T,N> &operator +=(const VectorN<T,N> &v) {
|
VectorN<T,N> &operator +=(const VectorN<T,N> &v) {
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
_v[i] += v[i];
|
_v[i] += v[i];
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -115,7 +115,7 @@ public:
|
|||||||
VectorN<T,N> &operator -=(const VectorN<T,N> &v) {
|
VectorN<T,N> &operator -=(const VectorN<T,N> &v) {
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
_v[i] -= v[i];
|
_v[i] -= v[i];
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -123,7 +123,7 @@ public:
|
|||||||
VectorN<T,N> &operator *=(const T num) {
|
VectorN<T,N> &operator *=(const T num) {
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
_v[i] *= num;
|
_v[i] *= num;
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -131,7 +131,7 @@ public:
|
|||||||
VectorN<T,N> &operator /=(const T num) {
|
VectorN<T,N> &operator /=(const T num) {
|
||||||
for (uint8_t i=0; i<N; i++) {
|
for (uint8_t i=0; i<N; i++) {
|
||||||
_v[i] /= num;
|
_v[i] /= num;
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user