63#define TRRFN(root, suffix) root ## suffix 
   64#define TRFN(root, suffix) TRRFN(root, suffix) 
   65#define TFN(suffix) TRFN(TNAME, suffix) 
   74    memcpy(r, v, len * 
sizeof(
TNAME));
 
 
   80    for (
int i = 0; i < len; i++)
 
 
   87    for (
int i = 0; i < nrows * ncols; i++) {
 
   89        if ((i % ncols) == (ncols - 1))
 
 
   96    for (
int i = 0; i < 4 * 4; i++) {
 
 
  105    for (
int i = 0; i < len; i++)
 
 
  111    for (
int i = 0; i < len; i++)
 
 
  117    for (
int i = 0; i < len; i++)
 
 
  124    for (
int i = 0; i < len; i++)
 
 
  132    for (
int i = 0; i < len; i++)
 
  133        acc += (a[i] - b[i])*(a[i] - b[i]);
 
  134    return (
TNAME)sqrt(acc);
 
 
  140    for (
int i = 0; i < len; i++)
 
  141        acc += (a[i] - b[i])*(a[i] - b[i]);
 
 
  148    for (
int i = 0; i < len; i++)
 
 
  156    for (
int i = 0; i < len; i++)
 
  158    return (
TNAME)sqrt(acc);
 
 
  164    for (
int i = 0; i < len; i++)
 
 
  171    for (
int i = 0; i < len; i++)
 
 
  177    for (
int i = 0; i < len; i++)
 
  178        v[i] = (
TNAME)(v[i] * scale);
 
 
  183    TNAME t2, t3, t4, t5, t6, t7, t8, t9, t10;
 
  195    r[0] = 2*((t8+t10)*v[0] + (t6-t4)*v[1]  + (t3+t7)*v[2]) + v[0];
 
  196    r[1] = 2*((t4+t6)*v[0]  + (t5+t10)*v[1] + (t9-t2)*v[2]) + v[1];
 
  197    r[2] = 2*((t7-t3)*v[0]  + (t2+t9)*v[1]  + (t5+t8)*v[2]) + v[2];
 
 
  202    r[0] = a[0]*b[0] - a[1]*b[1] - a[2]*b[2] - a[3]*b[3];
 
  203    r[1] = a[0]*b[1] + a[1]*b[0] + a[2]*b[3] - a[3]*b[2];
 
  204    r[2] = a[0]*b[2] - a[1]*b[3] + a[2]*b[0] + a[3]*b[1];
 
  205    r[3] = a[0]*b[3] + a[1]*b[2] - a[2]*b[1] + a[3]*b[0];
 
 
  219    memcpy(dst, src, n * 
sizeof(
TNAME));
 
 
  230    memset(r, 0, 
sizeof(
TNAME)*16);
 
 
  244    r[0] = c*xy[0] - s*xy[1] + xyt[0];
 
  245    r[1] = s*xy[0] + c*xy[1] + xyt[1];
 
 
  250    r[0] = M[0]*xyz[0] + M[1]*xyz[1] + M[2]*xyz[2]  + M[3];
 
  251    r[1] = M[4]*xyz[0] + M[5]*xyz[1] + M[6]*xyz[2]  + M[7];
 
  252    r[2] = M[8]*xyz[0] + M[9]*xyz[1] + M[10]*xyz[2] + M[11];
 
 
  278    q[0] = (
TNAME)cos(rad / 2.0);
 
  281    TNAME v[3] = { aa[1], aa[2], aa[3] };
 
 
  291    TNAME w = q[0], x = q[1], y = q[2], z = q[3];
 
  293    r[0] = w*w + x*x - y*y - z*z;
 
  294    r[1] = 2*x*y - 2*w*z;
 
  295    r[2] = 2*x*z + 2*w*y;
 
  298    r[4] = 2*x*y + 2*w*z;
 
  299    r[5] = w*w - x*x + y*y - z*z;
 
  300    r[6] = 2*y*z - 2*w*x;
 
  303    r[8] = 2*x*z - 2*w*y;
 
  304    r[9] = 2*y*z + 2*w*x;
 
  305    r[10] = w*w - x*x - y*y + z*z;
 
 
  354    TNAME roll = rpy[0], pitch = rpy[1], yaw = rpy[2];
 
  356    TNAME halfroll = roll / 2;
 
  357    TNAME halfpitch = pitch / 2;
 
  358    TNAME halfyaw = yaw / 2;
 
  368    quat[0] = cos_r2 * cos_p2 * cos_y2 + sin_r2 * sin_p2 * sin_y2;
 
  369    quat[1] = sin_r2 * cos_p2 * cos_y2 - cos_r2 * sin_p2 * sin_y2;
 
  370    quat[2] = cos_r2 * sin_p2 * cos_y2 + sin_r2 * cos_p2 * sin_y2;
 
  371    quat[3] = cos_r2 * cos_p2 * sin_y2 - sin_r2 * sin_p2 * cos_y2;
 
 
  378    const TNAME qr = q[0];
 
  379    const TNAME qx = q[1];
 
  380    const TNAME qy = q[2];
 
  381    const TNAME qz = q[3];
 
  383    TNAME disc = qr*qy - qx*qz;
 
  385    if (fabs(disc+0.5) < DBL_EPSILON) {         
 
  387        rpy[1] = (
TNAME)(-M_PI/2);
 
  388        rpy[2] = (
TNAME)(2 * atan2(qx, qr));
 
  390    else if (fabs(disc-0.5) < DBL_EPSILON) {    
 
  392        rpy[1] = (
TNAME)(M_PI/2);
 
  393        rpy[2] = (
TNAME)(-2 * atan2(qx, qr));
 
  397        TNAME roll_a = 2 * (qr*qx + qy*qz);
 
  398        TNAME roll_b = 1 - 2 * (qx*qx + qy*qy);
 
  399        rpy[0] = (
TNAME)atan2(roll_a, roll_b);
 
  402        rpy[1] = (
TNAME)asin(2*disc);
 
  405        TNAME yaw_a = 2 * (qr*qz + qx*qy);
 
  406        TNAME yaw_b = 1 - 2 * (qy*qy + qz*qz);
 
  407        rpy[2] = (
TNAME)atan2(yaw_a, yaw_b);
 
 
  429    for (
int i = 0; i < 3; i++)
 
  430        out[i] = M[4*i + 0]*in[0] + M[4*i + 1]*in[1] + M[4*i + 2]*in[2] + M[4*i + 3];
 
 
  436    for (
int i = 0; i < 3; i++)
 
  437        out[i] = M[4*i + 0]*in[0] + M[4*i + 1]*in[1] + M[4*i + 2]*in[2];
 
 
  446    xyt[2] = (
TNAME)atan2(M[4], M[0]);
 
 
  458    double T = M[0] + M[5] + M[10] + 1.0;
 
  464        q[1] = (
TNAME)((M[9] - M[6]) / 
S);
 
  465        q[2] = (
TNAME)((M[2] - M[8]) / 
S);
 
  466        q[3] = (
TNAME)((M[4] - M[1]) / 
S);
 
  467    } 
else if (M[0] > M[5] && M[0] > M[10]) {   
 
  468        S = sqrt(1.0 + M[0] - M[5] - M[10]) * 2;
 
  469        q[0] = (
TNAME)((M[9] - M[6]) / 
S);
 
  471        q[2] = (
TNAME)((M[4] + M[1]) / 
S);
 
  472        q[3] = (
TNAME)((M[2] + M[8]) / 
S);
 
  473    } 
else if (M[5] > M[10]) {                  
 
  474        S = sqrt(1.0 + M[5] - M[0] - M[10]) * 2;
 
  475        q[0] = (
TNAME)((M[2] - M[8]) / 
S);
 
  476        q[1] = (
TNAME)((M[4] + M[1]) / 
S);
 
  478        q[3] = (
TNAME)((M[9] + M[6]) / 
S);
 
  480        S = sqrt(1.0 + M[10] - M[0] - M[5]);
 
  481        q[0] = (
TNAME)((M[4] - M[1]) / 
S);
 
  482        q[1] = (
TNAME)((M[2] + M[8]) / 
S);
 
  483        q[2] = (
TNAME)((M[9] + M[6]) / 
S);
 
 
  500    TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
 
  503    xytr[0] = c*xytb[0] - s*xytb[1] + xa;
 
  504    xytr[1] = s*xytb[0] + c*xytb[1] + ya;
 
  505    xytr[2] = ta + xytb[2];
 
 
  511    memcpy(xytr, xyta, 3 * 
sizeof(
TNAME));
 
  512    memcpy(Cr, Ca, 9 * 
sizeof(
TNAME));
 
 
  519    TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
 
  520    TNAME xb = xytb[0], yb = xytb[1];
 
  524    TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
 
  525    TNAME              P22 = Ca[4], P23 = Ca[5];
 
  528    TNAME Q11 = Cb[0], Q12 = Cb[1], Q13 = Cb[2];
 
  529    TNAME              Q22 = Cb[4], Q23 = Cb[5];
 
  532    TNAME JA13 = -sa*xb - ca*yb;
 
  533    TNAME JA23 = ca*xb - sa*yb;
 
  539    Cr[0] = P33*JA13*JA13 + 2*P13*JA13 + Q11*JB11*JB11 + 2*Q12*JB11*JB12 + Q22*JB12*JB12 + P11;
 
  540    Cr[1] = P12 + JA23*(P13 + JA13*P33) + JA13*P23 + JB21*(JB11*Q11 + JB12*Q12) + JB22*(JB11*Q12 + JB12*Q22);
 
  541    Cr[2] = P13 + JA13*P33 + JB11*Q13 + JB12*Q23;
 
  543    Cr[4] = P33*JA23*JA23 + 2*P23*JA23 + Q11*JB21*JB21 + 2*Q12*JB21*JB22 + Q22*JB22*JB22 + P22;
 
  544    Cr[5] = P23 + JA23*P33 + JB21*Q13 + JB22*Q23;
 
  549    xytr[0] = ca*xb - sa*yb + xa;
 
  550    xytr[1] = sa*xb + ca*yb + ya;
 
  551    xytr[2] = xyta[2] + xytb[2];
 
 
  572    xytr[0] = -s*xyta[1] - c*xyta[0];
 
  573    xytr[1] = -c*xyta[1] + s*xyta[0];
 
 
  580    TNAME x = xyta[0], y = xyta[1], theta = xyta[2];
 
  583    TNAME J11 = -c, J12 = -s, J13 = -c*y + s*x;
 
  584    TNAME J21 = s,  J22 = -c, J23 = s*y + c*x;
 
  586    TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
 
  587    TNAME              P22 = Ca[4], P23 = Ca[5];
 
  590    Cr[0] = P11*J11*J11 + 2*P12*J11*J12 + 2*P13*J11*J13 +
 
  591        P22*J12*J12 + 2*P23*J12*J13 + P33*J13*J13;
 
  592    Cr[1] = J21*(J11*P11 + J12*P12 + J13*P13) +
 
  593        J22*(J11*P12 + J12*P22 + J13*P23) +
 
  594        J23*(J11*P13 + J12*P23 + J13*P33);
 
  595    Cr[2] = - J11*P13 - J12*P23 - J13*P33;
 
  597    Cr[4] = P11*J21*J21 + 2*P12*J21*J22 + 2*P13*J21*J23 +
 
  598        P22*J22*J22 + 2*P23*J22*J23 + P33*J23*J23;
 
  599    Cr[5] = - J21*P13 - J22*P23 - J23*P33;
 
  613    xytr[0] = -s*y - c*x;
 
  614    xytr[1] = -c*y + s*x;
 
 
  621    TNAME theta = xyta[2];
 
  624    TNAME dx = xytb[0] - xyta[0];
 
  625    TNAME dy = xytb[1] - xyta[1];
 
  627    xytr[0] = ca*dx + sa*dy;
 
  628    xytr[1] = -sa*dx + ca*dy;
 
  629    xytr[2]= xytb[2] - xyta[2];
 
 
  633                                   const TNAME *B, 
int Brows, 
int Bcols,
 
  634                                   TNAME *R, 
int Rrows, 
int Rcols)
 
  636    assert(Arows == Brows);
 
  637    assert(Arows == Rrows);
 
  638    assert(Bcols == Bcols);
 
  639    assert(Bcols == Rcols);
 
  641    for (
int i = 0; i < Arows; i++)
 
  642        for (
int j = 0; j < Bcols; j++)
 
  643            R[i*Acols + j] = A[i*Acols + j] + B[i*Acols + j];
 
 
  649                                  const TNAME *B, 
int Brows, 
int Bcols,
 
  650                                  TNAME *R, 
int Rrows, 
int Rcols)
 
  652    assert(Acols == Brows);
 
  653    assert(Rrows == Arows);
 
  654    assert(Bcols == Rcols);
 
  656    for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
 
  657        for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
 
  659            for (
int i = 0; i < Acols; i++)
 
  660                acc += A[Rrow*Acols + i] * B[i*Bcols + Rcol];
 
  661            R[Rrow*Rcols + Rcol] = acc;
 
 
  669                                  const TNAME *B, 
int Brows, 
int Bcols,
 
  670                                  TNAME *R, 
int Rrows, 
int Rcols)
 
  672    assert(Acols == Bcols);
 
  673    assert(Rrows == Arows);
 
  674    assert(Brows == Rcols);
 
  676    for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
 
  677        for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
 
  679            for (
int i = 0; i < Acols; i++)
 
  680                acc += A[Rrow*Acols + i] * B[Rcol*Bcols + i];
 
  681            R[Rrow*Rcols + Rcol] = acc;
 
 
  687                                  const TNAME *B, 
int Brows, 
int Bcols,
 
  688                                  const TNAME *C, 
int Crows, 
int Ccols,
 
  689                                  TNAME *R, 
int Rrows, 
int Rcols)
 
  691    TNAME *tmp = malloc(
sizeof(
TNAME)*Arows*Bcols);
 
  693    TFN(
s_mat_AB)(A, Arows, Acols, B, Brows, Bcols, tmp, Arows, Bcols);
 
  694    TFN(
s_mat_AB)(tmp, Arows, Bcols, C, Crows, Ccols, R, Rrows, Rcols);
 
 
  699                                  const TNAME *B, 
