mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: add non-uniform Vector3f scaling
This commit is contained in:
parent
2f87d8808f
commit
5521fce676
@ -117,6 +117,12 @@ public:
|
||||
// uniform scaling
|
||||
Vector3<T> &operator /=(const T num);
|
||||
|
||||
// non-uniform scaling
|
||||
Vector3<T> &operator *=(const Vector3<T> &v) {
|
||||
x *= v.x; y *= v.y; z *= v.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
// allow a vector3 to be used as an array, 0 indexed
|
||||
T & operator[](uint8_t i) {
|
||||
T *_v = &x;
|
||||
|
Loading…
Reference in New Issue
Block a user