Go to the documentation of this file.
16 #ifndef TF_MATRIX3x3_H
17 #define TF_MATRIX3x3_H
28 #define Matrix3x3Data Matrix3x3DoubleData
122 m_el[0].setValue(m[0],m[4],m[8]);
123 m_el[1].setValue(m[1],m[5],m[9]);
124 m_el[2].setValue(m[2],m[6],m[10]);
141 m_el[0].setValue(xx,xy,xz);
142 m_el[1].setValue(yx,yy,yz);
143 m_el[2].setValue(zx,zy,zz);
153 tfScalar xs = q.x() *
s, ys = q.y() *
s, zs = q.z() *
s;
154 tfScalar wx = q.w() * xs, wy = q.w() * ys, wz = q.w() * zs;
155 tfScalar xx = q.x() * xs, xy = q.x() * ys, xz = q.x() * zs;
156 tfScalar yy = q.y() * ys, yz = q.y() * zs, zz = q.z() * zs;
158 xy + wz,
tfScalar(1.0) - (xx + zz), yz - wx,
159 xz - wy, yz + wx,
tfScalar(1.0) - (xx + yy));
194 setValue(cj * ch, sj * sc - cs, sj * cc + ss,
195 cj * sh, sj * ss + cc, sj * cs - sc,
196 -sj, cj * si, cj * ci);
222 return identityMatrix;
256 temp[0]=((
m_el[2].y() -
m_el[1].z()) *
s);
257 temp[1]=((
m_el[0].z() -
m_el[2].x()) *
s);
258 temp[2]=((
m_el[1].x() -
m_el[0].y()) *
s);
263 (
m_el[1].y() <
m_el[2].z() ? 2 : 1) :
264 (
m_el[0].x() <
m_el[2].z() ? 2 : 0);
276 q.setValue(temp[0],temp[1],temp[2],temp[3]);
320 euler_out.roll = delta;
321 euler_out2.roll = delta;
328 euler_out.roll = delta;
329 euler_out2.roll = delta;
335 euler_out2.pitch =
TFSIMD_PI - euler_out.pitch;
348 if (solution_number == 1)
351 pitch = euler_out.pitch;
352 roll = euler_out.roll;
356 yaw = euler_out2.yaw;
357 pitch = euler_out2.pitch;
358 roll = euler_out2.roll;
398 return m_el[0].x() * v.x() +
m_el[1].x() * v.y() +
m_el[2].x() * v.z();
402 return m_el[0].y() * v.x() +
m_el[1].y() * v.y() +
m_el[2].y() * v.z();
406 return m_el[0].z() * v.x() +
m_el[1].z() * v.y() +
m_el[2].z() * v.z();
463 t = (theta >= 0) ? 1 / (theta +
tfSqrt(1 + theta2))
464 : 1 / (theta -
tfSqrt(1 + theta2));
465 cos = 1 /
tfSqrt(1 + t * t);
471 t = 1 / (theta * (2 +
tfScalar(0.5) / theta2));
478 m_el[p][p] -= t * mpq;
479 m_el[q][q] += t * mpq;
482 m_el[r][p] =
m_el[p][r] = cos * mrp - sin * mrq;
483 m_el[r][q] =
m_el[q][r] = cos * mrq + sin * mrp;
486 for (
int i = 0; i < 3; i++)
491 row[p] = cos * mrp - sin * mrq;
492 row[q] = cos * mrq + sin * mrp;
537 return tfTriple((*
this)[0], (*
this)[1], (*
this)[2]);
561 return Matrix3x3(
cofac(1, 1, 2, 2),
cofac(0, 2, 2, 1),
cofac(0, 1, 1, 2),
562 cofac(1, 2, 2, 0),
cofac(0, 0, 2, 2),
cofac(0, 2, 1, 0),
563 cofac(1, 0, 2, 1),
cofac(0, 1, 2, 0),
cofac(0, 0, 1, 1));
569 Vector3 co(
cofac(1, 1, 2, 2),
cofac(1, 2, 2, 0),
cofac(1, 0, 2, 1));
582 m_el[0].x() * m[0].x() +
m_el[1].x() * m[1].x() +
m_el[2].x() * m[2].x(),
583 m_el[0].x() * m[0].y() +
m_el[1].x() * m[1].y() +
m_el[2].x() * m[2].y(),
584 m_el[0].x() * m[0].z() +
m_el[1].x() * m[1].z() +
m_el[2].x() * m[2].z(),
585 m_el[0].y() * m[0].x() +
m_el[1].y() * m[1].x() +
m_el[2].y() * m[2].x(),
586 m_el[0].y() * m[0].y() +
m_el[1].y() * m[1].y() +
m_el[2].y() * m[2].y(),
587 m_el[0].y() * m[0].z() +
m_el[1].y() * m[1].z() +
m_el[2].y() * m[2].z(),
588 m_el[0].z() * m[0].x() +
m_el[1].z() * m[1].x() +
m_el[2].z() * m[2].x(),
589 m_el[0].z() * m[0].y() +
m_el[1].z() * m[1].y() +
m_el[2].z() * m[2].y(),
590 m_el[0].z() * m[0].z() +
m_el[1].z() * m[1].z() +
m_el[2].z() * m[2].z());
644 return ( m1[0][0] == m2[0][0] && m1[1][0] == m2[1][0] && m1[2][0] == m2[2][0] &&
645 m1[0][1] == m2[0][1] && m1[1][1] == m2[1][1] && m1[2][1] == m2[2][1] &&
646 m1[0][2] == m2[0][2] && m1[1][2] == m2[1][2] && m1[2][2] == m2[2][2] );
666 for (
int i=0;i<3;i++)
672 for (
int i=0;i<3;i++)
679 for (
int i=0;i<3;i++)
685 for (
int i=0;i<3;i++)
691 for (
int i=0;i<3;i++)
697 #endif //TF_MATRIX3x3_H
Matrix3x3 transposeTimes(const Matrix3x3 &m) const
The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Q...
void setRPY(tfScalar roll, tfScalar pitch, tfScalar yaw)
Set the matrix using RPY about XYZ fixed axes.
Matrix3x3(const Quaternion &q)
Constructor from Quaternion.
Matrix3x3(const tfScalar &xx, const tfScalar &xy, const tfScalar &xz, const tfScalar &yx, const tfScalar &yy, const tfScalar &yz, const tfScalar &zx, const tfScalar &zy, const tfScalar &zz)
Constructor with row major formatting.
TFSIMD_FORCE_INLINE tfScalar tfTriple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
const TFSIMD_FORCE_INLINE Vector3 & operator[](int i) const
Get a const reference to a row of the matrix as a vector.
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Get the matrix represented as roll pitch and yaw about fixed axes XYZ.
ROS_DEPRECATED void setEulerZYX(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Set the matrix from euler angles using YPR around ZYX respectively.
#define TFSIMD_FORCE_INLINE
TFSIMD_FORCE_INLINE tfScalar tfFabs(tfScalar x)
tfScalar cofac(int r1, int c1, int r2, int c2) const
Calculate the matrix cofactor.
void getRotation(Quaternion &q) const
Get the matrix represented as a quaternion.
void setEulerYPR(tfScalar eulerZ, tfScalar eulerY, tfScalar eulerX)
Set the matrix from euler angles YPR around ZYX axes.
TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x)
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x)
void setFromOpenGLSubMatrix(const tfScalar *m)
Set from a carray of tfScalars.
const TFSIMD_FORCE_INLINE Vector3 & getRow(int i) const
Get a row of the matrix as a vector.
Matrix3x3 adjoint() const
Return the adjoint of the matrix.
TFSIMD_FORCE_INLINE tfScalar tfAsin(tfScalar x)
void serializeFloat(struct Matrix3x3FloatData &dataOut) const
Matrix3x3()
No initializaion constructor.
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
ROS_DEPRECATED void getEulerZYX(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
Get the matrix represented as euler angles around ZYX.
TFSIMD_FORCE_INLINE Vector3 getColumn(int i) const
Get a column of the matrix as a vector.
Matrix3x3 timesTranspose(const Matrix3x3 &m) const
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
Matrix3x3 transpose() const
Return the transpose of the matrix.
Matrix3x3 absolute() const
Return the matrix with all values non negative.
TFSIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
tfScalar determinant() const
Return the determinant of the matrix.
void setIdentity()
Set the matrix to the identity.
TFSIMD_FORCE_INLINE Vector3 & operator[](int i)
Get a mutable reference to a row of the matrix as a vector.
Matrix3x3 inverse() const
Return the inverse of the matrix.
Vector3DoubleData m_el[3]
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR.
Matrix3x3 & operator*=(const Matrix3x3 &m)
Multiply by the target matrix on the right.
TFSIMD_FORCE_INLINE Matrix3x3(const Matrix3x3 &other)
Copy constructor.
TFSIMD_FORCE_INLINE tfScalar tdotz(const Vector3 &v) const
void getOpenGLSubMatrix(tfScalar *m) const
Fill the values of the matrix into a 9 element array.
tfScalar length2() const
Return the length squared of the quaternion.
TFSIMD_FORCE_INLINE tfScalar tdotx(const Vector3 &v) const
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
void deSerialize(const struct Matrix3x3Data &dataIn)
void deSerializeDouble(const struct Matrix3x3DoubleData &dataIn)
static const Matrix3x3 & getIdentity()
Vector3 m_el[3]
Data storage for the matrix, each vector is a row of the matrix.
TFSIMD_FORCE_INLINE Matrix3x3 & operator=(const Matrix3x3 &other)
Assignment Operator.
void setValue(const tfScalar &xx, const tfScalar &xy, const tfScalar &xz, const tfScalar &yx, const tfScalar &yy, const tfScalar &yz, const tfScalar &zx, const tfScalar &zy, const tfScalar &zz)
Set the values of the matrix explicitly (row major)
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
void serialize(struct Matrix3x3Data &dataOut) const
void deSerializeFloat(const struct Matrix3x3FloatData &dataIn)
Matrix3x3 scaled(const Vector3 &s) const
Create a scaled copy of the matrix.
TFSIMD_FORCE_INLINE tfScalar tdoty(const Vector3 &v) const
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
void diagonalize(Matrix3x3 &rot, tfScalar threshold, int maxSteps)
diagonalizes this matrix by the Jacobi method.
void setRotation(const Quaternion &q)
Set the matrix from a quaternion.
TFSIMD_FORCE_INLINE tfScalar tfAtan2(tfScalar x, tfScalar y)
tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:07