00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016 #ifndef TF_MATRIX3x3_H
00017 #define TF_MATRIX3x3_H
00018
00019 #include "Vector3.h"
00020 #include "Quaternion.h"
00021
00022 #include "LinearMath/btMatrix3x3.h"
00023
00024 namespace tf
00025 {
00026
00027
00028 #define Matrix3x3Data Matrix3x3DoubleData
00029
00030
00033 class Matrix3x3 {
00034
00036 Vector3 m_el[3];
00037
00038 public:
00040 Matrix3x3 () {}
00041
00042
00043
00045 explicit Matrix3x3(const Quaternion& q) { setRotation(q); }
00046
00047
00048
00049
00050
00051
00052
00054 Matrix3x3(const tfScalar& xx, const tfScalar& xy, const tfScalar& xz,
00055 const tfScalar& yx, const tfScalar& yy, const tfScalar& yz,
00056 const tfScalar& zx, const tfScalar& zy, const tfScalar& zz)
00057 {
00058 setValue(xx, xy, xz,
00059 yx, yy, yz,
00060 zx, zy, zz);
00061 }
00063 TFSIMD_FORCE_INLINE Matrix3x3 (const Matrix3x3& other)
00064 {
00065 m_el[0] = other.m_el[0];
00066 m_el[1] = other.m_el[1];
00067 m_el[2] = other.m_el[2];
00068 }
00069
00070 TFSIMD_FORCE_INLINE Matrix3x3 (const btMatrix3x3& other)
00071 {
00072 m_el[0] = other.getRow(0);
00073 m_el[1] = other.getRow(1);
00074 m_el[2] = other.getRow(2);
00075 }
00076
00078 TFSIMD_FORCE_INLINE Matrix3x3& operator=(const Matrix3x3& other)
00079 {
00080 m_el[0] = other.m_el[0];
00081 m_el[1] = other.m_el[1];
00082 m_el[2] = other.m_el[2];
00083 return *this;
00084 }
00085
00087 TFSIMD_FORCE_INLINE Matrix3x3& operator=(const btMatrix3x3& other)
00088 {
00089 m_el[0] = other.getRow(0);
00090 m_el[1] = other.getRow(1);
00091 m_el[2] = other.getRow(2);
00092 return *this;
00093 }
00094
00097 TFSIMD_FORCE_INLINE btMatrix3x3 as_bt(void) const __attribute__((deprecated)) { return asBt(); };
00098 TFSIMD_FORCE_INLINE btMatrix3x3 asBt(void) const
00099 {
00100 return btMatrix3x3(
00101 m_el[0][0], m_el[0][1], m_el[0][2],
00102 m_el[1][0], m_el[1][1], m_el[1][2],
00103 m_el[2][0], m_el[2][1], m_el[2][2]);
00104 }
00105
00108 TFSIMD_FORCE_INLINE Vector3 getColumn(int i) const
00109 {
00110 return Vector3(m_el[0][i],m_el[1][i],m_el[2][i]);
00111 }
00112
00113
00116 TFSIMD_FORCE_INLINE const Vector3& getRow(int i) const
00117 {
00118 tfFullAssert(0 <= i && i < 3);
00119 return m_el[i];
00120 }
00121
00124 TFSIMD_FORCE_INLINE Vector3& operator[](int i)
00125 {
00126 tfFullAssert(0 <= i && i < 3);
00127 return m_el[i];
00128 }
00129
00132 TFSIMD_FORCE_INLINE const Vector3& operator[](int i) const
00133 {
00134 tfFullAssert(0 <= i && i < 3);
00135 return m_el[i];
00136 }
00137
00141 Matrix3x3& operator*=(const Matrix3x3& m);
00142
00145 void setFromOpenGLSubMatrix(const tfScalar *m)
00146 {
00147 m_el[0].setValue(m[0],m[4],m[8]);
00148 m_el[1].setValue(m[1],m[5],m[9]);
00149 m_el[2].setValue(m[2],m[6],m[10]);
00150
00151 }
00162 void setValue(const tfScalar& xx, const tfScalar& xy, const tfScalar& xz,
00163 const tfScalar& yx, const tfScalar& yy, const tfScalar& yz,
00164 const tfScalar& zx, const tfScalar& zy, const tfScalar& zz)
00165 {
00166 m_el[0].setValue(xx,xy,xz);
00167 m_el[1].setValue(yx,yy,yz);
00168 m_el[2].setValue(zx,zy,zz);
00169 }
00170
00173 void setRotation(const Quaternion& q)
00174 {
00175 tfScalar d = q.length2();
00176 tfFullAssert(d != tfScalar(0.0));
00177 tfScalar s = tfScalar(2.0) / d;
00178 tfScalar xs = q.x() * s, ys = q.y() * s, zs = q.z() * s;
00179 tfScalar wx = q.w() * xs, wy = q.w() * ys, wz = q.w() * zs;
00180 tfScalar xx = q.x() * xs, xy = q.x() * ys, xz = q.x() * zs;
00181 tfScalar yy = q.y() * ys, yz = q.y() * zs, zz = q.z() * zs;
00182 setValue(tfScalar(1.0) - (yy + zz), xy - wz, xz + wy,
00183 xy + wz, tfScalar(1.0) - (xx + zz), yz - wx,
00184 xz - wy, yz + wx, tfScalar(1.0) - (xx + yy));
00185 }
00186
00187
00193 void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated))
00194 {
00195 setEulerYPR(yaw, pitch, roll);
00196 }
00197
00207 void setEulerYPR(tfScalar eulerZ, tfScalar eulerY,tfScalar eulerX) {
00208 tfScalar ci ( tfCos(eulerX));
00209 tfScalar cj ( tfCos(eulerY));
00210 tfScalar ch ( tfCos(eulerZ));
00211 tfScalar si ( tfSin(eulerX));
00212 tfScalar sj ( tfSin(eulerY));
00213 tfScalar sh ( tfSin(eulerZ));
00214 tfScalar cc = ci * ch;
00215 tfScalar cs = ci * sh;
00216 tfScalar sc = si * ch;
00217 tfScalar ss = si * sh;
00218
00219 setValue(cj * ch, sj * sc - cs, sj * cc + ss,
00220 cj * sh, sj * ss + cc, sj * cs - sc,
00221 -sj, cj * si, cj * ci);
00222 }
00223
00230 void setRPY(tfScalar roll, tfScalar pitch,tfScalar yaw) {
00231 setEulerYPR(yaw, pitch, roll);
00232 }
00233
00235 void setIdentity()
00236 {
00237 setValue(tfScalar(1.0), tfScalar(0.0), tfScalar(0.0),
00238 tfScalar(0.0), tfScalar(1.0), tfScalar(0.0),
00239 tfScalar(0.0), tfScalar(0.0), tfScalar(1.0));
00240 }
00241
00242 static const Matrix3x3& getIdentity()
00243 {
00244 static const Matrix3x3 identityMatrix(tfScalar(1.0), tfScalar(0.0), tfScalar(0.0),
00245 tfScalar(0.0), tfScalar(1.0), tfScalar(0.0),
00246 tfScalar(0.0), tfScalar(0.0), tfScalar(1.0));
00247 return identityMatrix;
00248 }
00249
00252 void getOpenGLSubMatrix(tfScalar *m) const
00253 {
00254 m[0] = tfScalar(m_el[0].x());
00255 m[1] = tfScalar(m_el[1].x());
00256 m[2] = tfScalar(m_el[2].x());
00257 m[3] = tfScalar(0.0);
00258 m[4] = tfScalar(m_el[0].y());
00259 m[5] = tfScalar(m_el[1].y());
00260 m[6] = tfScalar(m_el[2].y());
00261 m[7] = tfScalar(0.0);
00262 m[8] = tfScalar(m_el[0].z());
00263 m[9] = tfScalar(m_el[1].z());
00264 m[10] = tfScalar(m_el[2].z());
00265 m[11] = tfScalar(0.0);
00266 }
00267
00270 void getRotation(Quaternion& q) const
00271 {
00272 tfScalar trace = m_el[0].x() + m_el[1].y() + m_el[2].z();
00273 tfScalar temp[4];
00274
00275 if (trace > tfScalar(0.0))
00276 {
00277 tfScalar s = tfSqrt(trace + tfScalar(1.0));
00278 temp[3]=(s * tfScalar(0.5));
00279 s = tfScalar(0.5) / s;
00280
00281 temp[0]=((m_el[2].y() - m_el[1].z()) * s);
00282 temp[1]=((m_el[0].z() - m_el[2].x()) * s);
00283 temp[2]=((m_el[1].x() - m_el[0].y()) * s);
00284 }
00285 else
00286 {
00287 int i = m_el[0].x() < m_el[1].y() ?
00288 (m_el[1].y() < m_el[2].z() ? 2 : 1) :
00289 (m_el[0].x() < m_el[2].z() ? 2 : 0);
00290 int j = (i + 1) % 3;
00291 int k = (i + 2) % 3;
00292
00293 tfScalar s = tfSqrt(m_el[i][i] - m_el[j][j] - m_el[k][k] + tfScalar(1.0));
00294 temp[i] = s * tfScalar(0.5);
00295 s = tfScalar(0.5) / s;
00296
00297 temp[3] = (m_el[k][j] - m_el[j][k]) * s;
00298 temp[j] = (m_el[j][i] + m_el[i][j]) * s;
00299 temp[k] = (m_el[k][i] + m_el[i][k]) * s;
00300 }
00301 q.setValue(temp[0],temp[1],temp[2],temp[3]);
00302 }
00303
00309 __attribute__((deprecated)) void getEulerZYX(tfScalar& yaw, tfScalar& pitch, tfScalar& roll, unsigned int solution_number = 1) const
00310 {
00311 getEulerYPR(yaw, pitch, roll, solution_number);
00312 };
00313
00314
00319 void getEulerYPR(tfScalar& yaw, tfScalar& pitch, tfScalar& roll, unsigned int solution_number = 1) const
00320 {
00321 struct Euler
00322 {
00323 tfScalar yaw;
00324 tfScalar pitch;
00325 tfScalar roll;
00326 };
00327
00328 Euler euler_out;
00329 Euler euler_out2;
00330
00331
00332
00333
00334 if (tfFabs(m_el[2].x()) >= 1)
00335 {
00336 euler_out.yaw = 0;
00337 euler_out2.yaw = 0;
00338
00339
00340 tfScalar delta = tfAtan2(m_el[2].y(),m_el[2].z());
00341 if (m_el[2].x() < 0)
00342 {
00343 euler_out.pitch = TFSIMD_PI / tfScalar(2.0);
00344 euler_out2.pitch = TFSIMD_PI / tfScalar(2.0);
00345 euler_out.roll = delta;
00346 euler_out2.roll = delta;
00347 }
00348 else
00349 {
00350 euler_out.pitch = -TFSIMD_PI / tfScalar(2.0);
00351 euler_out2.pitch = -TFSIMD_PI / tfScalar(2.0);
00352 euler_out.roll = delta;
00353 euler_out2.roll = delta;
00354 }
00355 }
00356 else
00357 {
00358 euler_out.pitch = - tfAsin(m_el[2].x());
00359 euler_out2.pitch = TFSIMD_PI - euler_out.pitch;
00360
00361 euler_out.roll = tfAtan2(m_el[2].y()/tfCos(euler_out.pitch),
00362 m_el[2].z()/tfCos(euler_out.pitch));
00363 euler_out2.roll = tfAtan2(m_el[2].y()/tfCos(euler_out2.pitch),
00364 m_el[2].z()/tfCos(euler_out2.pitch));
00365
00366 euler_out.yaw = tfAtan2(m_el[1].x()/tfCos(euler_out.pitch),
00367 m_el[0].x()/tfCos(euler_out.pitch));
00368 euler_out2.yaw = tfAtan2(m_el[1].x()/tfCos(euler_out2.pitch),
00369 m_el[0].x()/tfCos(euler_out2.pitch));
00370 }
00371
00372 if (solution_number == 1)
00373 {
00374 yaw = euler_out.yaw;
00375 pitch = euler_out.pitch;
00376 roll = euler_out.roll;
00377 }
00378 else
00379 {
00380 yaw = euler_out2.yaw;
00381 pitch = euler_out2.pitch;
00382 roll = euler_out2.roll;
00383 }
00384 }
00385
00391 void getRPY(tfScalar& roll, tfScalar& pitch, tfScalar& yaw, unsigned int solution_number = 1) const
00392 {
00393 getEulerYPR(yaw, pitch, roll, solution_number);
00394 }
00395
00399 Matrix3x3 scaled(const Vector3& s) const
00400 {
00401 return Matrix3x3(m_el[0].x() * s.x(), m_el[0].y() * s.y(), m_el[0].z() * s.z(),
00402 m_el[1].x() * s.x(), m_el[1].y() * s.y(), m_el[1].z() * s.z(),
00403 m_el[2].x() * s.x(), m_el[2].y() * s.y(), m_el[2].z() * s.z());
00404 }
00405
00407 tfScalar determinant() const;
00409 Matrix3x3 adjoint() const;
00411 Matrix3x3 absolute() const;
00413 Matrix3x3 transpose() const;
00415 Matrix3x3 inverse() const;
00416
00417 Matrix3x3 transposeTimes(const Matrix3x3& m) const;
00418 Matrix3x3 timesTranspose(const Matrix3x3& m) const;
00419
00420 TFSIMD_FORCE_INLINE tfScalar tdotx(const Vector3& v) const
00421 {
00422 return m_el[0].x() * v.x() + m_el[1].x() * v.y() + m_el[2].x() * v.z();
00423 }
00424 TFSIMD_FORCE_INLINE tfScalar tdoty(const Vector3& v) const
00425 {
00426 return m_el[0].y() * v.x() + m_el[1].y() * v.y() + m_el[2].y() * v.z();
00427 }
00428 TFSIMD_FORCE_INLINE tfScalar tdotz(const Vector3& v) const
00429 {
00430 return m_el[0].z() * v.x() + m_el[1].z() * v.y() + m_el[2].z() * v.z();
00431 }
00432
00433
00443 void diagonalize(Matrix3x3& rot, tfScalar threshold, int maxSteps)
00444 {
00445 rot.setIdentity();
00446 for (int step = maxSteps; step > 0; step--)
00447 {
00448
00449 int p = 0;
00450 int q = 1;
00451 int r = 2;
00452 tfScalar max = tfFabs(m_el[0][1]);
00453 tfScalar v = tfFabs(m_el[0][2]);
00454 if (v > max)
00455 {
00456 q = 2;
00457 r = 1;
00458 max = v;
00459 }
00460 v = tfFabs(m_el[1][2]);
00461 if (v > max)
00462 {
00463 p = 1;
00464 q = 2;
00465 r = 0;
00466 max = v;
00467 }
00468
00469 tfScalar t = threshold * (tfFabs(m_el[0][0]) + tfFabs(m_el[1][1]) + tfFabs(m_el[2][2]));
00470 if (max <= t)
00471 {
00472 if (max <= TFSIMD_EPSILON * t)
00473 {
00474 return;
00475 }
00476 step = 1;
00477 }
00478
00479
00480 tfScalar mpq = m_el[p][q];
00481 tfScalar theta = (m_el[q][q] - m_el[p][p]) / (2 * mpq);
00482 tfScalar theta2 = theta * theta;
00483 tfScalar cos;
00484 tfScalar sin;
00485 if (theta2 * theta2 < tfScalar(10 / TFSIMD_EPSILON))
00486 {
00487 t = (theta >= 0) ? 1 / (theta + tfSqrt(1 + theta2))
00488 : 1 / (theta - tfSqrt(1 + theta2));
00489 cos = 1 / tfSqrt(1 + t * t);
00490 sin = cos * t;
00491 }
00492 else
00493 {
00494
00495 t = 1 / (theta * (2 + tfScalar(0.5) / theta2));
00496 cos = 1 - tfScalar(0.5) * t * t;
00497 sin = cos * t;
00498 }
00499
00500
00501 m_el[p][q] = m_el[q][p] = 0;
00502 m_el[p][p] -= t * mpq;
00503 m_el[q][q] += t * mpq;
00504 tfScalar mrp = m_el[r][p];
00505 tfScalar mrq = m_el[r][q];
00506 m_el[r][p] = m_el[p][r] = cos * mrp - sin * mrq;
00507 m_el[r][q] = m_el[q][r] = cos * mrq + sin * mrp;
00508
00509
00510 for (int i = 0; i < 3; i++)
00511 {
00512 Vector3& row = rot[i];
00513 mrp = row[p];
00514 mrq = row[q];
00515 row[p] = cos * mrp - sin * mrq;
00516 row[q] = cos * mrq + sin * mrp;
00517 }
00518 }
00519 }
00520
00521
00522
00523
00531 tfScalar cofac(int r1, int c1, int r2, int c2) const
00532 {
00533 return m_el[r1][c1] * m_el[r2][c2] - m_el[r1][c2] * m_el[r2][c1];
00534 }
00535
00536 void serialize(struct Matrix3x3Data& dataOut) const;
00537
00538 void serializeFloat(struct Matrix3x3FloatData& dataOut) const;
00539
00540 void deSerialize(const struct Matrix3x3Data& dataIn);
00541
00542 void deSerializeFloat(const struct Matrix3x3FloatData& dataIn);
00543
00544 void deSerializeDouble(const struct Matrix3x3DoubleData& dataIn);
00545
00546 };
00547
00548
00549 TFSIMD_FORCE_INLINE Matrix3x3&
00550 Matrix3x3::operator*=(const Matrix3x3& m)
00551 {
00552 setValue(m.tdotx(m_el[0]), m.tdoty(m_el[0]), m.tdotz(m_el[0]),
00553 m.tdotx(m_el[1]), m.tdoty(m_el[1]), m.tdotz(m_el[1]),
00554 m.tdotx(m_el[2]), m.tdoty(m_el[2]), m.tdotz(m_el[2]));
00555 return *this;
00556 }
00557
00558 TFSIMD_FORCE_INLINE tfScalar
00559 Matrix3x3::determinant() const
00560 {
00561 return tfTriple((*this)[0], (*this)[1], (*this)[2]);
00562 }
00563
00564
00565 TFSIMD_FORCE_INLINE Matrix3x3
00566 Matrix3x3::absolute() const
00567 {
00568 return Matrix3x3(
00569 tfFabs(m_el[0].x()), tfFabs(m_el[0].y()), tfFabs(m_el[0].z()),
00570 tfFabs(m_el[1].x()), tfFabs(m_el[1].y()), tfFabs(m_el[1].z()),
00571 tfFabs(m_el[2].x()), tfFabs(m_el[2].y()), tfFabs(m_el[2].z()));
00572 }
00573
00574 TFSIMD_FORCE_INLINE Matrix3x3
00575 Matrix3x3::transpose() const
00576 {
00577 return Matrix3x3(m_el[0].x(), m_el[1].x(), m_el[2].x(),
00578 m_el[0].y(), m_el[1].y(), m_el[2].y(),
00579 m_el[0].z(), m_el[1].z(), m_el[2].z());
00580 }
00581
00582 TFSIMD_FORCE_INLINE Matrix3x3
00583 Matrix3x3::adjoint() const
00584 {
00585 return Matrix3x3(cofac(1, 1, 2, 2), cofac(0, 2, 2, 1), cofac(0, 1, 1, 2),
00586 cofac(1, 2, 2, 0), cofac(0, 0, 2, 2), cofac(0, 2, 1, 0),
00587 cofac(1, 0, 2, 1), cofac(0, 1, 2, 0), cofac(0, 0, 1, 1));
00588 }
00589
00590 TFSIMD_FORCE_INLINE Matrix3x3
00591 Matrix3x3::inverse() const
00592 {
00593 Vector3 co(cofac(1, 1, 2, 2), cofac(1, 2, 2, 0), cofac(1, 0, 2, 1));
00594 tfScalar det = (*this)[0].dot(co);
00595 tfFullAssert(det != tfScalar(0.0));
00596 tfScalar s = tfScalar(1.0) / det;
00597 return Matrix3x3(co.x() * s, cofac(0, 2, 2, 1) * s, cofac(0, 1, 1, 2) * s,
00598 co.y() * s, cofac(0, 0, 2, 2) * s, cofac(0, 2, 1, 0) * s,
00599 co.z() * s, cofac(0, 1, 2, 0) * s, cofac(0, 0, 1, 1) * s);
00600 }
00601
00602 TFSIMD_FORCE_INLINE Matrix3x3
00603 Matrix3x3::transposeTimes(const Matrix3x3& m) const
00604 {
00605 return Matrix3x3(
00606 m_el[0].x() * m[0].x() + m_el[1].x() * m[1].x() + m_el[2].x() * m[2].x(),
00607 m_el[0].x() * m[0].y() + m_el[1].x() * m[1].y() + m_el[2].x() * m[2].y(),
00608 m_el[0].x() * m[0].z() + m_el[1].x() * m[1].z() + m_el[2].x() * m[2].z(),
00609 m_el[0].y() * m[0].x() + m_el[1].y() * m[1].x() + m_el[2].y() * m[2].x(),
00610 m_el[0].y() * m[0].y() + m_el[1].y() * m[1].y() + m_el[2].y() * m[2].y(),
00611 m_el[0].y() * m[0].z() + m_el[1].y() * m[1].z() + m_el[2].y() * m[2].z(),
00612 m_el[0].z() * m[0].x() + m_el[1].z() * m[1].x() + m_el[2].z() * m[2].x(),
00613 m_el[0].z() * m[0].y() + m_el[1].z() * m[1].y() + m_el[2].z() * m[2].y(),
00614 m_el[0].z() * m[0].z() + m_el[1].z() * m[1].z() + m_el[2].z() * m[2].z());
00615 }
00616
00617 TFSIMD_FORCE_INLINE Matrix3x3
00618 Matrix3x3::timesTranspose(const Matrix3x3& m) const
00619 {
00620 return Matrix3x3(
00621 m_el[0].dot(m[0]), m_el[0].dot(m[1]), m_el[0].dot(m[2]),
00622 m_el[1].dot(m[0]), m_el[1].dot(m[1]), m_el[1].dot(m[2]),
00623 m_el[2].dot(m[0]), m_el[2].dot(m[1]), m_el[2].dot(m[2]));
00624
00625 }
00626
00627 TFSIMD_FORCE_INLINE Vector3
00628 operator*(const Matrix3x3& m, const Vector3& v)
00629 {
00630 return Vector3(m[0].dot(v), m[1].dot(v), m[2].dot(v));
00631 }
00632
00633
00634 TFSIMD_FORCE_INLINE Vector3
00635 operator*(const Vector3& v, const Matrix3x3& m)
00636 {
00637 return Vector3(m.tdotx(v), m.tdoty(v), m.tdotz(v));
00638 }
00639
00640 TFSIMD_FORCE_INLINE Matrix3x3
00641 operator*(const Matrix3x3& m1, const Matrix3x3& m2)
00642 {
00643 return Matrix3x3(
00644 m2.tdotx( m1[0]), m2.tdoty( m1[0]), m2.tdotz( m1[0]),
00645 m2.tdotx( m1[1]), m2.tdoty( m1[1]), m2.tdotz( m1[1]),
00646 m2.tdotx( m1[2]), m2.tdoty( m1[2]), m2.tdotz( m1[2]));
00647 }
00648
00649
00650
00651
00652
00653
00654
00655
00656
00657
00658
00659
00660
00661
00662
00663
00666 TFSIMD_FORCE_INLINE bool operator==(const Matrix3x3& m1, const Matrix3x3& m2)
00667 {
00668 return ( m1[0][0] == m2[0][0] && m1[1][0] == m2[1][0] && m1[2][0] == m2[2][0] &&
00669 m1[0][1] == m2[0][1] && m1[1][1] == m2[1][1] && m1[2][1] == m2[2][1] &&
00670 m1[0][2] == m2[0][2] && m1[1][2] == m2[1][2] && m1[2][2] == m2[2][2] );
00671 }
00672
00674 struct Matrix3x3FloatData
00675 {
00676 Vector3FloatData m_el[3];
00677 };
00678
00680 struct Matrix3x3DoubleData
00681 {
00682 Vector3DoubleData m_el[3];
00683 };
00684
00685
00686
00687
00688 TFSIMD_FORCE_INLINE void Matrix3x3::serialize(struct Matrix3x3Data& dataOut) const
00689 {
00690 for (int i=0;i<3;i++)
00691 m_el[i].serialize(dataOut.m_el[i]);
00692 }
00693
00694 TFSIMD_FORCE_INLINE void Matrix3x3::serializeFloat(struct Matrix3x3FloatData& dataOut) const
00695 {
00696 for (int i=0;i<3;i++)
00697 m_el[i].serializeFloat(dataOut.m_el[i]);
00698 }
00699
00700
00701 TFSIMD_FORCE_INLINE void Matrix3x3::deSerialize(const struct Matrix3x3Data& dataIn)
00702 {
00703 for (int i=0;i<3;i++)
00704 m_el[i].deSerialize(dataIn.m_el[i]);
00705 }
00706
00707 TFSIMD_FORCE_INLINE void Matrix3x3::deSerializeFloat(const struct Matrix3x3FloatData& dataIn)
00708 {
00709 for (int i=0;i<3;i++)
00710 m_el[i].deSerializeFloat(dataIn.m_el[i]);
00711 }
00712
00713 TFSIMD_FORCE_INLINE void Matrix3x3::deSerializeDouble(const struct Matrix3x3DoubleData& dataIn)
00714 {
00715 for (int i=0;i<3;i++)
00716 m_el[i].deSerializeDouble(dataIn.m_el[i]);
00717 }
00718
00719 }
00720
00721 #endif //TF_MATRIX3x3_H
00722