16#ifndef TF2__LINEARMATH__MATRIX3x3_HPP
17#define TF2__LINEARMATH__MATRIX3x3_HPP
28#define Matrix3x3Data Matrix3x3DoubleData
68 m_el[0] =
other.m_el[0];
69 m_el[1] =
other.m_el[1];
70 m_el[2] =
other.m_el[2];
77 m_el[0] =
other.m_el[0];
78 m_el[1] =
other.m_el[1];
79 m_el[2] =
other.m_el[2];
88 return Vector3(m_el[0][
i],m_el[1][
i],m_el[2][
i]);
258 temp[0]=((m_el[2].
y() - m_el[1].
z()) *
s);
259 temp[1]=((m_el[0].
z() - m_el[2].
x()) *
s);
260 temp[2]=((m_el[1].
x() - m_el[0].
y()) *
s);
264 int i = m_el[0].
x() < m_el[1].
y() ?
265 (m_el[1].
y() < m_el[2].
z() ? 2 : 1) :
266 (m_el[0].
x() < m_el[2].
z() ? 2 : 0);
371 return Matrix3x3(m_el[0].x() *
s.
x(), m_el[0].
y() *
s.y(), m_el[0].
z() *
s.z(),
372 m_el[1].
x() *
s.x(), m_el[1].
y() *
s.y(), m_el[1].
z() *
s.z(),
373 m_el[2].
x() *
s.x(), m_el[2].
y() *
s.y(), m_el[2].
z() *
s.z());
399 return m_el[0].
x() *
v.x() + m_el[1].
x() *
v.y() + m_el[2].
x() *
v.z();
403 return m_el[0].
y() *
v.x() + m_el[1].
y() *
v.y() + m_el[2].
y() *
v.z();
407 return m_el[0].
z() *
v.x() + m_el[1].
z() *
v.y() + m_el[2].
z() *
v.z();
479 m_el[
p][
q] = m_el[
q][
p] = 0;
488 for (
int i = 0;
i < 3;
i++)
536 setValue(
m.tdotx(m_el[0]),
m.tdoty(m_el[0]),
m.tdotz(m_el[0]),
537 m.tdotx(m_el[1]),
m.tdoty(m_el[1]),
m.tdotz(m_el[1]),
538 m.tdotx(m_el[2]),
m.tdoty(m_el[2]),
m.tdotz(m_el[2]));
545 return tf2Triple((*
this)[0], (*
this)[1], (*
this)[2]);
561 return Matrix3x3(m_el[0].x(), m_el[1].x(), m_el[2].x(),
562 m_el[0].y(), m_el[1].y(), m_el[2].y(),
563 m_el[0].z(), m_el[1].z(), m_el[2].z());
569 return Matrix3x3(
cofac(1, 1, 2, 2),
cofac(0, 2, 2, 1),
cofac(0, 1, 1, 2),
570 cofac(1, 2, 2, 0),
cofac(0, 0, 2, 2),
cofac(0, 2, 1, 0),
571 cofac(1, 0, 2, 1),
cofac(0, 1, 2, 0),
cofac(0, 0, 1, 1));
577 Vector3 co(
cofac(1, 1, 2, 2),
cofac(1, 2, 2, 0),
cofac(1, 0, 2, 1));
590 m_el[0].x() *
m[0].x() + m_el[1].x() *
m[1].x() + m_el[2].x() *
m[2].x(),
591 m_el[0].x() *
m[0].y() + m_el[1].x() *
m[1].y() + m_el[2].x() *
m[2].y(),
592 m_el[0].x() *
m[0].z() + m_el[1].x() *
m[1].z() + m_el[2].x() *
m[2].z(),
593 m_el[0].y() *
m[0].x() + m_el[1].y() *
m[1].x() + m_el[2].y() *
m[2].x(),
594 m_el[0].y() *
m[0].y() + m_el[1].y() *
m[1].y() + m_el[2].y() *
m[2].y(),
595 m_el[0].y() *
m[0].z() + m_el[1].y() *
m[1].z() + m_el[2].y() *
m[2].z(),
596 m_el[0].z() *
m[0].x() + m_el[1].z() *
m[1].x() + m_el[2].z() *
m[2].x(),
597 m_el[0].z() *
m[0].y() + m_el[1].z() *
m[1].y() + m_el[2].z() *
m[2].y(),
598 m_el[0].z() *
m[0].z() + m_el[1].z() *
m[1].z() + m_el[2].z() *
m[2].z());
605 m_el[0].
dot(
m[0]), m_el[0].
dot(
m[1]), m_el[0].
dot(
m[2]),
606 m_el[1].
dot(
m[0]), m_el[1].
dot(
m[1]), m_el[1].
dot(
m[2]),
607 m_el[2].
dot(
m[0]), m_el[2].
dot(
m[1]), m_el[2].
dot(
m[2]));
652 return (
m1[0][0] ==
m2[0][0] &&
m1[1][0] ==
m2[1][0] &&
m1[2][0] ==
m2[2][0] &&
653 m1[0][1] ==
m2[0][1] &&
m1[1][1] ==
m2[1][1] &&
m1[2][1] ==
m2[2][1] &&
654 m1[0][2] ==
m2[0][2] &&
m1[1][2] ==
m2[1][2] &&
m1[2][2] ==
m2[2][2] );
674 for (
int i=0;
i<3;
i++)
680 for (
int i=0;
i<3;
i++)
687 for (
int i=0;
i<3;
i++)
693 for (
int i=0;
i<3;
i++)
699 for (
int i=0;
i<3;
i++)
#define Matrix3x3Data
Definition Matrix3x3.hpp:28
tf2Scalar tf2Sqrt(tf2Scalar x)
Definition Scalar.hpp:177
#define TF2SIMD_PI
Definition Scalar.hpp:193
#define TF2SIMD_EPSILON
Definition Scalar.hpp:202
tf2Scalar tf2Cos(tf2Scalar x)
Definition Scalar.hpp:179
#define tf2FullAssert(x)
Definition Scalar.hpp:148
tf2Scalar tf2Atan2(tf2Scalar x, tf2Scalar y)
Definition Scalar.hpp:185
#define TF2SIMD_FORCE_INLINE
Definition Scalar.hpp:129
tf2Scalar tf2Fabs(tf2Scalar x)
Definition Scalar.hpp:178
tf2Scalar tf2Asin(tf2Scalar x)
Definition Scalar.hpp:183
tf2Scalar tf2Sin(tf2Scalar x)
Definition Scalar.hpp:180
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Definition Scalar.hpp:159
The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Q...
Definition Matrix3x3.hpp:33
tf2Scalar tdoty(const Vector3 &v) const
Definition Matrix3x3.hpp:401
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)
Constructor with row major formatting.
Definition Matrix3x3.hpp:57
tf2Scalar tdotx(const Vector3 &v) const
Definition Matrix3x3.hpp:397
Matrix3x3(const Quaternion &q)
Constructor from Quaternion.
Definition Matrix3x3.hpp:47
const Vector3 & operator[](int i) const
Get a const reference to a row of the matrix as a vector.
Definition Matrix3x3.hpp:110
void setRPY(tf2Scalar roll, tf2Scalar pitch, tf2Scalar yaw)
Set the matrix using RPY about XYZ fixed axes.
Definition Matrix3x3.hpp:203
void serialize(struct Matrix3x3Data &dataOut) const
Definition Matrix3x3.hpp:672
Matrix3x3 & operator=(const Matrix3x3 &other)
Assignment Operator.
Definition Matrix3x3.hpp:75
Matrix3x3 timesTranspose(const Matrix3x3 &m) const
Definition Matrix3x3.hpp:602
void deSerializeFloat(const struct Matrix3x3FloatData &dataIn)
Definition Matrix3x3.hpp:691
Vector3 getColumn(int i) const
Get a column of the matrix as a vector.
Definition Matrix3x3.hpp:86
tf2Scalar cofac(int r1, int c1, int r2, int c2) const
Calculate the matrix cofactor.
Definition Matrix3x3.hpp:510
void setRotation(const Quaternion &q)
Set the matrix from a quaternion.
Definition Matrix3x3.hpp:155
Matrix3x3(const Matrix3x3 &other)
Copy constructor.
Definition Matrix3x3.hpp:66
void diagonalize(Matrix3x3 &rot, tf2Scalar threshold, int maxSteps)
diagonalizes this matrix by the Jacobi method.
Definition Matrix3x3.hpp:421
void getRPY(tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
Get the matrix represented as roll pitch and yaw about fixed axes XYZ.
Definition Matrix3x3.hpp:360
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)
Set the values of the matrix explicitly (row major)
Definition Matrix3x3.hpp:143
Matrix3x3 absolute() const
Return the matrix with all values non negative.
Definition Matrix3x3.hpp:550
static const Matrix3x3 & getIdentity()
Definition Matrix3x3.hpp:217
void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY, tf2Scalar eulerX)
Set the matrix from euler angles YPR around ZYX axes.
Definition Matrix3x3.hpp:179
void getOpenGLSubMatrix(tf2Scalar *m) const
Fill the values of the matrix into a 9 element array.
Definition Matrix3x3.hpp:228
tf2Scalar tdotz(const Vector3 &v) const
Definition Matrix3x3.hpp:405
void deSerializeDouble(const struct Matrix3x3DoubleData &dataIn)
Definition Matrix3x3.hpp:697
const Vector3 & getRow(int i) const
Get a row of the matrix as a vector.
Definition Matrix3x3.hpp:94
void setIdentity()
Set the matrix to the identity.
Definition Matrix3x3.hpp:209
Matrix3x3 & operator*=(const Matrix3x3 &m)
Multiply by the target matrix on the right.
Definition Matrix3x3.hpp:534
void getRotation(Quaternion &q) const
Get the matrix represented as a quaternion.
Definition Matrix3x3.hpp:247
void serializeFloat(struct Matrix3x3FloatData &dataOut) const
Definition Matrix3x3.hpp:678
Matrix3x3()
No initialization constructor.
Definition Matrix3x3.hpp:41
void deSerialize(const struct Matrix3x3Data &dataIn)
Definition Matrix3x3.hpp:685
tf2Scalar determinant() const
Return the determinant of the matrix.
Definition Matrix3x3.hpp:543
Matrix3x3 scaled(const Vector3 &s) const
Create a scaled copy of the matrix.
Definition Matrix3x3.hpp:369
Matrix3x3 transposeTimes(const Matrix3x3 &m) const
Definition Matrix3x3.hpp:587
Vector3 & operator[](int i)
Get a mutable reference to a row of the matrix as a vector.
Definition Matrix3x3.hpp:102
void setFromOpenGLSubMatrix(const tf2Scalar *m)
Set from a carray of tf2Scalars.
Definition Matrix3x3.hpp:125
Matrix3x3 adjoint() const
Return the adjoint of the matrix.
Definition Matrix3x3.hpp:567
Matrix3x3 transpose() const
Return the transpose of the matrix.
Definition Matrix3x3.hpp:559
Matrix3x3 inverse() const
Return the inverse of the matrix.
Definition Matrix3x3.hpp:575
void getEulerYPR(tf2Scalar &yaw, tf2Scalar &pitch, tf2Scalar &roll, unsigned int solution_number=1) const
Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR.
Definition Matrix3x3.hpp:287
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition Quaternion.hpp:30
tf2::Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16...
Definition Vector3.hpp:40
const tf2Scalar & z() const
Return the z value.
Definition Vector3.hpp:269
const tf2Scalar & x() const
Return the x value.
Definition Vector3.hpp:265
void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z)
Definition Vector3.hpp:310
const tf2Scalar & y() const
Return the y value.
Definition Vector3.hpp:267
Definition buffer_core.hpp:58
Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
Definition Matrix3x3.hpp:612
tf2Scalar tf2Triple(const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
Definition Vector3.hpp:454
B toMsg(const A &a)
Function that converts from one type to a ROS message type. It has to be implemented by each data typ...
tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition Quaternion.hpp:456
bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
Definition Matrix3x3.hpp:650
for serialization
Definition Matrix3x3.hpp:665
Vector3DoubleData m_el[3]
Definition Matrix3x3.hpp:666
for serialization
Definition Matrix3x3.hpp:659
Vector3FloatData m_el[3]
Definition Matrix3x3.hpp:660
Definition Vector3.hpp:676
Definition Vector3.hpp:671
#define TF2_PUBLIC
Definition visibility_control.h:57