Remove a bunch of probably wrong const cruft. Ditch the dubious array index operators from vector2.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@538 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2010-09-22 17:41:49 +00:00
parent 815e5f871a
commit ac2e14c4ec
3 changed files with 33 additions and 41 deletions

View File

@ -60,33 +60,33 @@ public:
{ return (a!=m.a || b!=m.b || c!=m.c); } { return (a!=m.a || b!=m.b || c!=m.c); }
// negation // negation
const Matrix3<T> operator - (void) const Matrix3<T> operator - (void) const
{ return Matrix3<T>(-a,-b,-c); } { return Matrix3<T>(-a,-b,-c); }
// addition // addition
const Matrix3<T> operator + (const Matrix3<T> &m) const Matrix3<T> operator + (const Matrix3<T> &m) const
{ return Matrix3<T>(a+m.a, b+m.b, c+m.c); } { return Matrix3<T>(a+m.a, b+m.b, c+m.c); }
const Matrix3<T> &operator += (const Matrix3<T> &m) Matrix3<T> &operator += (const Matrix3<T> &m)
{ return *this = *this + m; } { return *this = *this + m; }
// subtraction // subtraction
const Matrix3<T> operator - (const Matrix3<T> &m) const Matrix3<T> operator - (const Matrix3<T> &m) const
{ return Matrix3<T>(a-m.a, b-m.b, c-m.c); } { return Matrix3<T>(a-m.a, b-m.b, c-m.c); }
const Matrix3<T> &operator -= (const Matrix3<T> &m) Matrix3<T> &operator -= (const Matrix3<T> &m)
{ return *this = *this - m; } { return *this = *this - m; }
// uniform scaling // uniform scaling
const Matrix3<T> operator * (const T num) const Matrix3<T> operator * (const T num) const
{ return Matrix3<T>(a*num, b*num, c*num); } { return Matrix3<T>(a*num, b*num, c*num); }
const Matrix3<T> operator *= (const T num) Matrix3<T> operator *= (const T num)
{ return *this = *this * num; } { return *this = *this * num; }
const Matrix3<T> operator / (const T num) const Matrix3<T> operator / (const T num) const
{ return Matrix3<T>(a/num, b/num, c/num); } { return Matrix3<T>(a/num, b/num, c/num); }
const Matrix3<T> operator /= (const T num) Matrix3<T> operator /= (const T num)
{ return *this = *this / num; } { return *this = *this / num; }
// multiplication by a vector // multiplication by a vector
const Vector3<T> operator *(const Vector3<T> &v) const Vector3<T> operator *(const Vector3<T> &v) const
{ {
return Vector3<T>(a.x * v.x + a.y * v.x + a.z * v.x, return Vector3<T>(a.x * v.x + a.y * v.x + a.z * v.x,
b.x * v.y + b.y * v.y + b.z * v.y, b.x * v.y + b.y * v.y + b.z * v.y,
@ -94,7 +94,7 @@ public:
} }
// multiplication by another Matrix3<T> // multiplication by another Matrix3<T>
const Matrix3<T> operator *(const Matrix3<T> &m) 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,
@ -107,17 +107,17 @@ public:
c.x * m.a.z + c.y * m.b.z + c.z * m.c.z)); c.x * m.a.z + c.y * m.b.z + c.z * m.c.z));
return temp; return temp;
} }
const Matrix3<T> operator *=(const Matrix3<T> &m) Matrix3<T> operator *=(const Matrix3<T> &m)
{ return *this = this * m; } { return *this = this * m; }
// transpose the matrix // transpose the matrix
const Matrix3<T> transposed(void) Matrix3<T> transposed(void)
{ {
return Matrix3<T>(Vector3<T>(a.x, b.x, c.x), return Matrix3<T>(Vector3<T>(a.x, b.x, c.x),
Vector3<T>(a.y, b.y, c.y), Vector3<T>(a.y, b.y, c.y),
Vector3<T>(a.z, b.z, c.z)); Vector3<T>(a.z, b.z, c.z));
} }
const Matrix3<T> transpose(void) Matrix3<T> transpose(void)
{ return *this = transposed(); } { return *this = transposed(); }
}; };

View File

