Program Listing for File Matrix3x3.h
↰ Return to documentation for file (include/tf2/LinearMath/Matrix3x3.h
)
/*
Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef TF2_MATRIX3x3_H
#define TF2_MATRIX3x3_H
#include "Vector3.h"
#include "Quaternion.h"
#include "tf2/visibility_control.h"
namespace tf2
{
#define Matrix3x3Data Matrix3x3DoubleData
class Matrix3x3 {
Vector3 m_el[3];
public:
TF2_PUBLIC
Matrix3x3 () {}
// explicit Matrix3x3(const tf2Scalar *m) { setFromOpenGLSubMatrix(m); }
TF2_PUBLIC
explicit Matrix3x3(const Quaternion& q) { setRotation(q); }
/*
template <typename tf2Scalar>
Matrix3x3(const tf2Scalar& yaw, const tf2Scalar& pitch, const tf2Scalar& roll)
{
setEulerYPR(yaw, pitch, roll);
}
*/
TF2_PUBLIC
Matrix3x3(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz,
const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz,
const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz)
{
setValue(xx, xy, xz,
yx, yy, yz,
zx, zy, zz);
}
TF2SIMD_FORCE_INLINE Matrix3x3 (const Matrix3x3& other)
{
m_el[0] = other.m_el[0];
m_el[1] = other.m_el[1];
m_el[2] = other.m_el[2];
}
TF2SIMD_FORCE_INLINE Matrix3x3& operator=(const Matrix3x3& other)
{
m_el[0] = other.m_el[0];
m_el[1] = other.m_el[1];
m_el[2] = other.m_el[2];
return *this;
}
TF2SIMD_FORCE_INLINE Vector3 getColumn(int i) const
{
return Vector3(m_el[0][i],m_el[1][i],m_el[2][i]);
}
TF2SIMD_FORCE_INLINE const Vector3& getRow(int i) const
{
tf2FullAssert(0 <= i && i < 3);
return m_el[i];
}
TF2SIMD_FORCE_INLINE Vector3& operator[](int i)
{
tf2FullAssert(0 <= i && i < 3);
return m_el[i];
}
TF2SIMD_FORCE_INLINE const Vector3& operator[](int i) const
{
tf2FullAssert(0 <= i && i < 3);
return m_el[i];
}
TF2_PUBLIC
Matrix3x3& operator*=(const Matrix3x3& m);
TF2_PUBLIC
void setFromOpenGLSubMatrix(const tf2Scalar *m)
{
m_el[0].setValue(m[0],m[4],m[8]);
m_el[1].setValue(m[1],m[5],m[9]);
m_el[2].setValue(m[2],m[6],m[10]);
}
TF2_PUBLIC
void setValue(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz,
const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz,
const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz)
{
m_el[0].setValue(xx,xy,xz);
m_el[1].setValue(yx,yy,yz);
m_el[2].setValue(zx,zy,zz);
}
TF2_PUBLIC
void setRotation(const Quaternion& q)
{
tf2Scalar d = q.length2();
tf2FullAssert(d != tf2Scalar(0.0));
tf2Scalar s = tf2Scalar(2.0) / d;
tf2Scalar xs = q.x() * s, ys = q.y() * s, zs = q.z() * s;
tf2Scalar wx = q.w() * xs, wy = q.w() * ys, wz = q.w() * zs;
tf2Scalar xx = q.x() * xs, xy = q.x() * ys, xz = q.x() * zs;
tf2Scalar yy = q.y() * ys, yz = q.y() * zs, zz = q.z() * zs;
setValue(tf2Scalar(1.0) - (yy + zz), xy - wz, xz + wy,
xy + wz, tf2Scalar(1.0) - (xx + zz), yz - wx,
xz - wy, yz + wx, tf2Scalar(1.0) - (xx + yy));
}
TF2_PUBLIC
void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY,tf2Scalar eulerX) {
tf2Scalar ci ( tf2Cos(eulerX));
tf2Scalar cj ( tf2Cos(eulerY));
tf2Scalar ch ( tf2Cos(eulerZ));
tf2Scalar si ( tf2Sin(eulerX));
tf2Scalar sj ( tf2Sin(eulerY));
tf2Scalar sh ( tf2Sin(eulerZ));
tf2Scalar cc = ci * ch;
tf2Scalar cs = ci * sh;
tf2Scalar sc = si * ch;
tf2Scalar ss = si * sh;
setValue(cj * ch, sj * sc - cs, sj * cc + ss,
cj * sh, sj * ss + cc, sj * cs - sc,
-sj, cj * si, cj * ci);
}
TF2_PUBLIC
void setRPY(tf2Scalar roll, tf2Scalar pitch,tf2Scalar yaw) {
setEulerYPR(yaw, pitch, roll);
}
TF2_PUBLIC
void setIdentity()
{
setValue(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0),
tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0),
tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0));
}
TF2_PUBLIC
static const Matrix3x3& getIdentity()
{
static const Matrix3x3 identityMatrix(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0),
tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0),
tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0));
return identityMatrix;
}
TF2_PUBLIC
void getOpenGLSubMatrix(tf2Scalar *m) const
{
m[0] = tf2Scalar(m_el[0].x());
m[1] = tf2Scalar(m_el[1].x());
m[2] = tf2Scalar(m_el[2].x());
m[3] = tf2Scalar(0.0);
m[4] = tf2Scalar(m_el[0].y());
m[5] = tf2Scalar(m_el[1].y());
m[6] = tf2Scalar(m_el[2].y());
m[7] = tf2Scalar(0.0);
m[8] = tf2Scalar(m_el[0].z());
m[9] = tf2Scalar(m_el[1].z());
m[10] = tf2Scalar(m_el[2].z());
m[11] = tf2Scalar(0.0);
}
TF2_PUBLIC
void getRotation(Quaternion& q) const
{
tf2Scalar trace = m_el[0].x() + m_el[1].y() + m_el[2].z();
tf2Scalar temp[4];
if (trace > tf2Scalar(0.0))
{
tf2Scalar s = tf2Sqrt(trace + tf2Scalar(1.0));
temp[3]=(s * tf2Scalar(0.5));
s = tf2Scalar(0.5) / s;
temp[0]=((m_el[2].y() - m_el[1].z()) * s);
temp[1]=((m_el[0].z() - m_el[2].x()) * s);
temp[2]=((m_el[1].x() - m_el[0].y()) * s);
}
else
{
int i = m_el[0].x() < m_el[1].y() ?
(m_el[1].y() < m_el[2].z() ? 2 : 1) :
(m_el[0].x() < m_el[2].z() ? 2 : 0);
int j = (i + 1) % 3;
int k = (i + 2) % 3;
tf2Scalar s = tf2Sqrt(m_el[i][i] - m_el[j][j] - m_el[k][k] + tf2Scalar(1.0));
temp[i] = s * tf2Scalar(0.5);
s = tf2Scalar(0.5) / s;
temp[3] = (m_el[k][j] - m_el[j][k]) * s;
temp[j] = (m_el[j][i] + m_el[i][j]) * s;
temp[k] = (m_el[k][i] + m_el[i][k]) * s;
}
q.setValue(temp[0],temp[1],temp[2],temp[3]);
}
TF2_PUBLIC
void getEulerYPR(tf2Scalar& yaw, tf2Scalar& pitch, tf2Scalar& roll, unsigned int solution_number = 1) const
{
struct Euler
{
tf2Scalar yaw;
tf2Scalar pitch;
tf2Scalar roll;
};
Euler euler_out;
Euler euler_out2; //second solution
//get the pointer to the raw data
// Check that pitch is not at a singularity
// Check that pitch is not at a singularity
if (tf2Fabs(m_el[2].x()) >= 1)
{
euler_out.yaw = 0;
euler_out2.yaw = 0;
// From difference of angles formula
tf2Scalar delta = tf2Atan2(m_el[2].y(),m_el[2].z());
if (m_el[2].x() < 0) //gimbal locked down
{
euler_out.pitch = TF2SIMD_PI / tf2Scalar(2.0);
euler_out2.pitch = TF2SIMD_PI / tf2Scalar(2.0);
euler_out.roll = delta;
euler_out2.roll = delta;
}
else // gimbal locked up
{
euler_out.pitch = -TF2SIMD_PI / tf2Scalar(2.0);
euler_out2.pitch = -TF2SIMD_PI / tf2Scalar(2.0);
euler_out.roll = delta;
euler_out2.roll = delta;
}
}
else
{
euler_out.pitch = - tf2Asin(m_el[2].x());
euler_out2.pitch = TF2SIMD_PI - euler_out.pitch;
euler_out.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out.pitch),
m_el[2].z()/tf2Cos(euler_out.pitch));
euler_out2.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out2.pitch),
m_el[2].z()/tf2Cos(euler_out2.pitch));
euler_out.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out.pitch),
m_el[0].x()/tf2Cos(euler_out.pitch));
euler_out2.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out2.pitch),
m_el[0].x()/tf2Cos(euler_out2.pitch));
}
if (solution_number == 1)
{
yaw = euler_out.yaw;
pitch = euler_out.pitch;
roll = euler_out.roll;
}
else
{
yaw = euler_out2.yaw;
pitch = euler_out2.pitch;
roll = euler_out2.roll;
}
}
TF2_PUBLIC
void getRPY(tf2Scalar& roll, tf2Scalar& pitch, tf2Scalar& yaw, unsigned int solution_number = 1) const
{
getEulerYPR(yaw, pitch, roll, solution_number);
}
TF2_PUBLIC
Matrix3x3 scaled(const Vector3& s) const
{
return Matrix3x3(m_el[0].x() * s.x(), m_el[0].y() * s.y(), m_el[0].z() * s.z(),
m_el[1].x() * s.x(), m_el[1].y() * s.y(), m_el[1].z() * s.z(),
m_el[2].x() * s.x(), m_el[2].y() * s.y(), m_el[2].z() * s.z());
}
TF2_PUBLIC
tf2Scalar determinant() const;
TF2_PUBLIC
Matrix3x3 adjoint() const;
TF2_PUBLIC
Matrix3x3 absolute() const;
TF2_PUBLIC
Matrix3x3 transpose() const;
TF2_PUBLIC
Matrix3x3 inverse() const;
TF2_PUBLIC
Matrix3x3 transposeTimes(const Matrix3x3& m) const;
TF2_PUBLIC
Matrix3x3 timesTranspose(const Matrix3x3& m) const;
TF2SIMD_FORCE_INLINE tf2Scalar tdotx(const Vector3& v) const
{
return m_el[0].x() * v.x() + m_el[1].x() * v.y() + m_el[2].x() * v.z();
}
TF2SIMD_FORCE_INLINE tf2Scalar tdoty(const Vector3& v) const
{
return m_el[0].y() * v.x() + m_el[1].y() * v.y() + m_el[2].y() * v.z();
}
TF2SIMD_FORCE_INLINE tf2Scalar tdotz(const Vector3& v) const
{
return m_el[0].z() * v.x() + m_el[1].z() * v.y() + m_el[2].z() * v.z();
}
TF2_PUBLIC
void diagonalize(Matrix3x3& rot, tf2Scalar threshold, int maxSteps)
{
rot.setIdentity();
for (int step = maxSteps; step > 0; step--)
{
// find off-diagonal element [p][q] with largest magnitude
int p = 0;
int q = 1;
int r = 2;
tf2Scalar max = tf2Fabs(m_el[0][1]);
tf2Scalar v = tf2Fabs(m_el[0][2]);
if (v > max)
{
q = 2;
r = 1;
max = v;
}
v = tf2Fabs(m_el[1][2]);
if (v > max)
{
p = 1;
q = 2;
r = 0;
max = v;
}
tf2Scalar t = threshold * (tf2Fabs(m_el[0][0]) + tf2Fabs(m_el[1][1]) + tf2Fabs(m_el[2][2]));
if (max <= t)
{
if (max <= TF2SIMD_EPSILON * t)
{
return;
}
step = 1;
}
// compute Jacobi rotation J which leads to a zero for element [p][q]
tf2Scalar mpq = m_el[p][q];
tf2Scalar theta = (m_el[q][q] - m_el[p][p]) / (2 * mpq);
tf2Scalar theta2 = theta * theta;
tf2Scalar cos;
tf2Scalar sin;
if (theta2 * theta2 < tf2Scalar(10 / TF2SIMD_EPSILON))
{
t = (theta >= 0) ? 1 / (theta + tf2Sqrt(1 + theta2))
: 1 / (theta - tf2Sqrt(1 + theta2));
cos = 1 / tf2Sqrt(1 + t * t);
sin = cos * t;
}
else
{
// approximation for large theta-value, i.e., a nearly diagonal matrix
t = 1 / (theta * (2 + tf2Scalar(0.5) / theta2));
cos = 1 - tf2Scalar(0.5) * t * t;
sin = cos * t;
}
// apply rotation to matrix (this = J^T * this * J)
m_el[p][q] = m_el[q][p] = 0;
m_el[p][p] -= t * mpq;
m_el[q][q] += t * mpq;
tf2Scalar mrp = m_el[r][p];
tf2Scalar mrq = m_el[r][q];
m_el[r][p] = m_el[p][r] = cos * mrp - sin * mrq;
m_el[r][q] = m_el[q][r] = cos * mrq + sin * mrp;
// apply rotation to rot (rot = rot * J)
for (int i = 0; i < 3; i++)
{
Vector3& row = rot[i];
mrp = row[p];
mrq = row[q];
row[p] = cos * mrp - sin * mrq;
row[q] = cos * mrq + sin * mrp;
}
}
}
TF2_PUBLIC
tf2Scalar cofac(int r1, int c1, int r2, int c2) const
{
return m_el[r1][c1] * m_el[r2][c2] - m_el[r1][c2] * m_el[r2][c1];
}
TF2_PUBLIC
void serialize(struct Matrix3x3Data& dataOut) const;
TF2_PUBLIC
void serializeFloat(struct Matrix3x3FloatData& dataOut) const;
TF2_PUBLIC
void deSerialize(const struct Matrix3x3Data& dataIn);
TF2_PUBLIC
void deSerializeFloat(const struct Matrix3x3FloatData& dataIn);
TF2_PUBLIC
void deSerializeDouble(const struct Matrix3x3DoubleData& dataIn);
};
TF2SIMD_FORCE_INLINE Matrix3x3&
Matrix3x3::operator*=(const Matrix3x3& m)
{
setValue(m.tdotx(m_el[0]), m.tdoty(m_el[0]), m.tdotz(m_el[0]),
m.tdotx(m_el[1]), m.tdoty(m_el[1]), m.tdotz(m_el[1]),
m.tdotx(m_el[2]), m.tdoty(m_el[2]), m.tdotz(m_el[2]));
return *this;
}
TF2SIMD_FORCE_INLINE tf2Scalar
Matrix3x3::determinant() const
{
return tf2Triple((*this)[0], (*this)[1], (*this)[2]);
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::absolute() const
{
return Matrix3x3(
tf2Fabs(m_el[0].x()), tf2Fabs(m_el[0].y()), tf2Fabs(m_el[0].z()),
tf2Fabs(m_el[1].x()), tf2Fabs(m_el[1].y()), tf2Fabs(m_el[1].z()),
tf2Fabs(m_el[2].x()), tf2Fabs(m_el[2].y()), tf2Fabs(m_el[2].z()));
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::transpose() const
{
return Matrix3x3(m_el[0].x(), m_el[1].x(), m_el[2].x(),
m_el[0].y(), m_el[1].y(), m_el[2].y(),
m_el[0].z(), m_el[1].z(), m_el[2].z());
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::adjoint() const
{
return Matrix3x3(cofac(1, 1, 2, 2), cofac(0, 2, 2, 1), cofac(0, 1, 1, 2),
cofac(1, 2, 2, 0), cofac(0, 0, 2, 2), cofac(0, 2, 1, 0),
cofac(1, 0, 2, 1), cofac(0, 1, 2, 0), cofac(0, 0, 1, 1));
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::inverse() const
{
Vector3 co(cofac(1, 1, 2, 2), cofac(1, 2, 2, 0), cofac(1, 0, 2, 1));
tf2Scalar det = (*this)[0].dot(co);
tf2FullAssert(det != tf2Scalar(0.0));
tf2Scalar s = tf2Scalar(1.0) / det;
return Matrix3x3(co.x() * s, cofac(0, 2, 2, 1) * s, cofac(0, 1, 1, 2) * s,
co.y() * s, cofac(0, 0, 2, 2) * s, cofac(0, 2, 1, 0) * s,
co.z() * s, cofac(0, 1, 2, 0) * s, cofac(0, 0, 1, 1) * s);
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::transposeTimes(const Matrix3x3& m) const
{
return Matrix3x3(
m_el[0].x() * m[0].x() + m_el[1].x() * m[1].x() + m_el[2].x() * m[2].x(),
m_el[0].x() * m[0].y() + m_el[1].x() * m[1].y() + m_el[2].x() * m[2].y(),
m_el[0].x() * m[0].z() + m_el[1].x() * m[1].z() + m_el[2].x() * m[2].z(),
m_el[0].y() * m[0].x() + m_el[1].y() * m[1].x() + m_el[2].y() * m[2].x(),
m_el[0].y() * m[0].y() + m_el[1].y() * m[1].y() + m_el[2].y() * m[2].y(),
m_el[0].y() * m[0].z() + m_el[1].y() * m[1].z() + m_el[2].y() * m[2].z(),
m_el[0].z() * m[0].x() + m_el[1].z() * m[1].x() + m_el[2].z() * m[2].x(),
m_el[0].z() * m[0].y() + m_el[1].z() * m[1].y() + m_el[2].z() * m[2].y(),
m_el[0].z() * m[0].z() + m_el[1].z() * m[1].z() + m_el[2].z() * m[2].z());
}
TF2SIMD_FORCE_INLINE Matrix3x3
Matrix3x3::timesTranspose(const Matrix3x3& m) const
{
return Matrix3x3(
m_el[0].dot(m[0]), m_el[0].dot(m[1]), m_el[0].dot(m[2]),
m_el[1].dot(m[0]), m_el[1].dot(m[1]), m_el[1].dot(m[2]),
m_el[2].dot(m[0]), m_el[2].dot(m[1]), m_el[2].dot(m[2]));
}
TF2SIMD_FORCE_INLINE Vector3
operator*(const Matrix3x3& m, const Vector3& v)
{
return Vector3(m[0].dot(v), m[1].dot(v), m[2].dot(v));
}
TF2SIMD_FORCE_INLINE Vector3
operator*(const Vector3& v, const Matrix3x3& m)
{
return Vector3(m.tdotx(v), m.tdoty(v), m.tdotz(v));
}
TF2SIMD_FORCE_INLINE Matrix3x3
operator*(const Matrix3x3& m1, const Matrix3x3& m2)
{
return Matrix3x3(
m2.tdotx( m1[0]), m2.tdoty( m1[0]), m2.tdotz( m1[0]),
m2.tdotx( m1[1]), m2.tdoty( m1[1]), m2.tdotz( m1[1]),
m2.tdotx( m1[2]), m2.tdoty( m1[2]), m2.tdotz( m1[2]));
}
/*
TF2SIMD_FORCE_INLINE Matrix3x3 tf2MultTransposeLeft(const Matrix3x3& m1, const Matrix3x3& m2) {
return Matrix3x3(
m1[0][0] * m2[0][0] + m1[1][0] * m2[1][0] + m1[2][0] * m2[2][0],
m1[0][0] * m2[0][1] + m1[1][0] * m2[1][1] + m1[2][0] * m2[2][1],
m1[0][0] * m2[0][2] + m1[1][0] * m2[1][2] + m1[2][0] * m2[2][2],
m1[0][1] * m2[0][0] + m1[1][1] * m2[1][0] + m1[2][1] * m2[2][0],
m1[0][1] * m2[0][1] + m1[1][1] * m2[1][1] + m1[2][1] * m2[2][1],
m1[0][1] * m2[0][2] + m1[1][1] * m2[1][2] + m1[2][1] * m2[2][2],
m1[0][2] * m2[0][0] + m1[1][2] * m2[1][0] + m1[2][2] * m2[2][0],
m1[0][2] * m2[0][1] + m1[1][2] * m2[1][1] + m1[2][2] * m2[2][1],
m1[0][2] * m2[0][2] + m1[1][2] * m2[1][2] + m1[2][2] * m2[2][2]);
}
*/
TF2SIMD_FORCE_INLINE bool operator==(const Matrix3x3& m1, const Matrix3x3& m2)
{
return ( m1[0][0] == m2[0][0] && m1[1][0] == m2[1][0] && m1[2][0] == m2[2][0] &&
m1[0][1] == m2[0][1] && m1[1][1] == m2[1][1] && m1[2][1] == m2[2][1] &&
m1[0][2] == m2[0][2] && m1[1][2] == m2[1][2] && m1[2][2] == m2[2][2] );
}
struct Matrix3x3FloatData
{
Vector3FloatData m_el[3];
};
struct Matrix3x3DoubleData
{
Vector3DoubleData m_el[3];
};
TF2SIMD_FORCE_INLINE void Matrix3x3::serialize(struct Matrix3x3Data& dataOut) const
{
for (int i=0;i<3;i++)
m_el[i].serialize(dataOut.m_el[i]);
}
TF2SIMD_FORCE_INLINE void Matrix3x3::serializeFloat(struct Matrix3x3FloatData& dataOut) const
{
for (int i=0;i<3;i++)
m_el[i].serializeFloat(dataOut.m_el[i]);
}
TF2SIMD_FORCE_INLINE void Matrix3x3::deSerialize(const struct Matrix3x3Data& dataIn)
{
for (int i=0;i<3;i++)
m_el[i].deSerialize(dataIn.m_el[i]);
}
TF2SIMD_FORCE_INLINE void Matrix3x3::deSerializeFloat(const struct Matrix3x3FloatData& dataIn)
{
for (int i=0;i<3;i++)
m_el[i].deSerializeFloat(dataIn.m_el[i]);
}
TF2SIMD_FORCE_INLINE void Matrix3x3::deSerializeDouble(const struct Matrix3x3DoubleData& dataIn)
{
for (int i=0;i<3;i++)
m_el[i].deSerializeDouble(dataIn.m_el[i]);
}
}
#endif //TF2_MATRIX3x3_H