Browse Source

AP_Math: remove use of Vector3 as function

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
2f8c0dd65b
  1. 4
      libraries/AP_Math/AP_GeodesicGrid.cpp
  2. 6
      libraries/AP_Math/matrix3.cpp
  3. 6
      libraries/AP_Math/vector3.h

4
libraries/AP_Math/AP_GeodesicGrid.cpp

@ -427,10 +427,10 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f &v, bool inclusive) @@ -427,10 +427,10 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f &v, bool inclusive)
w.z = -w.z;
break;
case 1:
w(w.y, w.z, -w.x);
w = {w.y, w.z, -w.x};
break;
case 2:
w(w.z, w.x, -w.y);
w = {w.z, w.x, -w.y};
break;
}

6
libraries/AP_Math/matrix3.cpp

@ -62,9 +62,9 @@ void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw) const @@ -62,9 +62,9 @@ void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw) const
template <typename T>
void Matrix3<T>::from_rotation(enum Rotation rotation)
{
(*this).a(1,0,0);
(*this).b(0,1,0);
(*this).c(0,0,1);
(*this).a = {1,0,0};
(*this).b = {0,1,0};
(*this).c = {0,0,1};
(*this).a.rotate(rotation);
(*this).b.rotate(rotation);

6
libraries/AP_Math/vector3.h

@ -78,12 +78,6 @@ public: @@ -78,12 +78,6 @@ public:
, y(y0)
, z(z0) {}
// function call operator
void operator ()(const T x0, const T y0, const T z0)
{
x= x0; y= y0; z= z0;
}
// test for equality
bool operator ==(const Vector3<T> &v) const;

Loading…
Cancel
Save