@ -37,14 +37,6 @@ struct Vector2
// setting ctor // setting ctor
Vector2<T>(const T x0, const T y0): x(x0), y(y0) {} Vector2<T>(const T x0, const T y0): x(x0), y(y0) {}
// array indexing
T &operator [](unsigned int i)
{ return *(&x+i); }
// array indexing
const T &operator [](unsigned int i) const
{ return *(&x+i); }
// function call operator // function call operator
void operator ()(const T x0, const T y0) void operator ()(const T x0, const T y0)
{ x= x0; y= y0; } { x= x0; y= y0; }
@ -58,54 +50,54 @@ struct Vector2
{ return (x!=v.x || y!=v.y); } { return (x!=v.x || y!=v.y); }
// negation // negation
const Vector2<T> operator -(void) const Vector2<T> operator -(void) const
{ return Vector2<T>(-x, -y); } { return Vector2<T>(-x, -y); }
// addition // addition
const Vector2<T> operator +(const Vector2<T> &v) const Vector2<T> operator +(const Vector2<T> &v) const
{ return Vector2<T>(x+v.x, y+v.y); } { return Vector2<T>(x+v.x, y+v.y); }
// subtraction // subtraction
const Vector2<T> operator -(const Vector2<T> &v) const Vector2<T> operator -(const Vector2<T> &v) const
{ return Vector2<T>(x-v.x, y-v.y); } { return Vector2<T>(x-v.x, y-v.y); }
// uniform scaling // uniform scaling
const Vector2<T> operator *(const T num) const Vector2<T> operator *(const T num) const
{ {
Vector2<T> temp(*this); Vector2<T> temp(*this);
return temp*=num; return temp*=num;
} }
// uniform scaling // uniform scaling
const Vector2<T> operator /(const T num) const Vector2<T> operator /(const T num) const
{ {
Vector2<T> temp(*this); Vector2<T> temp(*this);
return temp/=num; return temp/=num;
} }
// addition // addition
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;
} }
// subtraction // subtraction
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;
} }
// uniform scaling // uniform scaling
const Vector2<T> &operator *=(const T num) Vector2<T> &operator *=(const T num)
{ {
x*=num; y*=num; x*=num; y*=num;
return *this; return *this;
} }
// uniform scaling // uniform scaling
const Vector2<T> &operator /=(const T num) Vector2<T> &operator /=(const T num)
{ {
x/=num; y/=num; x/=num; y/=num;
return *this; return *this;

View File

@ -68,54 +68,54 @@ public:
{ return (x!=v.x || y!=v.y || z!=v.z); } { return (x!=v.x || y!=v.y || z!=v.z); }
// negation // negation
const Vector3<T> operator -(void) const Vector3<T> operator -(void) const
{ return Vector3<T>(-x,-y,-z); } { return Vector3<T>(-x,-y,-z); }
// addition // addition
const Vector3<T> operator +(const Vector3<T> &v) const Vector3<T> operator +(const Vector3<T> &v) const
{ return Vector3<T>(x+v.x, y+v.y, z+v.z); } { return Vector3<T>(x+v.x, y+v.y, z+v.z); }
// subtraction // subtraction
const Vector3<T> operator -(const Vector3<T> &v) const Vector3<T> operator -(const Vector3<T> &v) const
{ return Vector3<T>(x-v.x, y-v.y, z-v.z); } { return Vector3<T>(x-v.x, y-v.y, z-v.z); }
// uniform scaling // uniform scaling
const Vector3<T> operator *(const T num) const Vector3<T> operator *(const T num) const
{ {
Vector3<T> temp(*this); Vector3<T> temp(*this);
return temp*=num; return temp*=num;
} }
// uniform scaling // uniform scaling
const Vector3<T> operator /(const T num) const Vector3<T> operator /(const T num) const
{ {
Vector3<T> temp(*this); Vector3<T> temp(*this);
return temp/=num; return temp/=num;
} }
// addition // addition
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;
} }
// subtraction // subtraction
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;
} }
// uniform scaling // uniform scaling
const Vector3<T> &operator *=(const T num) Vector3<T> &operator *=(const T num)
{ {
x*=num; y*=num; z*=num; x*=num; y*=num; z*=num;
return *this; return *this;
} }
// uniform scaling // uniform scaling
const Vector3<T> &operator /=(const T num) Vector3<T> &operator /=(const T num)
{ {
x/=num; y/=num; z/=num; x/=num; y/=num; z/=num;
return *this; return *this;
@ -126,7 +126,7 @@ public:
{ return x*v.x + y*v.y + z*v.z; } { return x*v.x + y*v.y + z*v.z; }
// cross product // cross product
const Vector3<T> operator %(const Vector3<T> &v) const Vector3<T> operator %(const Vector3<T> &v) const
{ {
Vector3<T> temp(y*v.z - z*v.y, z*v.x - x*v.z, x*v.y - y*v.x); Vector3<T> temp(y*v.z - z*v.y, z*v.x - x*v.z, x*v.y - y*v.x);
return temp; return temp;