mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
9db013e648
commit
646045ef44
|
@ -60,7 +60,7 @@ public:
|
||||||
{ return (a!=m.a || b!=m.b || c!=m.c); }
|
{ return (a!=m.a || b!=m.b || c!=m.c); }
|
||||||
|
|
||||||
// set to value
|
// 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;
|
a= m.a; b= m.b; c= m.c;
|
||||||
return *this;
|
return *this;
|
||||||
|
@ -103,7 +103,7 @@ public:
|
||||||
// multiplication by another Matrix3<T>
|
// multiplication by another Matrix3<T>
|
||||||
const Matrix3<T> operator *(const Matrix3<T> &m) const
|
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,
|
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.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),
|
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,
|
Vector3<T>(b.x * m.a.x + b.y * m.b.x + b.z * m.c.x,
|
||||||
|
|
|
@ -58,7 +58,7 @@ struct Vector2
|
||||||
{ return (x!=v.x || y!=v.y); }
|
{ return (x!=v.x || y!=v.y); }
|
||||||
|
|
||||||
// set to value
|
// set to value
|
||||||
const Vector2<T> &operator =(const Vector2<T> &v)
|
Vector2<T> &operator =(const Vector2<T> &v)
|
||||||
{
|
{
|
||||||
x= v.x; y= v.y;
|
x= v.x; y= v.y;
|
||||||
return *this;
|
return *this;
|
||||||
|
|
|
@ -68,7 +68,7 @@ public:
|
||||||
{ return (x!=v.x || y!=v.y || z!=v.z); }
|
{ return (x!=v.x || y!=v.y || z!=v.z); }
|
||||||
|
|
||||||
// set to value
|
// 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;
|
x= v.x; y= v.y; z= v.z;
|
||||||
return *this;
|
return *this;
|
||||||
|
|
Loading…
Reference in New Issue