57 #define TRRFN(root, suffix) root ## suffix 58 #define TRFN(root, suffix) TRRFN(root, suffix) 59 #define TFN(suffix) TRFN(TNAME, suffix) 68 memcpy(r, v, len *
sizeof(
TNAME));
74 for (
int i = 0; i < len; i++)
81 for (
int i = 0; i < nrows * ncols; i++) {
83 if ((i % ncols) == (ncols - 1))
90 for (
int i = 0; i < 4 * 4; i++) {
99 for (
int i = 0; i < len; i++)
105 for (
int i = 0; i < len; i++)
111 for (
int i = 0; i < len; i++)
118 for (
int i = 0; i < len; i++)
126 for (
int i = 0; i < len; i++)
127 acc += (a[i] - b[i])*(a[i] - b[i]);
134 for (
int i = 0; i < len; i++)
135 acc += (a[i] - b[i])*(a[i] - b[i]);
142 for (
int i = 0; i < len; i++)
150 for (
int i = 0; i < len; i++)
158 for (
int i = 0; i < len; i++)
165 for (
int i = 0; i < len; i++)
171 for (
int i = 0; i < len; i++)
177 TNAME t2, t3, t4, t5, t6, t7, t8, t9, t10;
189 r[0] = 2*((t8+t10)*v[0] + (t6-t4)*v[1] + (t3+t7)*v[2]) + v[0];
190 r[1] = 2*((t4+t6)*v[0] + (t5+t10)*v[1] + (t9-t2)*v[2]) + v[1];
191 r[2] = 2*((t7-t3)*v[0] + (t2+t9)*v[1] + (t5+t8)*v[2]) + v[2];
196 r[0] = a[0]*b[0] - a[1]*b[1] - a[2]*b[2] - a[3]*b[3];
197 r[1] = a[0]*b[1] + a[1]*b[0] + a[2]*b[3] - a[3]*b[2];
198 r[2] = a[0]*b[2] - a[1]*b[3] + a[2]*b[0] + a[3]*b[1];
199 r[3] = a[0]*b[3] + a[1]*b[2] - a[2]*b[1] + a[3]*b[0];
213 memcpy(dst, src, n *
sizeof(
TNAME));
223 TNAME s = sin(xyt[2]), c = cos(xyt[2]);
224 memset(r, 0,
sizeof(
TNAME)*16);
237 TNAME s = sin(xyt[2]), c = cos(xyt[2]);
238 r[0] = c*xy[0] - s*xy[1] + xyt[0];
239 r[1] = s*xy[0] + c*xy[1] + xyt[1];
244 r[0] = M[0]*xyz[0] + M[1]*xyz[1] + M[2]*xyz[2] + M[3];
245 r[1] = M[4]*xyz[0] + M[5]*xyz[1] + M[6]*xyz[2] + M[7];
246 r[2] = M[8]*xyz[0] + M[9]*xyz[1] + M[10]*xyz[2] + M[11];
257 r[0] =
mod2pi(2 * atan2(mag, q[0]));
272 q[0] = cos(rad / 2.0);
273 TNAME s = sin(rad / 2.0);
275 TNAME v[3] = { aa[1], aa[2], aa[3] };
285 TNAME w = q[0], x = q[1], y = q[2], z = q[3];
287 r[0] = w*w + x*x - y*y - z*z;
288 r[1] = 2*x*y - 2*w*z;
289 r[2] = 2*x*z + 2*w*y;
292 r[4] = 2*x*y + 2*w*z;
293 r[5] = w*w - x*x + y*y - z*z;
294 r[6] = 2*y*z - 2*w*x;
297 r[8] = 2*x*z - 2*w*y;
298 r[9] = 2*y*z + 2*w*x;
299 r[10] = w*w - x*x - y*y + z*z;
329 TNAME roll = rpy[0], pitch = rpy[1], yaw = rpy[2];
331 TNAME halfroll = roll / 2;
332 TNAME halfpitch = pitch / 2;
333 TNAME halfyaw = yaw / 2;
335 TNAME sin_r2 = sin(halfroll);
336 TNAME sin_p2 = sin(halfpitch);
337 TNAME sin_y2 = sin(halfyaw);
339 TNAME cos_r2 = cos(halfroll);
340 TNAME cos_p2 = cos(halfpitch);
341 TNAME cos_y2 = cos(halfyaw);
343 quat[0] = cos_r2 * cos_p2 * cos_y2 + sin_r2 * sin_p2 * sin_y2;
344 quat[1] = sin_r2 * cos_p2 * cos_y2 - cos_r2 * sin_p2 * sin_y2;
345 quat[2] = cos_r2 * sin_p2 * cos_y2 + sin_r2 * cos_p2 * sin_y2;
346 quat[3] = cos_r2 * cos_p2 * sin_y2 - sin_r2 * sin_p2 * cos_y2;
353 const TNAME qr = q[0];
354 const TNAME qx = q[1];
355 const TNAME qy = q[2];
356 const TNAME qz = q[3];
358 TNAME disc = qr*qy - qx*qz;
360 if (fabs(disc+0.5) < DBL_EPSILON) {
363 rpy[2] = 2 * atan2(qx, qr);
365 else if (fabs(disc-0.5) < DBL_EPSILON) {
368 rpy[2] = -2 * atan2(qx, qr);
372 TNAME roll_a = 2 * (qr*qx + qy*qz);
373 TNAME roll_b = 1 - 2 * (qx*qx + qy*qy);
374 rpy[0] = atan2(roll_a, roll_b);
377 rpy[1] = asin(2*disc);
380 TNAME yaw_a = 2 * (qr*qz + qx*qy);
381 TNAME yaw_b = 1 - 2 * (qy*qy + qz*qz);
382 rpy[2] = atan2(yaw_a, yaw_b);
404 for (
int i = 0; i < 3; i++)
405 out[i] = M[4*i + 0]*in[0] + M[4*i + 1]*in[1] + M[4*i + 2]*in[2] + M[4*i + 3];
411 for (
int i = 0; i < 3; i++)
412 out[i] = M[4*i + 0]*in[0] + M[4*i + 1]*in[1] + M[4*i + 2]*in[2];
421 xyt[2] = atan2(M[4], M[0]);
433 double T = M[0] + M[5] + M[10] + 1.0;
439 q[1] = (M[9] - M[6]) / S;
440 q[2] = (M[2] - M[8]) / S;
441 q[3] = (M[4] - M[1]) / S;
442 }
else if (M[0] > M[5] && M[0] > M[10]) {
443 S = sqrt(1.0 + M[0] - M[5] - M[10]) * 2;
444 q[0] = (M[9] - M[6]) / S;
446 q[2] = (M[4] + M[1]) / S;
447 q[3] = (M[2] + M[8]) / S;
448 }
else if (M[5] > M[10]) {
449 S = sqrt(1.0 + M[5] - M[0] - M[10]) * 2;
450 q[0] = (M[2] - M[8]) / S;
451 q[1] = (M[4] + M[1]) / S;
453 q[3] = (M[9] + M[6]) / S;
455 S = sqrt(1.0 + M[10] - M[0] - M[5]);
456 q[0] = (M[4] - M[1]) / S;
457 q[1] = (M[2] + M[8]) / S;
458 q[2] = (M[9] + M[6]) / S;
475 TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
476 TNAME s = sin(ta), c = cos(ta);
478 xytr[0] = c*xytb[0] - s*xytb[1] + xa;
479 xytr[1] = s*xytb[0] + c*xytb[1] + ya;
480 xytr[2] = ta + xytb[2];
486 memcpy(xytr, xyta, 3 *
sizeof(
TNAME));
487 memcpy(Cr, Ca, 9 *
sizeof(
TNAME));
494 TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
495 TNAME xb = xytb[0], yb = xytb[1];
497 TNAME sa = sin(ta), ca = cos(ta);
499 TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
500 TNAME P22 = Ca[4], P23 = Ca[5];
503 TNAME Q11 = Cb[0], Q12 = Cb[1], Q13 = Cb[2];
504 TNAME Q22 = Cb[4], Q23 = Cb[5];
507 TNAME JA13 = -sa*xb - ca*yb;
508 TNAME JA23 = ca*xb - sa*yb;
514 Cr[0] = P33*JA13*JA13 + 2*P13*JA13 + Q11*JB11*JB11 + 2*Q12*JB11*JB12 + Q22*JB12*JB12 + P11;
515 Cr[1] = P12 + JA23*(P13 + JA13*P33) + JA13*P23 + JB21*(JB11*Q11 + JB12*Q12) + JB22*(JB11*Q12 + JB12*Q22);
516 Cr[2] = P13 + JA13*P33 + JB11*Q13 + JB12*Q23;
518 Cr[4] = P33*JA23*JA23 + 2*P23*JA23 + Q11*JB21*JB21 + 2*Q12*JB21*JB22 + Q22*JB22*JB22 + P22;
519 Cr[5] = P23 + JA23*P33 + JB21*Q13 + JB22*Q23;
524 xytr[0] = ca*xb - sa*yb + xa;
525 xytr[1] = sa*xb + ca*yb + ya;
526 xytr[2] = xyta[2] + xytb[2];
546 TNAME s = sin(xyta[2]), c = cos(xyta[2]);
547 xytr[0] = -s*xyta[1] - c*xyta[0];
548 xytr[1] = -c*xyta[1] + s*xyta[0];
555 TNAME x = xyta[0], y = xyta[1], theta = xyta[2];
556 TNAME s = sin(theta), c = cos(theta);
558 TNAME J11 = -c, J12 = -s, J13 = -c*y + s*x;
559 TNAME J21 = s, J22 = -c, J23 = s*y + c*x;
561 TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
562 TNAME P22 = Ca[4], P23 = Ca[5];
565 Cr[0] = P11*J11*J11 + 2*P12*J11*J12 + 2*P13*J11*J13 +
566 P22*J12*J12 + 2*P23*J12*J13 + P33*J13*J13;
567 Cr[1] = J21*(J11*P11 + J12*P12 + J13*P13) +
568 J22*(J11*P12 + J12*P22 + J13*P23) +
569 J23*(J11*P13 + J12*P23 + J13*P33);
570 Cr[2] = - J11*P13 - J12*P23 - J13*P33;
572 Cr[4] = P11*J21*J21 + 2*P12*J21*J22 + 2*P13*J21*J23 +
573 P22*J22*J22 + 2*P23*J22*J23 + P33*J23*J23;
574 Cr[5] = - J21*P13 - J22*P23 - J23*P33;
588 xytr[0] = -s*y - c*x;
589 xytr[1] = -c*y + s*x;
596 TNAME theta = xyta[2];
597 TNAME ca = cos(theta);
598 TNAME sa = sin(theta);
599 TNAME dx = xytb[0] - xyta[0];
600 TNAME dy = xytb[1] - xyta[1];
602 xytr[0] = ca*dx + sa*dy;
603 xytr[1] = -sa*dx + ca*dy;
604 xytr[2]= xytb[2] - xyta[2];
608 const TNAME *B,
int Brows,
int Bcols,
609 TNAME *R,
int Rrows,
int Rcols)
611 assert(Arows == Brows);
612 assert(Arows == Rrows);
613 assert(Bcols == Bcols);
614 assert(Bcols == Rcols);
616 for (
int i = 0; i < Arows; i++)
617 for (
int j = 0; j < Bcols; j++)
618 R[i*Acols + j] = A[i*Acols + j] + B[i*Acols + j];
624 const TNAME *B,
int Brows,
int Bcols,
625 TNAME *R,
int Rrows,
int Rcols)
627 assert(Acols == Brows);
628 assert(Rrows == Arows);
629 assert(Bcols == Rcols);
631 for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
632 for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
634 for (
int i = 0; i < Acols; i++)
635 acc += A[Rrow*Acols + i] * B[i*Bcols + Rcol];
636 R[Rrow*Rcols + Rcol] = acc;
644 const TNAME *B,
int Brows,
int Bcols,
645 TNAME *R,
int Rrows,
int Rcols)
647 assert(Acols == Bcols);
648 assert(Rrows == Arows);
649 assert(Brows == Rcols);
651 for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
652 for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
654 for (
int i = 0; i < Acols; i++)
655 acc += A[Rrow*Acols + i] * B[Rcol*Bcols + i];
656 R[Rrow*Rcols + Rcol] = acc;
662 const TNAME *B,
int Brows,
int Bcols,
663 const TNAME *C,
int Crows,
int Ccols,
664 TNAME *R,
int Rrows,
int Rcols)
666 TNAME tmp[Arows*Bcols];
668 TFN(
s_mat_AB)(A, Arows, Acols, B, Brows, Bcols, tmp, Arows, Bcols);
669 TFN(
s_mat_AB)(tmp, Arows, Bcols, C, Crows, Ccols, R, Rrows, Rcols);
673 const TNAME *B,
int Blength,
674 TNAME *R,
int Rlength)
676 assert(Acols == Blength);
677 assert(Arows == Rlength);
679 for (
int Ridx = 0; Ridx < Rlength; Ridx++) {
681 for (
int i = 0; i < Blength; i++)
682 acc += A[Ridx*Acols + i] * B[i];
688 const TNAME *B,
int Brows,
int Bcols,
689 TNAME *R,
int Rrows,
int Rcols)
691 assert(Arows == Brows);
692 assert(Rrows == Acols);
693 assert(Bcols == Rcols);
695 for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
696 for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
698 for (
int i = 0; i < Acols; i++)
699 acc += A[i*Acols + Rrow] * B[i*Bcols + Rcol];
700 R[Rrow*Rcols + Rcol] = acc;
710 memcpy(q1, _q1,
sizeof(
TNAME) * 4);
717 for (
int i = 0; i < 4; i++)
725 for (
int i = 0; i < 4; i++)
726 r[i] = q0[i]*(1-w) + q1[i]*w;
729 TNAME angle = acos(dot);
731 TNAME w0 = sin(angle*(1-w)), w1 = sin(angle*w);
733 for (
int i = 0; i < 4; i++)
734 r[i] = q0[i]*w0 + q1[i]*w1;
742 r[0] = v1[1]*v2[2] - v1[2]*v2[1];
743 r[1] = v1[2]*v2[0] - v1[0]*v2[2];
744 r[2] = v1[0]*v2[1] - v1[1]*v2[0];
750 memset(out, 0, 16 *
sizeof(
TNAME));
761 for (
int i = 0; i < 3; i++)
762 out[4*i + 3] += txyz[i];
769 for (
int i = 0; i < 3; i++)
770 out[4*i + i] = sxyz[i];
776 double s = sin(rad), c = cos(rad);
786 double s = sin(rad), c = cos(rad);
796 double s = sin(rad), c = cos(rad);
806 TNAME tmp[16], prod[16];
809 memcpy(out, prod,
sizeof(
TNAME)*16);
814 TNAME tmp[16], prod[16];
817 memcpy(out, prod,
sizeof(
TNAME)*16);
822 TNAME tmp[16], prod[16];
825 memcpy(out, prod,
sizeof(
TNAME)*16);
834 for (
int i = 0; i < 3; i++)
835 for (
int j = 0; j < 3; j++)
836 out[4*i + j] = M[4*j + i];
842 for (
int i = 0; i < 3; i++)
843 for (
int j = 0; j < 3; j++)
844 out[4*i + 3] -= out[4*i + j] * M[4*j + 3];
888 for (
int i = 0; i < 3; i++)
889 up[i] -= up_dot*f[i];
897 TNAME R[16] = { s[0], s[1], s[2], 0,
899 -f[0], -f[1], -f[2], 0,
902 TNAME T[16] = {1, 0, 0, -eye[0],
916 TNAME *R,
int Brows,
int Bcols)
918 assert(Arows == Brows);
919 assert(Bcols == Bcols);
931 R[4] = sqrt(A[4] - R[3]*R[3]);
934 R[7] = (A[5] - R[3]*R[6]) / R[4];
937 R[8] = sqrt(A[8] - R[6]*R[6] - R[7]*R[7]);
945 TNAME *R,
int Rrows,
int Rcols)
951 R[3] = -A[3]*R[0] / A[4];
957 R[6] = (-A[6]*R[0] - A[7]*R[3]) / A[8];
960 R[7] = -A[7]*R[4] / A[8];
968 const TNAME *B,
int Brows,
int Bcols,
969 TNAME *R,
int Rrows,
int Rcols)
971 assert(Arows == Acols);
986 tmp[1] = M[3]*B[0] + M[4]*B[1];
987 tmp[2] = M[6]*B[0] + M[7]*B[1] + M[8]*B[2];
989 R[0] = M[0]*tmp[0] + M[3]*tmp[1] + M[6]*tmp[2];
990 R[1] = M[4]*tmp[1] + M[7]*tmp[2];
static void TFN() s_mat44_transform_xyz(const TNAME M[16], const TNAME in[3], TNAME out[3])
static void TFN() s_quat_xyz_to_mat44(const TNAME q[4], const TNAME xyz[3], TNAME r[16])
static void TFN() s_mat33_sym_solve(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_mat44_rotate_vector(const TNAME M[16], const TNAME in[3], TNAME out[3])
static void TFN() s_print(const TNAME *a, int len, const char *fmt)
static void TFN() s_quat_rotate(const TNAME q[4], const TNAME v[3], TNAME r[3])
static TNAME *TFN() s_dup(const TNAME *v, int len)
static void TFN() s_angleaxis_to_quat(const TNAME aa[4], TNAME q[4])
static void TFN() s_quat_slerp(const TNAME q0[4], const TNAME _q1[4], TNAME r[4], TNAME w)
static void TFN() s_elu_to_mat44(const TNAME eye[3], const TNAME lookat[3], const TNAME _up[3], TNAME M[16])
static void TFN() s_copy(const TNAME *src, TNAME *dst, int n)
static void TFN() s_normalize_self(TNAME *v, int len)
static void TFN() s_normalize(const TNAME *v, int len, TNAME *r)
static void TFN() s_print_mat44(const TNAME *a, const char *fmt)
static void TFN() s_mat44_translate(const TNAME txyz[3], TNAME out[16])
static void TFN() s_cross_product(const TNAME v1[3], const TNAME v2[3], TNAME r[3])
static void TFN() s_mat44_inv_rotate_vector(const TNAME M[16], const TNAME in[3], TNAME out[3])
static double mod2pi(double vin)
static void TFN() s_mat44_rotate_z_self(TNAME rad, TNAME out[16])
static void TFN() s_mat44_identity(TNAME out[16])
static void TFN() s_xyt_inv(const TNAME xyta[3], TNAME xytr[3])
static void TFN() s_mat44_inv(const TNAME M[16], TNAME out[16])
static void TFN() s_xyt_copy(const TNAME xyt[3], TNAME r[3])
static TNAME TFN() s_dot(const TNAME *a, const TNAME *b, int len)
static void TFN() s_xytcov_mul(const TNAME xyta[3], const TNAME Ca[9], const TNAME xytb[3], const TNAME Cb[9], TNAME xytr[3], TNAME Cr[9])
static void TFN() s_xytcov_inv(const TNAME xyta[3], const TNAME Ca[9], TNAME xytr[3], TNAME Cr[9])
static void TFN() s_mat33_lower_tri_inv(const TNAME *A, int Arows, int Acols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_xyt_to_mat44(const TNAME xyt[3], TNAME r[16])
static void TFN() s_mat_ABC(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, const TNAME *C, int Crows, int Ccols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_subtract(const TNAME *a, const TNAME *b, int len, TNAME *r)
static void TFN() s_rpy_to_mat44(const TNAME rpy[3], TNAME M[16])
static void TFN() s_quat_multiply(const TNAME a[4], const TNAME b[4], TNAME r[4])
static void TFN() s_mat_transform_xyz(const TNAME M[16], const TNAME xyz[3], TNAME r[3])
static void TFN() s_mat44_inv_transform_xyz(const TNAME M[16], const TNAME in[3], TNAME out[3])
static void TFN() s_quat_to_rpy(const TNAME q[4], TNAME rpy[3])
static void TFN() s_scale(TNAME s, const TNAME *v, int len, TNAME *r)
static void TFN() s_mat44_rotate_z(TNAME rad, TNAME out[16])
static TNAME TFN() s_squared_distance(const TNAME *a, const TNAME *b, int len)
static void TFN() s_mat44_scale_self(const TNAME sxyz[3], TNAME out[16])
static void TFN() s_xyt_mul(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
static void TFN() s_mat33_chol(const TNAME *A, int Arows, int Acols, TNAME *R, int Brows, int Bcols)
static void TFN() s_mat_to_xyz(const TNAME M[16], TNAME xyz[3])
static void TFN() s_quat_inverse(const TNAME q[4], TNAME r[4])
static void TFN() s_print_mat(const TNAME *a, int nrows, int ncols, const char *fmt)
static void TFN() s_scale_self(TNAME *v, int len, double scale)
static TNAME TFN() s_distance(const TNAME *a, const TNAME *b, int len)
static void TFN() s_mat44_translate_self(const TNAME txyz[3], TNAME out[16])
static void TFN() s_mat44_rotate_y(TNAME rad, TNAME out[16])
static void TFN() s_angleaxis_to_mat44(const TNAME aa[4], TNAME r[4])
static void TFN() s_quat_to_mat44(const TNAME q[4], TNAME r[16])
static void TFN() s_mat_AtB(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_mat44_to_xyt(const TNAME M[16], TNAME xyt[3])
static void TFN() s_xyt_inv_mul(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
static void TFN() s_mat44_rotate_x(TNAME rad, TNAME out[16])
static void TFN() s_quat_to_angleaxis(const TNAME _q[4], TNAME r[4])
static void TFN() s_mat_ABt(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, TNAME *R, int Rrows, int Rcols)
static TNAME TFN() s_magnitude(const TNAME *v, int len)
static void TFN() s_mat_to_quat(const TNAME M[16], TNAME q[4])
static void TFN() s_mat44_scale(const TNAME sxyz[3], TNAME out[16])
static void TFN() s_xyt_transform_xy(const TNAME xyt[3], const TNAME xy[2], TNAME r[2])
static void TFN() s_xytcov_copy(const TNAME xyta[3], const TNAME Ca[9], TNAME xytr[3], TNAME Cr[9])
static TNAME TFN() s_squared_magnitude(const TNAME *v, int len)
static void TFN() s_quat_xyz_to_xyt(const TNAME q[4], const TNAME xyz[3], TNAME xyt[3])
static void TFN() s_add(const TNAME *a, const TNAME *b, int len, TNAME *r)
static void TFN() s_mat_add(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_mat_AB(const TNAME *A, int Arows, int Acols, const TNAME *B, int Brows, int Bcols, TNAME *R, int Rrows, int Rcols)
static void TFN() s_rpy_to_quat(const TNAME rpy[3], TNAME quat[4])
static void TFN() s_xyzrpy_to_mat44(const TNAME xyzrpy[6], TNAME M[16])
static void TFN() s_mat_Ab(const TNAME *A, int Arows, int Acols, const TNAME *B, int Blength, TNAME *R, int Rlength)