7 #ifndef _MATRIX3D_MAL_DEFAULT_
8 #define _MATRIX3D_MAL_DEFAULT_
13 template<
typename U,
bool b>
26 template<
class Archive>
126 template<
typename T2>
158 T q0 = q[0], q1 = q[1], q2 = q[2], q3 = q[3];
159 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
162 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
163 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
164 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
165 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
167 m[0] = T(1.0) - (yy + zz),
m[1] = xy - wz,
m[2] = xz + wy,
m[3] = xy + wz,
m[4] = T(1.0) - (xx + zz),
168 m[5] = yz - wx,
m[6] = xz - wy,
m[7] = yz + wx,
m[8] = T(1.0) - (xx + yy);
172 explicit Matrix3x3T<T>(
const T & q0,
const T & q1,
const T & q2,
const T & q3)
174 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
177 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
178 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
179 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
180 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
182 m[0] = T(1.0) - (yy + zz);
186 m[4] = T(1.0) - (xx + zz);
190 m[8] = T(1.0) - (xx + yy);
197 T sin_a = sin(angle / 2), cos_a = cos(angle / 2);
199 T q0 = axis[0] * sin_a;
200 T q1 = axis[1] * sin_a;
201 T q2 = axis[2] * sin_a;
204 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
208 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
209 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
210 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
211 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
213 m[0] = T(1.0) - (yy + zz);
217 m[4] = T(1.0) - (xx + zz);
221 m[8] = T(1.0) - (xx + yy);
241 this->m[0] = cy * cp;
242 this->m[1] = cysp * sr - sycr;
243 this->m[2] = cysp * cr + sysr;
245 this->m[3] = sy * cp;
246 this->m[4] = sysp * sr + cy * cr;
247 this->m[5] = sysp * cr - cy * sr;
250 this->m[7] = cp * sr;
251 this->m[8] = cp * cr;
255 void Set(
const T x0,
const T x1,
const T x2,
const T x3,
const T x4,
const T x5,
const T x6,
const T x7,
const T x8)
272 T sin_a = sin(angle / 2), cos_a = cos(angle / 2);
274 T q0 = axis[0] * sin_a;
275 T q1 = axis[1] * sin_a;
276 T q2 = axis[2] * sin_a;
279 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
283 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
284 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
285 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
286 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
287 this->m[0] = T(1.0) - (yy + zz);
288 this->m[1] = xy - wz;
289 this->m[2] = xz + wy;
290 this->m[3] = xy + wz;
291 this->m[4] = T(1.0) - (xx + zz);
292 this->m[5] = yz - wx;
293 this->m[6] = xz - wy;
294 this->m[7] = yz + wx;
295 this->m[8] = T(1.0) - (xx + yy);
299 void Set(
const T *
const x)
315 T q0 = q[0], q1 = q[1], q2 = q[2], q3 = q[3];
316 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
319 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
320 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
321 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
322 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
323 this->m[0] = T(1.0) - (yy + zz), this->m[1] = xy - wz, this->m[2] = xz + wy, this->m[3] = xy + wz,
324 this->m[4] = T(1.0) - (xx + zz), this->m[5] = yz - wx, this->m[6] = xz - wy, this->m[7] = yz + wx,
325 this->m[8] = T(1.0) - (xx + yy);
329 void Set(
const T & q0,
const T & q1,
const T & q2,
const T & q3)
331 T d = q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3;
334 T xs = q0 * s, ys = q1 * s, zs = q2 * s;
335 T wx = q3 * xs, wy = q3 * ys, wz = q3 * zs;
336 T xx = q0 * xs, xy = q0 * ys, xz = q0 * zs;
337 T yy = q1 * ys, yz = q1 * zs, zz = q2 * zs;
338 this->m[0] = T(1.0) - (yy + zz);
339 this->m[1] = xy - wz;
340 this->m[2] = xz + wy;
341 this->m[3] = xy + wz;
342 this->m[4] = T(1.0) - (xx + zz);
343 this->m[5] = yz - wx;
344 this->m[6] = xz - wy;
345 this->m[7] = yz + wx;
346 this->m[8] = T(1.0) - (xx + yy);
350 void Set(
const T & yaw,
const T & pitch,
const T & roll)
352 T cy(cos(
double(yaw)));
353 T sy(sin(
double(yaw)));
354 T cp(cos(
double(pitch)));
355 T sp(sin(
double(pitch)));
356 T cr(cos(
double(roll)));
357 T sr(sin(
double(roll)));
363 this->m[0] = cc + sp * ss;
364 this->m[1] = cs - sp * sc;
365 this->m[2] = -sy * cp;
366 this->m[3] = -cp * sr;
367 this->m[4] = cp * cr;
369 this->m[6] = sc - sp * cs;
370 this->m[7] = ss + sp * cc;
371 this->m[8] = cy * cp;
393 inline const T &
operator()(
unsigned int i,
unsigned int j)
const
430 A.
m[0] =
m[0] + B.
m[0];
431 A.
m[1] =
m[1] + B.
m[1];
432 A.
m[2] =
m[2] + B.
m[2];
433 A.
m[3] =
m[3] + B.
m[3];
434 A.
m[4] =
m[4] + B.
m[4];
435 A.
m[5] =
m[5] + B.
m[5];
436 A.
m[6] =
m[6] + B.
m[6];
437 A.
m[7] =
m[7] + B.
m[7];
438 A.
m[8] =
m[8] + B.
m[8];
446 A.
m[0] =
m[0] - B.m[0];
447 A.
m[1] =
m[1] - B.m[1];
448 A.
m[2] =
m[2] - B.m[2];
449 A.
m[3] =
m[3] - B.m[3];
450 A.
m[4] =
m[4] - B.m[4];
451 A.
m[5] =
m[5] - B.m[5];
452 A.
m[6] =
m[6] - B.m[6];
453 A.
m[7] =
m[7] - B.m[7];
454 A.
m[8] =
m[8] - B.m[8];
460 C.
m[0] =
m[0] * B.
m[0] +
m[1] * B.
m[3] +
m[2] * B.
m[6];
461 C.
m[1] =
m[0] * B.
m[1] +
m[1] * B.
m[4] +
m[2] * B.
m[7];
462 C.
m[2] =
m[0] * B.
m[2] +
m[1] * B.
m[5] +
m[2] * B.
m[8];
463 C.
m[3] =
m[3] * B.
m[0] +
m[4] * B.
m[3] +
m[5] * B.
m[6];
464 C.
m[4] =
m[3] * B.
m[1] +
m[4] * B.
m[4] +
m[5] * B.
m[7];
465 C.
m[5] =
m[3] * B.
m[2] +
m[4] * B.
m[5] +
m[5] * B.
m[8];
466 C.
m[6] =
m[6] * B.
m[0] +
m[7] * B.
m[3] +
m[8] * B.
m[6];
467 C.
m[7] =
m[6] * B.
m[1] +
m[7] * B.
m[4] +
m[8] * B.
m[7];
468 C.
m[8] =
m[6] * B.
m[2] +
m[7] * B.
m[5] +
m[8] * B.
m[8];
475 result.
m[0] =
m[0] * r;
476 result.
m[1] =
m[1] * r;
477 result.
m[2] =
m[2] * r;
478 result.
m[3] =
m[3] * r;
479 result.
m[4] =
m[4] * r;
480 result.
m[5] =
m[5] * r;
481 result.
m[6] =
m[6] * r;
482 result.
m[7] =
m[7] * r;
483 result.
m[8] =
m[8] * r;
490 Vector3T<T, b> vr(
m[0] * v[0] +
m[1] * v[1] +
m[2] * v[2],
m[3] * v[0] +
m[4] * v[1] +
m[5] * v[2],
491 m[6] * v[0] +
m[7] * v[1] +
m[8] * v[2]);
500 C[0] =
m[0] * B[0] +
m[1] * B[1] +
m[2] * B[2];
501 C[1] =
m[3] * B[0] +
m[4] * B[1] +
m[5] * B[2];
502 C[2] =
m[6] * B[0] +
m[7] * B[1] +
m[8] * B[2];
527 return Matrix3x3T<T>(this->m[0], this->m[3], this->m[6], this->m[1], this->m[4], this->m[7], this->m[2], this->m[5],
549 A.
m[0] = (
m[4] *
m[8] -
m[5] *
m[7]) * det;
550 A.
m[1] = (
m[2] *
m[7] -
m[1] *
m[8]) * det;
551 A.
m[2] = (
m[1] *
m[5] -
m[2] *
m[4]) * det;
552 A.
m[3] = (
m[5] *
m[6] -
m[3] *
m[8]) * det;
553 A.
m[4] = (
m[0] *
m[8] -
m[2] *
m[6]) * det;
554 A.
m[5] = (
m[2] *
m[3] -
m[0] *
m[5]) * det;
555 A.
m[6] = (
m[3] *
m[7] -
m[4] *
m[6]) * det;
556 A.
m[7] = (
m[1] *
m[6] -
m[0] *
m[7]) * det;
557 A.
m[8] = (
m[0] *
m[4] -
m[1] *
m[3]) * det;
563 T det =
m[0] *
m[4] *
m[8];
564 det +=
m[1] *
m[5] *
m[6];
565 det +=
m[2] *
m[3] *
m[7];
566 det -=
m[2] *
m[4] *
m[6];
567 det -=
m[0] *
m[5] *
m[7];
568 det -=
m[1] *
m[3] *
m[8];
589 return ((
m[0] == 1) && (
m[4] == 1) && (
m[8] == 1) && (
m[1] == 0) && (
m[2] == 0) && (
m[3] == 0) && (
m[5] == 0)
590 && (
m[6] == 0) && (
m[7] == 0));
626 m[0] * B.
m[2] +
m[1] * B.
m[5] +
m[2] * B.
m[8],
m[3] * B.
m[0] +
m[4] * B.
m[3] +
m[5] * B.
m[6],
627 m[3] * B.
m[1] +
m[4] * B.
m[4] +
m[5] * B.
m[7],
m[3] * B.
m[2] +
m[4] * B.
m[5] +
m[5] * B.
m[8],
628 m[6] * B.
m[0] +
m[7] * B.
m[3] +
m[8] * B.
m[6],
m[6] * B.
m[1] +
m[7] * B.
m[4] +
m[8] * B.
m[7],
629 m[6] * B.
m[2] +
m[7] * B.
m[5] +
m[8] * B.
m[8]);
636 m[0] = temp.
m[0] * B.
m[0] + temp.
m[1] * B.
m[3] + temp.
m[2] * B.
m[6];
637 m[1] = temp.
m[0] * B.
m[1] + temp.
m[1] * B.
m[4] + temp.
m[2] * B.
m[7];
638 m[2] = temp.
m[0] * B.
m[2] + temp.
m[1] * B.
m[5] + temp.
m[2] * B.
m[8];
639 m[3] = temp.
m[3] * B.
m[0] + temp.
m[4] * B.
m[3] + temp.
m[5] * B.
m[6];
640 m[4] = temp.
m[3] * B.
m[1] + temp.
m[4] * B.
m[4] + temp.
m[5] * B.
m[7];
641 m[5] = temp.
m[3] * B.
m[2] + temp.
m[4] * B.
m[5] + temp.
m[5] * B.
m[8];
642 m[6] = temp.
m[6] * B.
m[0] + temp.
m[7] * B.
m[3] + temp.
m[8] * B.
m[6];
643 m[7] = temp.
m[6] * B.
m[1] + temp.
m[7] * B.
m[4] + temp.
m[8] * B.
m[7];
644 m[8] = temp.
m[6] * B.
m[2] + temp.
m[7] * B.
m[5] + temp.
m[8] * B.
m[8];
663 for(
int i = 0; i < 3; i++)
665 for(
int j = 0; j < 3; j++) os << A.
m[i * 3 + j] <<
" ";