int Blength,
 
  700                                  TNAME *R, 
int Rlength)
 
  702    assert(Acols == Blength);
 
  703    assert(Arows == Rlength);
 
  705    for (
int Ridx = 0; Ridx < Rlength; Ridx++) {
 
  707        for (
int i = 0; i < Blength; i++)
 
  708            acc += A[Ridx*Acols + i] * B[i];
 
 
  714                                   const TNAME *B, 
int Brows, 
int Bcols,
 
  715                                   TNAME *R, 
int Rrows, 
int Rcols)
 
  717    assert(Arows == Brows);
 
  718    assert(Rrows == Acols);
 
  719    assert(Bcols == Rcols);
 
  721    for (
int Rrow = 0; Rrow < Rrows; Rrow++) {
 
  722        for (
int Rcol = 0; Rcol < Rcols; Rcol++) {
 
  724            for (
int i = 0; i < Acols; i++)
 
  725                acc += A[i*Acols + Rrow] * B[i*Bcols + Rcol];
 
  726            R[Rrow*Rcols + Rcol] = acc;
 
 
  736    memcpy(q1, _q1, 
sizeof(
TNAME) * 4);
 
  743        for (
int i = 0; i < 4; i++)
 
  751        for (
int i = 0; i < 4; i++)
 
  752            r[i] = q0[i]*(1-w) + q1[i]*w;
 
  759        for (
int i = 0; i < 4; i++)
 
  760            r[i] = q0[i]*w0 + q1[i]*w1;
 
 
  768    r[0] = v1[1]*v2[2] - v1[2]*v2[1];
 
  769    r[1] = v1[2]*v2[0] - v1[0]*v2[2];
 
  770    r[2] = v1[0]*v2[1] - v1[1]*v2[0];
 
 
  776    memset(out, 0, 16 * 
sizeof(
TNAME));
 
 
  787    for (
int i = 0; i < 3; i++)
 
  788        out[4*i + 3] += txyz[i];
 
 
  795    for (
int i = 0; i < 3; i++)
 
  796        out[4*i + i] = sxyz[i];
 
 
  832    TNAME tmp[16], prod[16];
 
  835    memcpy(out, prod, 
sizeof(
TNAME)*16);
 
 
  840    TNAME tmp[16], prod[16];
 
  843    memcpy(out, prod, 
sizeof(
TNAME)*16);
 
 
  848    TNAME tmp[16], prod[16];
 
  851    memcpy(out, prod, 
sizeof(
TNAME)*16);
 
 
  860    for (
int i = 0; i < 3; i++)
 
  861        for (
int j = 0; j < 3; j++)
 
  862            out[4*i + j] = M[4*j + i];
 
  868    for (
int i = 0; i < 3; i++)
 
  869        for (
int j = 0; j < 3; j++)
 
  870            out[4*i + 3] -= out[4*i + j] * M[4*j + 3];
 
 
  914    for (
int i = 0; i < 3; i++)
 
  915        up[i] -= up_dot*f[i];
 
  923    TNAME R[16] = {  s[0],  s[1],  s[2], 0,
 
  925                    -f[0], -f[1], -f[2], 0,
 
  928    TNAME T[16] = {1, 0, 0,  -eye[0],
 
 
  942                                     TNAME *R, 
int Brows, 
int Bcols)
 
  944    assert(Arows == Brows);
 
  945    assert(Bcols == Bcols);
 
  948    R[0] = (
TNAME)sqrt(A[0]);
 
  957    R[4] = (
TNAME)sqrt(A[4] - R[3]*R[3]);
 
  960    R[7] = (A[5] - R[3]*R[6]) / R[4];
 
  963    R[8] = (
TNAME)sqrt(A[8] - R[6]*R[6] - R[7]*R[7]);
 
 
  971                                              TNAME *R, 
int Rrows, 
int Rcols)
 
  977    R[3] = -A[3]*R[0] / A[4];
 
  983    R[6] = (-A[6]*R[0] - A[7]*R[3]) / A[8];
 
  986    R[7] = -A[7]*R[4] / A[8];
 
 
  994                                          const TNAME *B, 
int Brows, 
int Bcols,
 
  995                                          TNAME *R, 
int Rrows, 
int Rcols)
 
  997    assert(Arows == Acols);
 
 1012    tmp[1] = M[3]*B[0] + M[4]*B[1];
 
 1013    tmp[2] = M[6]*B[0] + M[7]*B[1] + M[8]*B[2];
 
 1015    R[0] = (
TNAME)(M[0]*tmp[0] + M[3]*tmp[1] + M[6]*tmp[2]);
 
 1016    R[1] = (
TNAME)(M[4]*tmp[1] + M[7]*tmp[2]);
 
 1017    R[2] = (
TNAME)(M[8]*tmp[2]);
 
 
and restrictions which apply to each piece of software is included later in this file and or inside of the individual applicable source files The disclaimer of warranty in the WPILib license above applies to all code in and nothing in any of the other licenses gives permission to use the names of FIRST nor the names of the WPILib contributors to endorse or promote products derived from this software The following pieces of software have additional or alternate and or and nanopb were all modified for use in Google Inc All rights reserved Redistribution and use in source and binary with or without are permitted provided that the following conditions are this list of conditions and the following disclaimer *Redistributions in binary form must reproduce the above copyright this list of conditions and the following disclaimer in the documentation and or other materials provided with the distribution *Neither the name of Google Inc nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS AND ANY EXPRESS OR IMPLIED BUT NOT LIMITED THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY OR CONSEQUENTIAL WHETHER IN STRICT OR EVEN IF ADVISED OF THE POSSIBILITY OF SUCH January AND DISTRIBUTION Definitions License shall mean the terms and conditions for and distribution as defined by Sections through of this document Licensor shall mean the copyright owner or entity authorized by the copyright owner that is granting the License Legal Entity shall mean the union of the acting entity and all other entities that control are controlled by or are under common control with that entity For the purposes of this definition control direct or to cause the direction or management of such whether by contract or including but not limited to software source documentation and configuration files Object form shall mean any form resulting from mechanical transformation or translation of a Source including but not limited to compiled object generated and conversions to other media types Work shall mean the work of whether in Source or Object made available under the as indicated by a copyright notice that is included in or attached to the whether in Source or Object that is based or other modifications as a an original work of authorship For the purposes of this Derivative Works shall not include works that remain separable or merely the Work and Derivative Works thereof Contribution shall mean any work of including the original version of the Work and any modifications or additions to that Work or Derivative Works that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner For the purposes of this submitted means any form of or written communication sent to the Licensor or its including but not limited to communication on electronic mailing source code control and issue tracking systems that are managed or on behalf the Licensor for the purpose of discussing and improving the but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as Not a Contribution Contributor shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work Grant of Copyright License Subject to the terms and conditions of this each Contributor hereby grants to You a non no royalty free
Definition ThirdPartyNotices.txt:164
#define TNAME
Definition doubles.h:30
static void TFN s_mat_Ab(const TNAME *A, int Arows, int Acols, const TNAME *B, int Blength, TNAME *R, int Rlength)
Definition doubles_floats_impl.h:698
static void TFN s_mat44_scale_self(const TNAME sxyz[3], TNAME out[16])
Definition doubles_floats_impl.h:838
static void TFN s_cross_product(const TNAME v1[3], const TNAME v2[3], TNAME r[3])
Definition doubles_floats_impl.h:766
static void TFN s_copy(const TNAME *src, TNAME *dst, int n)
Definition doubles_floats_impl.h:217
static void TFN s_print_mat(const TNAME *a, int nrows, int ncols, const char *fmt)
Definition doubles_floats_impl.h:85
static void TFN s_rpy_to_mat44(const TNAME rpy[3], TNAME M[16])
Definition doubles_floats_impl.h:411
static void TFN s_elu_to_mat44(const TNAME eye[3], const TNAME lookat[3], const TNAME _up[3], TNAME M[16])
Definition doubles_floats_impl.h:901
static void TFN s_mat44_translate(const TNAME txyz[3], TNAME out[16])
Definition doubles_floats_impl.h:783
static void TFN s_mat44_inv_rotate_vector(const TNAME M[16], const TNAME in[3], TNAME out[3])
Definition doubles_floats_impl.h:893
static void TFN s_mat44_rotate_z_self(TNAME rad, TNAME out[16])
Definition doubles_floats_impl.h:846
static void TFN s_angleaxis_to_mat44(const TNAME aa[4], TNAME r[16])
Definition doubles_floats_impl.h:333
static void TFN s_mat_transform_xyz(const TNAME M[16], const TNAME xyz[3], TNAME r[3])
Definition doubles_floats_impl.h:248
static void TFN s_xyt_copy(const TNAME xyt[3], TNAME r[3])
Definition doubles_floats_impl.h:222
static TNAME TFN s_distance(const TNAME *a, const TNAME *b, int len)
Definition doubles_floats_impl.h:129
static void TFN s_mat44_transform_xyz(const TNAME M[16], const TNAME in[3], TNAME out[3])
Definition doubles_floats_impl.h:427
static void TFN s_xyt_to_mat44(const TNAME xyt[3], TNAME r[16])
Definition doubles_floats_impl.h:227
static void TFN s_subtract(const TNAME *a, const TNAME *b, int len, TNAME *r)
Definition doubles_floats_impl.h:109
static void TFN s_print_mat44(const TNAME *a, const char *fmt)
Definition doubles_floats_impl.h:94
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)
Definition doubles_floats_impl.h:713
static void TFN s_scale_self(TNAME *v, int len, double scale)
Definition doubles_floats_impl.h:175
static void TFN s_rpy_to_quat(const TNAME rpy[3], TNAME quat[4])
Definition doubles_floats_impl.h:352
static void TFN s_cross_matrix(const TNAME v[3], TNAME V[9])
Definition doubles_floats_impl.h:320
static void TFN s_xytcov_copy(const TNAME xyta[3], const TNAME Ca[9], TNAME xytr[3], TNAME Cr[9])
Definition doubles_floats_impl.h:508
static void TFN s_mat44_scale(const TNAME sxyz[3], TNAME out[16])
Definition doubles_floats_impl.h:791
static void TFN s_mat44_inv_transform_xyz(const TNAME M[16], const TNAME in[3], TNAME out[3])
Definition doubles_floats_impl.h:884
static TNAME TFN s_magnitude(const TNAME *v, int len)
Definition doubles_floats_impl.h:153
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])
Definition doubles_floats_impl.h:515
static void TFN s_xyt_inv(const TNAME xyta[3], TNAME xytr[3])
Definition doubles_floats_impl.h:569
static void TFN s_mat44_rotate_x(TNAME rad, TNAME out[16])
Definition doubles_floats_impl.h:819
static void TFN s_mat44_rotate_y(TNAME rad, TNAME out[16])
Definition doubles_floats_impl.h:809
static void TFN s_quat_xyz_to_xyt(const TNAME q[4], const TNAME xyz[3], TNAME xyt[3])
Definition doubles_floats_impl.h:490
static TNAME TFN s_squared_magnitude(const TNAME *v, int len)
Definition doubles_floats_impl.h:145
static void TFN s_mat_to_xyz(const TNAME M[16], TNAME xyz[3])
Definition doubles_floats_impl.h:449
static void TFN s_xyt_mul(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
Definition doubles_floats_impl.h:498
static void TFN s_normalize(const TNAME *v, int len, TNAME *r)
Definition doubles_floats_impl.h:161
static void TFN s_mat44_rotate_z(TNAME rad, TNAME out[16])
Definition doubles_floats_impl.h:799
static void TFN s_mat33_chol(const TNAME *A, int Arows, int Acols, TNAME *R, int Brows, int Bcols)
Definition doubles_floats_impl.h:941
static void TFN s_add(const TNAME *a, const TNAME *b, int len, TNAME *r)
Definition doubles_floats_impl.h:103
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)
Definition doubles_floats_impl.h:686
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)
Definition doubles_floats_impl.h:668
static void TFN s_mat44_translate_self(const TNAME txyz[3], TNAME out[16])
Definition doubles_floats_impl.h:830
static void TFN s_quat_inverse(const TNAME q[4], TNAME r[4])
Definition doubles_floats_impl.h:208
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)
Definition doubles_floats_impl.h:993
static void TFN s_quat_to_rpy(const TNAME q[4], TNAME rpy[3])
Definition doubles_floats_impl.h:376
static void TFN s_normalize_self(TNAME *v, int len)
Definition doubles_floats_impl.h:168
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)
Definition doubles_floats_impl.h:648
static void TFN s_mat44_rotate_vector(const TNAME M[16], const TNAME in[3], TNAME out[3])
Definition doubles_floats_impl.h:434
static void TFN s_scale(TNAME s, const TNAME *v, int len, TNAME *r)
Definition doubles_floats_impl.h:115
static TNAME *TFN s_dup(const TNAME *v, int len)
Definition doubles_floats_impl.h:68
#define TFN(suffix)
Definition doubles_floats_impl.h:65
static void TFN s_mat44_to_xyt(const TNAME M[16], TNAME xyt[3])
Definition doubles_floats_impl.h:440
static void TFN s_quat_multiply(const TNAME a[4], const TNAME b[4], TNAME r[4])
Definition doubles_floats_impl.h:200
static void TFN s_mat_to_quat(const TNAME M[16], TNAME q[4])
Definition doubles_floats_impl.h:456
static void TFN s_mat33_lower_tri_inv(const TNAME *A, int Arows, int Acols, TNAME *R, int Rrows, int Rcols)
Definition doubles_floats_impl.h:970
static TNAME TFN s_squared_distance(const TNAME *a, const TNAME *b, int len)
Definition doubles_floats_impl.h:137
static void TFN s_xyt_transform_xy(const TNAME xyt[3], const TNAME xy[2], TNAME r[2])
Definition doubles_floats_impl.h:241
static void TFN s_quat_to_mat44(const TNAME q[4], TNAME r[16])
Definition doubles_floats_impl.h:289
static void TFN s_xyzrpy_to_mat44(const TNAME xyzrpy[6], TNAME M[16])
Definition doubles_floats_impl.h:419
static void TFN s_quat_slerp(const TNAME q0[4], const TNAME _q1[4], TNAME r[4], TNAME w)
Definition doubles_floats_impl.h:731
static void TFN s_quat_xyz_to_mat44(const TNAME q[4], const TNAME xyz[3], TNAME r[16])
Definition doubles_floats_impl.h:341
static TNAME TFN s_dot(const TNAME *a, const TNAME *b, int len)
Definition doubles_floats_impl.h:121
static void TFN s_xyt_inv_mul(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
Definition doubles_floats_impl.h:619
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)
Definition doubles_floats_impl.h:632
static void TFN s_mat44_identity(TNAME out[16])
Definition doubles_floats_impl.h:774
static void TFN s_mat44_inv(const TNAME M[16], TNAME out[16])
Definition doubles_floats_impl.h:855
static void TFN s_angleaxis_to_quat(const TNAME aa[4], TNAME q[4])
Definition doubles_floats_impl.h:275
static void TFN s_quat_rotate(const TNAME q[4], const TNAME v[3], TNAME r[3])
Definition doubles_floats_impl.h:181
static void TFN s_print(const TNAME *a, int len, const char *fmt)
Definition doubles_floats_impl.h:78
static void TFN s_xytcov_inv(const TNAME xyta[3], const TNAME Ca[9], TNAME xytr[3], TNAME Cr[9])
Definition doubles_floats_impl.h:577
static void TFN s_quat_to_angleaxis(const TNAME _q[4], TNAME r[4])
Definition doubles_floats_impl.h:255
static double mod2pi(double vin)
Map vin to [-PI, PI)
Definition math_util.h:106
auto printf(string_view fmt, const T &... args) -> int
Formats args according to specifications in fmt and writes the output to stdout.
Definition printf.h:621
#define S(label, offset, message)
Definition Errors.h:113