tf2 rolling
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Loading...
Searching...
No Matches
Matrix3x3.hpp
Go to the documentation of this file.
1/*
2Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
3
4This software is provided 'as-is', without any express or implied warranty.
5In no event will the authors be held liable for any damages arising from the use of this software.
6Permission is granted to anyone to use this software for any purpose,
7including commercial applications, and to alter it and redistribute it freely,
8subject to the following restrictions:
9
101. 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.
112. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
123. This notice may not be removed or altered from any source distribution.
13*/
14
15
16#ifndef TF2__LINEARMATH__MATRIX3x3_HPP
17#define TF2__LINEARMATH__MATRIX3x3_HPP
18
19#include "Vector3.hpp"
20#include "Quaternion.hpp"
21
23
24namespace tf2
25{
26
27
28#define Matrix3x3Data Matrix3x3DoubleData
29
30
33class Matrix3x3 {
34
36 Vector3 m_el[3];
37
38public:
42
43 // explicit Matrix3x3(const tf2Scalar *m) { setFromOpenGLSubMatrix(m); }
44
47 explicit Matrix3x3(const Quaternion& q) { setRotation(q); }
48 /*
49 template <typename tf2Scalar>
50 Matrix3x3(const tf2Scalar& yaw, const tf2Scalar& pitch, const tf2Scalar& roll)
51 {
52 setEulerYPR(yaw, pitch, roll);
53 }
54 */
57 Matrix3x3(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz,
58 const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz,
59 const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz)
60 {
61 setValue(xx, xy, xz,
62 yx, yy, yz,
63 zx, zy, zz);
64 }
67 {
68 m_el[0] = other.m_el[0];
69 m_el[1] = other.m_el[1];
70 m_el[2] = other.m_el[2];
71 }
72
73
76 {
77 m_el[0] = other.m_el[0];
78 m_el[1] = other.m_el[1];
79 m_el[2] = other.m_el[2];
80 return *this;
81 }
82
83
87 {
88 return Vector3(m_el[0][i],m_el[1][i],m_el[2][i]);
89 }
90
91
95 {
96 tf2FullAssert(0 <= i && i < 3);
97 return m_el[i];
98 }
99
103 {
104 tf2FullAssert(0 <= i && i < 3);
105 return m_el[i];
106 }
107
111 {
112 tf2FullAssert(0 <= i && i < 3);
113 return m_el[i];
114 }
115
121
126 {
127 m_el[0].setValue(m[0],m[4],m[8]);
128 m_el[1].setValue(m[1],m[5],m[9]);
129 m_el[2].setValue(m[2],m[6],m[10]);
130
131 }
143 void setValue(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz,
144 const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz,
145 const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz)
146 {
147 m_el[0].setValue(xx,xy,xz);
148 m_el[1].setValue(yx,yy,yz);
149 m_el[2].setValue(zx,zy,zz);
150 }
151
156 {
157 tf2Scalar d = q.length2();
158 tf2FullAssert(d != tf2Scalar(0.0));
159 tf2Scalar s = tf2Scalar(2.0) / d;
160 tf2Scalar xs = q.x() * s, ys = q.y() * s, zs = q.z() * s;
161 tf2Scalar wx = q.w() * xs, wy = q.w() * ys, wz = q.w() * zs;
162 tf2Scalar xx = q.x() * xs, xy = q.x() * ys, xz = q.x() * zs;
163 tf2Scalar yy = q.y() * ys, yz = q.y() * zs, zz = q.z() * zs;
164 setValue(tf2Scalar(1.0) - (yy + zz), xy - wz, xz + wy,
165 xy + wz, tf2Scalar(1.0) - (xx + zz), yz - wx,
166 xz - wy, yz + wx, tf2Scalar(1.0) - (xx + yy));
167 }
168
186 tf2Scalar cc = ci * ch;
187 tf2Scalar cs = ci * sh;
188 tf2Scalar sc = si * ch;
189 tf2Scalar ss = si * sh;
190
191 setValue(cj * ch, sj * sc - cs, sj * cc + ss,
192 cj * sh, sj * ss + cc, sj * cs - sc,
193 -sj, cj * si, cj * ci);
194 }
195
206
210 {
211 setValue(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0),
212 tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0),
213 tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0));
214 }
215
217 static const Matrix3x3& getIdentity()
218 {
219 static const Matrix3x3 identityMatrix(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0),
220 tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0),
221 tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0));
222 return identityMatrix;
223 }
224
229 {
230 m[0] = tf2Scalar(m_el[0].x());
231 m[1] = tf2Scalar(m_el[1].x());
232 m[2] = tf2Scalar(m_el[2].x());
233 m[3] = tf2Scalar(0.0);
234 m[4] = tf2Scalar(m_el[0].y());
235 m[5] = tf2Scalar(m_el[1].y());
236 m[6] = tf2Scalar(m_el[2].y());
237 m[7] = tf2Scalar(0.0);
238 m[8] = tf2Scalar(m_el[0].z());
239 m[9] = tf2Scalar(m_el[1].z());
240 m[10] = tf2Scalar(m_el[2].z());
241 m[11] = tf2Scalar(0.0);
242 }
243
248 {
249 tf2Scalar trace = m_el[0].x() + m_el[1].y() + m_el[2].z();
250 tf2Scalar temp[4];
251
252 if (trace > tf2Scalar(0.0))
253 {
255 temp[3]=(s * tf2Scalar(0.5));
256 s = tf2Scalar(0.5) / s;
257
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);
261 }
262 else
263 {
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);
267 int j = (i + 1) % 3;
268 int k = (i + 2) % 3;
269
270 tf2Scalar s = tf2Sqrt(m_el[i][i] - m_el[j][j] - m_el[k][k] + tf2Scalar(1.0));
271 temp[i] = s * tf2Scalar(0.5);
272 s = tf2Scalar(0.5) / s;
273
274 temp[3] = (m_el[k][j] - m_el[j][k]) * s;
275 temp[j] = (m_el[j][i] + m_el[i][j]) * s;
276 temp[k] = (m_el[k][i] + m_el[i][k]) * s;
277 }
278 q.setValue(temp[0],temp[1],temp[2],temp[3]);
279 }
280
288 {
289 struct Euler
290 {
291 tf2Scalar yaw;
292 tf2Scalar pitch;
293 tf2Scalar roll;
294 };
295
297 Euler euler_out2; //second solution
298 //get the pointer to the raw data
299
300 // Check that pitch is not at a singularity
301 // Check that pitch is not at a singularity
302 if (tf2Fabs(m_el[2].x()) >= 1)
303 {
304 euler_out.yaw = 0;
305 euler_out2.yaw = 0;
306
307 // From difference of angles formula
308 tf2Scalar delta = tf2Atan2(m_el[2].y(),m_el[2].z());
309 if (m_el[2].x() < 0) //gimbal locked down
310 {
311 euler_out.pitch = TF2SIMD_PI / tf2Scalar(2.0);
312 euler_out2.pitch = TF2SIMD_PI / tf2Scalar(2.0);
313 euler_out.roll = delta;
314 euler_out2.roll = delta;
315 }
316 else // gimbal locked up
317 {
318 euler_out.pitch = -TF2SIMD_PI / tf2Scalar(2.0);
319 euler_out2.pitch = -TF2SIMD_PI / tf2Scalar(2.0);
320 euler_out.roll = delta;
321 euler_out2.roll = delta;
322 }
323 }
324 else
325 {
326 euler_out.pitch = - tf2Asin(m_el[2].x());
327 euler_out2.pitch = TF2SIMD_PI - euler_out.pitch;
328
329 euler_out.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out.pitch),
330 m_el[2].z()/tf2Cos(euler_out.pitch));
331 euler_out2.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out2.pitch),
332 m_el[2].z()/tf2Cos(euler_out2.pitch));
333
334 euler_out.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out.pitch),
335 m_el[0].x()/tf2Cos(euler_out.pitch));
336 euler_out2.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out2.pitch),
337 m_el[0].x()/tf2Cos(euler_out2.pitch));
338 }
339
340 if (solution_number == 1)
341 {
342 yaw = euler_out.yaw;
343 pitch = euler_out.pitch;
344 roll = euler_out.roll;
345 }
346 else
347 {
348 yaw = euler_out2.yaw;
349 pitch = euler_out2.pitch;
350 roll = euler_out2.roll;
351 }
352 }
353
360 void getRPY(tf2Scalar& roll, tf2Scalar& pitch, tf2Scalar& yaw, unsigned int solution_number = 1) const
361 {
363 }
364
369 Matrix3x3 scaled(const Vector3& s) const
370 {
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());
374 }
375
378 tf2Scalar determinant() const;
381 Matrix3x3 adjoint() const;
384 Matrix3x3 absolute() const;
387 Matrix3x3 transpose() const;
390 Matrix3x3 inverse() const;
391
393 Matrix3x3 transposeTimes(const Matrix3x3& m) const;
395 Matrix3x3 timesTranspose(const Matrix3x3& m) const;
396
398 {
399 return m_el[0].x() * v.x() + m_el[1].x() * v.y() + m_el[2].x() * v.z();
400 }
402 {
403 return m_el[0].y() * v.x() + m_el[1].y() * v.y() + m_el[2].y() * v.z();
404 }
406 {
407 return m_el[0].z() * v.x() + m_el[1].z() * v.y() + m_el[2].z() * v.z();
408 }
409
410
422 {
423 rot.setIdentity();
424 for (int step = maxSteps; step > 0; step--)
425 {
426 // find off-diagonal element [p][q] with largest magnitude
427 int p = 0;
428 int q = 1;
429 int r = 2;
430 tf2Scalar max = tf2Fabs(m_el[0][1]);
431 tf2Scalar v = tf2Fabs(m_el[0][2]);
432 if (v > max)
433 {
434 q = 2;
435 r = 1;
436 max = v;
437 }
438 v = tf2Fabs(m_el[1][2]);
439 if (v > max)
440 {
441 p = 1;
442 q = 2;
443 r = 0;
444 max = v;
445 }
446
447 tf2Scalar t = threshold * (tf2Fabs(m_el[0][0]) + tf2Fabs(m_el[1][1]) + tf2Fabs(m_el[2][2]));
448 if (max <= t)
449 {
450 if (max <= TF2SIMD_EPSILON * t)
451 {
452 return;
453 }
454 step = 1;
455 }
456
457 // compute Jacobi rotation J which leads to a zero for element [p][q]
458 tf2Scalar mpq = m_el[p][q];
459 tf2Scalar theta = (m_el[q][q] - m_el[p][p]) / (2 * mpq);
464 {
465 t = (theta >= 0) ? 1 / (theta + tf2Sqrt(1 + theta2))
466 : 1 / (theta - tf2Sqrt(1 + theta2));
467 cos = 1 / tf2Sqrt(1 + t * t);
468 sin = cos * t;
469 }
470 else
471 {
472 // approximation for large theta-value, i.e., a nearly diagonal matrix
473 t = 1 / (theta * (2 + tf2Scalar(0.5) / theta2));
474 cos = 1 - tf2Scalar(0.5) * t * t;
475 sin = cos * t;
476 }
477
478 // apply rotation to matrix (this = J^T * this * J)
479 m_el[p][q] = m_el[q][p] = 0;
480 m_el[p][p] -= t * mpq;
481 m_el[q][q] += t * mpq;
482 tf2Scalar mrp = m_el[r][p];
483 tf2Scalar mrq = m_el[r][q];
484 m_el[r][p] = m_el[p][r] = cos * mrp - sin * mrq;
485 m_el[r][q] = m_el[q][r] = cos * mrq + sin * mrp;
486
487 // apply rotation to rot (rot = rot * J)
488 for (int i = 0; i < 3; i++)
489 {
490 Vector3& row = rot[i];
491 mrp = row[p];
492 mrq = row[q];
493 row[p] = cos * mrp - sin * mrq;
494 row[q] = cos * mrq + sin * mrp;
495 }
496 }
497 }
498
499
500
501
510 tf2Scalar cofac(int r1, int c1, int r2, int c2) const
511 {
512 return m_el[r1][c1] * m_el[r2][c2] - m_el[r1][c2] * m_el[r2][c1];
513 }
514
516 void serialize(struct Matrix3x3Data& dataOut) const;
517
519 void serializeFloat(struct Matrix3x3FloatData& dataOut) const;
520
522 void deSerialize(const struct Matrix3x3Data& dataIn);
523
525 void deSerializeFloat(const struct Matrix3x3FloatData& dataIn);
526
528 void deSerializeDouble(const struct Matrix3x3DoubleData& dataIn);
529
530};
531
532
533TF2SIMD_FORCE_INLINE Matrix3x3&
535{
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]));
539 return *this;
540}
541
544{
545 return tf2Triple((*this)[0], (*this)[1], (*this)[2]);
546}
547
548
551{
552 return Matrix3x3(
553 tf2Fabs(m_el[0].x()), tf2Fabs(m_el[0].y()), tf2Fabs(m_el[0].z()),
554 tf2Fabs(m_el[1].x()), tf2Fabs(m_el[1].y()), tf2Fabs(m_el[1].z()),
555 tf2Fabs(m_el[2].x()), tf2Fabs(m_el[2].y()), tf2Fabs(m_el[2].z()));
556}
557
560{
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());
564}
565
568{
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));
572}
573
576{
577 Vector3 co(cofac(1, 1, 2, 2), cofac(1, 2, 2, 0), cofac(1, 0, 2, 1));
578 tf2Scalar det = (*this)[0].dot(co);
579 tf2FullAssert(det != tf2Scalar(0.0));
580 tf2Scalar s = tf2Scalar(1.0) / det;
581 return Matrix3x3(co.x() * s, cofac(0, 2, 2, 1) * s, cofac(0, 1, 1, 2) * s,
582 co.y() * s, cofac(0, 0, 2, 2) * s, cofac(0, 2, 1, 0) * s,
583 co.z() * s, cofac(0, 1, 2, 0) * s, cofac(0, 0, 1, 1) * s);
584}
585
588{
589 return Matrix3x3(
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());
599}
600
603{
604 return Matrix3x3(
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]));
608
609}
610
612operator*(const Matrix3x3& m, const Vector3& v)
613{
614 return Vector3(m[0].dot(v), m[1].dot(v), m[2].dot(v));
615}
616
617
620{
621 return Vector3(m.tdotx(v), m.tdoty(v), m.tdotz(v));
622}
623
624TF2SIMD_FORCE_INLINE Matrix3x3
626{
627 return Matrix3x3(
628 m2.tdotx( m1[0]), m2.tdoty( m1[0]), m2.tdotz( m1[0]),
629 m2.tdotx( m1[1]), m2.tdoty( m1[1]), m2.tdotz( m1[1]),
630 m2.tdotx( m1[2]), m2.tdoty( m1[2]), m2.tdotz( m1[2]));
631}
632
633/*
634TF2SIMD_FORCE_INLINE Matrix3x3 tf2MultTransposeLeft(const Matrix3x3& m1, const Matrix3x3& m2) {
635return Matrix3x3(
636m1[0][0] * m2[0][0] + m1[1][0] * m2[1][0] + m1[2][0] * m2[2][0],
637m1[0][0] * m2[0][1] + m1[1][0] * m2[1][1] + m1[2][0] * m2[2][1],
638m1[0][0] * m2[0][2] + m1[1][0] * m2[1][2] + m1[2][0] * m2[2][2],
639m1[0][1] * m2[0][0] + m1[1][1] * m2[1][0] + m1[2][1] * m2[2][0],
640m1[0][1] * m2[0][1] + m1[1][1] * m2[1][1] + m1[2][1] * m2[2][1],
641m1[0][1] * m2[0][2] + m1[1][1] * m2[1][2] + m1[2][1] * m2[2][2],
642m1[0][2] * m2[0][0] + m1[1][2] * m2[1][0] + m1[2][2] * m2[2][0],
643m1[0][2] * m2[0][1] + m1[1][2] * m2[1][1] + m1[2][2] * m2[2][1],
644m1[0][2] * m2[0][2] + m1[1][2] * m2[1][2] + m1[2][2] * m2[2][2]);
645}
646*/
647
651{
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] );
655}
656
662
668
669
670
671
673{
674 for (int i=0;i<3;i++)
675 m_el[i].serialize(dataOut.m_el[i]);
676}
677
679{
680 for (int i=0;i<3;i++)
681 m_el[i].serializeFloat(dataOut.m_el[i]);
682}
683
684
686{
687 for (int i=0;i<3;i++)
688 m_el[i].deSerialize(dataIn.m_el[i]);
689}
690
692{
693 for (int i=0;i<3;i++)
694 m_el[i].deSerializeFloat(dataIn.m_el[i]);
695}
696
698{
699 for (int i=0;i<3;i++)
700 m_el[i].deSerializeDouble(dataIn.m_el[i]);
701}
702
703}
704#endif // TF2__LINEARMATH__MATRIX3x3_HPP
#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