diff --git a/libraries/AP_Math/AP_GeodesicGrid.cpp b/libraries/AP_Math/AP_GeodesicGrid.cpp index edf7a409f8..af21be10da 100644 --- a/libraries/AP_Math/AP_GeodesicGrid.cpp +++ b/libraries/AP_Math/AP_GeodesicGrid.cpp @@ -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; } diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index fa8e4dd6e9..f5462ba0ae 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -62,9 +62,9 @@ void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const template void Matrix3::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); diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 3813b40118..0cd80d4e4a 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -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 &v) const;