Browse Source

Some minor fixes prompted while looking at the code for other reasons.

Return non-const values from assignment.  Fix operator* for matrix3.



git-svn-id: https://arducopter.googlecode.com/svn/trunk@536 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
DrZiplok@gmail.com 15 years ago
parent
commit
646045ef44
  1. 20
      libraries/AP_Math/matrix3.h
  2. 2
      libraries/AP_Math/vector2.h
  3. 2
      libraries/AP_Math/vector3.h

20
libraries/AP_Math/matrix3.h

@ -60,7 +60,7 @@ public: @@ -60,7 +60,7 @@ public:
{ return (a!=m.a || b!=m.b || c!=m.c); }
// set to value
const Matrix3<T> &operator = (const Matrix3<T> &m)
Matrix3<T> &operator = (const Matrix3<T> &m)
{
a= m.a; b= m.b; c= m.c;
return *this;
@ -103,15 +103,15 @@ public: @@ -103,15 +103,15 @@ public:
// multiplication by another Matrix3<T>
const Matrix3<T> operator *(const Matrix3<T> &m) const
{
Matrix3<T> temp = (Vector3<T>(a.x * m.a.x + a.y * m.b.x + a.z * m.c.x,
a.x * m.a.y + a.y * m.b.y + a.z * m.c.y,
a.x * m.a.z + a.y * m.b.z + a.z * m.c.z),
Vector3<T>(b.x * m.a.x + b.y * m.b.x + b.z * m.c.x,
b.x * m.a.y + b.y * m.b.y + b.z * m.c.y,
b.x * m.a.z + b.y * m.b.z + b.z * m.c.z),
Vector3<T>(c.x * m.a.x + c.y * m.b.x + c.z * m.c.x,
c.x * m.a.y + c.y * m.b.y + c.z * m.c.y,
c.x * m.a.z + c.y * m.b.z + c.z * m.c.z));
Matrix3<T> temp (Vector3<T>(a.x * m.a.x + a.y * m.b.x + a.z * m.c.x,
a.x * m.a.y + a.y * m.b.y + a.z * m.c.y,
a.x * m.a.z + a.y * m.b.z + a.z * m.c.z),
Vector3<T>(b.x * m.a.x + b.y * m.b.x + b.z * m.c.x,
b.x * m.a.y + b.y * m.b.y + b.z * m.c.y,
b.x * m.a.z + b.y * m.b.z + b.z * m.c.z),
Vector3<T>(c.x * m.a.x + c.y * m.b.x + c.z * m.c.x,
c.x * m.a.y + c.y * m.b.y + c.z * m.c.y,
c.x * m.a.z + c.y * m.b.z + c.z * m.c.z));
return temp;
}
const Matrix3<T> operator *=(const Matrix3<T> &m)

2
libraries/AP_Math/vector2.h

@ -58,7 +58,7 @@ struct Vector2 @@ -58,7 +58,7 @@ struct Vector2
{ return (x!=v.x || y!=v.y); }
// set to value
const Vector2<T> &operator =(const Vector2<T> &v)
Vector2<T> &operator =(const Vector2<T> &v)
{
x= v.x; y= v.y;
return *this;

2
libraries/AP_Math/vector3.h

@ -68,7 +68,7 @@ public: @@ -68,7 +68,7 @@ public:
{ return (x!=v.x || y!=v.y || z!=v.z); }
// set to value
const Vector3<T> &operator =(const Vector3<T> &v)
Vector3<T> &operator =(const Vector3<T> &v)
{
x= v.x; y= v.y; z= v.z;
return *this;

Loading…
Cancel
Save