WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
doubles_floats_impl.h
Go to the documentation of this file.
1/* Copyright (C) 2013-2016, The Regents of The University of Michigan.
2All rights reserved.
3This software was developed in the APRIL Robotics Lab under the
4direction of Edwin Olson, ebolson@umich.edu. This software may be
5available under alternative licensing terms; contact the address above.
6Redistribution and use in source and binary forms, with or without
7modification, are permitted provided that the following conditions are met:
81. Redistributions of source code must retain the above copyright notice, this
9 list of conditions and the following disclaimer.
102. Redistributions in binary form must reproduce the above copyright notice,
11 this list of conditions and the following disclaimer in the documentation
12 and/or other materials provided with the distribution.
13THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
14ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
15WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
16DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
17ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
18(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
19LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
20ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
21(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
22SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23The views and conclusions contained in the software and documentation are those
24of the authors and should not be interpreted as representing official policies,
25either expressed or implied, of the Regents of The University of Michigan.
26*/
27
28#include <stdio.h>
29#include <math.h>
30#include <string.h>
31#include <float.h>
32
33#include "matd.h"
34#include "math_util.h"
35
36// XXX Write unit tests for me!
37// XXX Rewrite matd_coords in terms of this.
38
39/*
40 This file provides conversions between the following formats:
41
42 quaternion (TNAME[4], { w, x, y, z})
43
44 xyt (translation in x, y, and rotation in radians.)
45
46 xytcov (xyt as a TNAME[3] followed by covariance TNAME[9])
47
48 xy, xyz (translation in x, y, and z)
49
50 mat44 (4x4 rigid-body transformation matrix, row-major
51 order. Conventions: We assume points are projected via right
52 multiplication. E.g., p' = Mp.) Note: some functions really do rely
53 on it being a RIGID, scale=1 transform.
54
55 angleaxis (TNAME[4], { angle-rads, x, y, z }
56
57 xyzrpy (translation x, y, z, euler angles)
58
59 Roll Pitch Yaw are evaluated in the order: roll, pitch, then yaw. I.e.,
60 rollPitchYawToMatrix(rpy) = rotateZ(rpy[2]) * rotateY(rpy[1]) * Rotatex(rpy[0])
61*/
62
63#define TRRFN(root, suffix) root ## suffix
64#define TRFN(root, suffix) TRRFN(root, suffix)
65#define TFN(suffix) TRFN(TNAME, suffix)
66
67// if V is null, returns null.
68static inline TNAME *TFN(s_dup)(const TNAME *v, int len)
69{
70 if (!v)
71 return NULL;
72
73 TNAME *r = (TNAME*)malloc(len * sizeof(TNAME));
74 memcpy(r, v, len * sizeof(TNAME));
75 return r;
76}
77
78static inline void TFN(s_print)(const TNAME *a, int len, const char *fmt)
79{
80 for (int i = 0; i < len; i++)
81 printf(fmt, a[i]);
82 printf("\n");
83}
84
85static inline void TFN(s_print_mat)(const TNAME *a, int nrows, int ncols, const char *fmt)
86{
87 for (int i = 0; i < nrows * ncols; i++) {
88 printf(fmt, a[i]);
89 if ((i % ncols) == (ncols - 1))
90 printf("\n");
91 }
92}
93
94static inline void TFN(s_print_mat44)(const TNAME *a, const char *fmt)
95{
96 for (int i = 0; i < 4 * 4; i++) {
97 printf(fmt, a[i]);
98 if ((i % 4) == 3)
99 printf("\n");
100 }
101}
102
103static inline void TFN(s_add)(const TNAME *a, const TNAME *b, int len, TNAME *r)
104{
105 for (int i = 0; i < len; i++)
106 r[i] = a[i] + b[i];
107}
108
109static inline void TFN(s_subtract)(const TNAME *a, const TNAME *b, int len, TNAME *r)
110{
111 for (int i = 0; i < len; i++)
112 r[i] = a[i] - b[i];
113}
114
115static inline void TFN(s_scale)(TNAME s, const TNAME *v, int len, TNAME *r)
116{
117 for (int i = 0; i < len; i++)
118 r[i] = s * v[i];
119}
120
121static inline TNAME TFN(s_dot)(const TNAME *a, const TNAME *b, int len)
122{
123 TNAME acc = 0;
124 for (int i = 0; i < len; i++)
125 acc += a[i] * b[i];
126 return acc;
127}
128
129static inline TNAME TFN(s_distance)(const TNAME *a, const TNAME *b, int len)
130{
131 TNAME acc = 0;
132 for (int i = 0; i < len; i++)
133 acc += (a[i] - b[i])*(a[i] - b[i]);
134 return (TNAME)sqrt(acc);
135}
136
137static inline TNAME TFN(s_squared_distance)(const TNAME *a, const TNAME *b, int len)
138{
139 TNAME acc = 0;
140 for (int i = 0; i < len; i++)
141 acc += (a[i] - b[i])*(a[i] - b[i]);
142 return acc;
143}
144
145static inline TNAME TFN(s_squared_magnitude)(const TNAME *v, int len)
146{
147 TNAME acc = 0;
148 for (int i = 0; i < len; i++)
149 acc += v[i]*v[i];
150 return acc;
151}
152
153static inline TNAME TFN(s_magnitude)(const TNAME *v, int len)
154{
155 TNAME acc = 0;
156 for (int i = 0; i < len; i++)
157 acc += v[i]*v[i];
158 return (TNAME)sqrt(acc);
159}
160
161static inline void TFN(s_normalize)(const TNAME *v, int len, TNAME *r)
162{
163 TNAME mag = TFN(s_magnitude)(v, len);
164 for (int i = 0; i < len; i++)
165 r[i] = v[i] / mag;
166}
167
168static inline void TFN(s_normalize_self)(TNAME *v, int len)
169{
170 TNAME mag = TFN(s_magnitude)(v, len);
171 for (int i = 0; i < len; i++)
172 v[i] /= mag;
173}
174
175static inline void TFN(s_scale_self)(TNAME *v, int len, double scale)
176{
177 for (int i = 0; i < len; i++)
178 v[i] = (TNAME)(v[i] * scale);
179}
180
181static inline void TFN(s_quat_rotate)(const TNAME q[4], const TNAME v[3], TNAME r[3])
182{
183 TNAME t2, t3, t4, t5, t6, t7, t8, t9, t10;
184
185 t2 = q[0]*q[1];
186 t3 = q[0]*q[2];
187 t4 = q[0]*q[3];
188 t5 = -q[1]*q[1];
189 t6 = q[1]*q[2];
190 t7 = q[1]*q[3];
191 t8 = -q[2]*q[2];
192 t9 = q[2]*q[3];
193 t10 = -q[3]*q[3];
194
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];
198}
199
200static inline void TFN(s_quat_multiply)(const TNAME a[4], const TNAME b[4], TNAME r[4])
201{
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];
206}
207
208static inline void TFN(s_quat_inverse)(const TNAME q[4], TNAME r[4])
209{
210 TNAME mag = TFN(s_magnitude)(q, 4);
211 r[0] = q[0]/mag;
212 r[1] = -q[1]/mag;
213 r[2] = -q[2]/mag;
214 r[3] = -q[3]/mag;
215}
216
217static inline void TFN(s_copy)(const TNAME *src, TNAME *dst, int n)
218{
219 memcpy(dst, src, n * sizeof(TNAME));
220}
221
222static inline void TFN(s_xyt_copy)(const TNAME xyt[3], TNAME r[3])
223{
224 TFN(s_copy)(xyt, r, 3);
225}
226
227static inline void TFN(s_xyt_to_mat44)(const TNAME xyt[3], TNAME r[16])
228{
229 TNAME s = (TNAME)sin(xyt[2]), c = (TNAME)cos(xyt[2]);
230 memset(r, 0, sizeof(TNAME)*16);
231 r[0] = c;
232 r[1] = -s;
233 r[3] = xyt[0];
234 r[4] = s;
235 r[5] = c;
236 r[7] = xyt[1];
237 r[10] = 1;
238 r[15] = 1;
239}
240
241static inline void TFN(s_xyt_transform_xy)(const TNAME xyt[3], const TNAME xy[2], TNAME r[2])
242{
243 TNAME s = (TNAME)sin(xyt[2]), c = (TNAME)cos(xyt[2]);
244 r[0] = c*xy[0] - s*xy[1] + xyt[0];
245 r[1] = s*xy[0] + c*xy[1] + xyt[1];
246}
247
248static inline void TFN(s_mat_transform_xyz)(const TNAME M[16], const TNAME xyz[3], TNAME r[3])
249{
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];
253}
254
255static inline void TFN(s_quat_to_angleaxis)(const TNAME _q[4], TNAME r[4])
256{
257 TNAME q[4];
258 TFN(s_normalize)(_q, 4, q);
259
260 // be polite: return an angle from [-pi, pi]
261 // use atan2 to be 4-quadrant safe
262 TNAME mag = TFN(s_magnitude)(&q[1], 3);
263 r[0] = (TNAME)mod2pi(2 * atan2(mag, q[0]));
264 if (mag != 0) {
265 r[1] = q[1] / mag;
266 r[2] = q[2] / mag;
267 r[3] = q[3] / mag;
268 } else {
269 r[1] = 1;
270 r[2] = 0;
271 r[3] = 0;
272 }
273}
274
275static inline void TFN(s_angleaxis_to_quat)(const TNAME aa[4], TNAME q[4])
276{
277 TNAME rad = aa[0];
278 q[0] = (TNAME)cos(rad / 2.0);
279 TNAME s = (TNAME)sin(rad / 2.0);
280
281 TNAME v[3] = { aa[1], aa[2], aa[3] };
282 TFN(s_normalize)(v, 3, v);
283
284 q[1] = s * v[0];
285 q[2] = s * v[1];
286 q[3] = s * v[2];
287}
288
289static inline void TFN(s_quat_to_mat44)(const TNAME q[4], TNAME r[16])
290{
291 TNAME w = q[0], x = q[1], y = q[2], z = q[3];
292
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;
296 r[3] = 0;
297
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;
301 r[7] = 0;
302
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;
306 r[11] = 0;
307
308 r[12] = 0;
309 r[13] = 0;
310 r[14] = 0;
311 r[15] = 1;
312}
313
314/* Returns the skew-symmetric matrix V such that V*w = v x w (cross product).
315 Sometimes denoted [v]_x or \hat{v}.
316 [ 0 -v3 v2
317 v3 0 -v1
318 -v2 v1 0]
319 */
320static inline void TFN(s_cross_matrix)(const TNAME v[3], TNAME V[9])
321{
322 V[0] = 0;
323 V[1] = -v[2];
324 V[2] = v[1];
325 V[3] = v[2];
326 V[4] = 0;
327 V[5] = -v[0];
328 V[6] = -v[1];
329 V[7] = v[0];
330 V[8] = 0;
331}
332
333static inline void TFN(s_angleaxis_to_mat44)(const TNAME aa[4], TNAME r[16])
334{
335 TNAME q[4];
336
337 TFN(s_angleaxis_to_quat)(aa, q);
338 TFN(s_quat_to_mat44)(q, r);
339}
340
341static inline void TFN(s_quat_xyz_to_mat44)(const TNAME q[4], const TNAME xyz[3], TNAME r[16])
342{
343 TFN(s_quat_to_mat44)(q, r);
344
345 if (xyz != NULL) {
346 r[3] = xyz[0];
347 r[7] = xyz[1];
348 r[11] = xyz[2];
349 }
350}
351
352static inline void TFN(s_rpy_to_quat)(const TNAME rpy[3], TNAME quat[4])
353{
354 TNAME roll = rpy[0], pitch = rpy[1], yaw = rpy[2];
355
356 TNAME halfroll = roll / 2;
357 TNAME halfpitch = pitch / 2;
358 TNAME halfyaw = yaw / 2;
359
360 TNAME sin_r2 = (TNAME)sin(halfroll);
361 TNAME sin_p2 = (TNAME)sin(halfpitch);
362 TNAME sin_y2 = (TNAME)sin(halfyaw);
363
364 TNAME cos_r2 = (TNAME)cos(halfroll);
365 TNAME cos_p2 = (TNAME)cos(halfpitch);
366 TNAME cos_y2 = (TNAME)cos(halfyaw);
367
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;
372}
373
374// Reference: "A tutorial on SE(3) transformation parameterizations and
375// on-manifold optimization" by Jose-Luis Blanco
376static inline void TFN(s_quat_to_rpy)(const TNAME q[4], TNAME rpy[3])
377{
378 const TNAME qr = q[0];
379 const TNAME qx = q[1];
380 const TNAME qy = q[2];
381 const TNAME qz = q[3];
382
383 TNAME disc = qr*qy - qx*qz;
384
385 if (fabs(disc+0.5) < DBL_EPSILON) { // near -1/2
386 rpy[0] = 0;
387 rpy[1] = (TNAME)(-M_PI/2);
388 rpy[2] = (TNAME)(2 * atan2(qx, qr));
389 }
390 else if (fabs(disc-0.5) < DBL_EPSILON) { // near 1/2
391 rpy[0] = 0;
392 rpy[1] = (TNAME)(M_PI/2);
393 rpy[2] = (TNAME)(-2 * atan2(qx, qr));
394 }
395 else {
396 // roll
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);
400
401 // pitch
402 rpy[1] = (TNAME)asin(2*disc);
403
404 // yaw
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);
408 }
409}
410
411static inline void TFN(s_rpy_to_mat44)(const TNAME rpy[3], TNAME M[16])
412{
413 TNAME q[4];
414 TFN(s_rpy_to_quat)(rpy, q);
415 TFN(s_quat_to_mat44)(q, M);
416}
417
418
419static inline void TFN(s_xyzrpy_to_mat44)(const TNAME xyzrpy[6], TNAME M[16])
420{
421 TFN(s_rpy_to_mat44)(&xyzrpy[3], M);
422 M[3] = xyzrpy[0];
423 M[7] = xyzrpy[1];
424 M[11] = xyzrpy[2];
425}
426
427static inline void TFN(s_mat44_transform_xyz)(const TNAME M[16], const TNAME in[3], TNAME out[3])
428{
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];
431}
432
433// out = (upper 3x3 of M) * in
434static inline void TFN(s_mat44_rotate_vector)(const TNAME M[16], const TNAME in[3], TNAME out[3])
435{
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];
438}
439
440static inline void TFN(s_mat44_to_xyt)(const TNAME M[16], TNAME xyt[3])
441{
442 // c -s
443 // s c
444 xyt[0] = M[3];
445 xyt[1] = M[7];
446 xyt[2] = (TNAME)atan2(M[4], M[0]);
447}
448
449static inline void TFN(s_mat_to_xyz)(const TNAME M[16], TNAME xyz[3])
450{
451 xyz[0] = M[3];
452 xyz[1] = M[7];
453 xyz[2] = M[11];
454}
455
456static inline void TFN(s_mat_to_quat)(const TNAME M[16], TNAME q[4])
457{
458 double T = M[0] + M[5] + M[10] + 1.0;
459 double S;
460
461 if (T > 0.0000001) {
462 S = sqrt(T) * 2;
463 q[0] = (TNAME)(0.25 * S);
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]) { // Column 0:
468 S = sqrt(1.0 + M[0] - M[5] - M[10]) * 2;
469 q[0] = (TNAME)((M[9] - M[6]) / S);
470 q[1] = (TNAME)(0.25 * 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]) { // Column 1:
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);
477 q[2] = (TNAME)(0.25 * S);
478 q[3] = (TNAME)((M[9] + M[6]) / S);
479 } else { // Column 2:
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);
484 q[3] = (TNAME)(0.25 * S);
485 }
486
487 TFN(s_normalize)(q, 4, q);
488}
489
490static inline void TFN(s_quat_xyz_to_xyt)(const TNAME q[4], const TNAME xyz[3], TNAME xyt[3])
491{
492 TNAME M[16];
493 TFN(s_quat_xyz_to_mat44)(q, xyz, M);
494 TFN(s_mat44_to_xyt)(M, xyt);
495}
496
497// xytr = xyta * xytb;
498static inline void TFN(s_xyt_mul)(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
499{
500 TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
501 TNAME s = (TNAME)sin(ta), c = (TNAME)cos(ta);
502
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];
506}
507
508static inline void TFN(s_xytcov_copy)(const TNAME xyta[3], const TNAME Ca[9],
509 TNAME xytr[3], TNAME Cr[9])
510{
511 memcpy(xytr, xyta, 3 * sizeof(TNAME));
512 memcpy(Cr, Ca, 9 * sizeof(TNAME));
513}
514
515static inline void TFN(s_xytcov_mul)(const TNAME xyta[3], const TNAME Ca[9],
516 const TNAME xytb[3], const TNAME Cb[9],
517 TNAME xytr[3], TNAME Cr[9])
518{
519 TNAME xa = xyta[0], ya = xyta[1], ta = xyta[2];
520 TNAME xb = xytb[0], yb = xytb[1];
521
522 TNAME sa = (TNAME)sin(ta), ca = (TNAME)cos(ta);
523
524 TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
525 TNAME P22 = Ca[4], P23 = Ca[5];
526 TNAME P33 = Ca[8];
527
528 TNAME Q11 = Cb[0], Q12 = Cb[1], Q13 = Cb[2];
529 TNAME Q22 = Cb[4], Q23 = Cb[5];
530 TNAME Q33 = Cb[8];
531
532 TNAME JA13 = -sa*xb - ca*yb;
533 TNAME JA23 = ca*xb - sa*yb;
534 TNAME JB11 = ca;
535 TNAME JB12 = -sa;
536 TNAME JB21 = sa;
537 TNAME JB22 = ca;
538
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;
542 Cr[3] = Cr[1];
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;
545 Cr[6] = Cr[2];
546 Cr[7] = Cr[5];
547 Cr[8] = P33 + Q33;
548
549 xytr[0] = ca*xb - sa*yb + xa;
550 xytr[1] = sa*xb + ca*yb + ya;
551 xytr[2] = xyta[2] + xytb[2];
552
553/*
554 // the code above is just an unrolling of the following:
555
556 TNAME JA[][] = new TNAME[][] { { 1, 0, -sa*xb - ca*yb },
557 { 0, 1, ca*xb - sa*yb },
558 { 0, 0, 1 } };
559 TNAME JB[][] = new TNAME[][] { { ca, -sa, 0 },
560 { sa, ca, 0 },
561 { 0, 0, 1 } };
562
563 newge.P = LinAlg.add(LinAlg.matrixABCt(JA, P, JA),
564 LinAlg.matrixABCt(JB, ge.P, JB));
565*/
566}
567
568
569static inline void TFN(s_xyt_inv)(const TNAME xyta[3], TNAME xytr[3])
570{
571 TNAME s = (TNAME)sin(xyta[2]), c = (TNAME)cos(xyta[2]);
572 xytr[0] = -s*xyta[1] - c*xyta[0];
573 xytr[1] = -c*xyta[1] + s*xyta[0];
574 xytr[2] = -xyta[2];
575}
576
577static inline void TFN(s_xytcov_inv)(const TNAME xyta[3], const TNAME Ca[9],
578 TNAME xytr[3], TNAME Cr[9])
579{
580 TNAME x = xyta[0], y = xyta[1], theta = xyta[2];
581 TNAME s = (TNAME)sin(theta), c = (TNAME)cos(theta);
582
583 TNAME J11 = -c, J12 = -s, J13 = -c*y + s*x;
584 TNAME J21 = s, J22 = -c, J23 = s*y + c*x;
585
586 TNAME P11 = Ca[0], P12 = Ca[1], P13 = Ca[2];
587 TNAME P22 = Ca[4], P23 = Ca[5];
588 TNAME P33 = Ca[8];
589
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;
596 Cr[3] = Cr[1];
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;
600 Cr[6] = Cr[2];
601 Cr[7] = Cr[5];
602 Cr[8] = P33;
603
604 /*
605 // the code above is just an unrolling of the following:
606
607 TNAME J[][] = new TNAME[][] { { -c, -s, -c*y + s*x },
608 { s, -c, s*y + c*x },
609 { 0, 0, -1 } };
610 ge.P = LinAlg.matrixABCt(J, P, J);
611 */
612
613 xytr[0] = -s*y - c*x;
614 xytr[1] = -c*y + s*x;
615 xytr[2] = -xyta[2];
616}
617
618// xytr = inv(xyta) * xytb
619static inline void TFN(s_xyt_inv_mul)(const TNAME xyta[3], const TNAME xytb[3], TNAME xytr[3])
620{
621 TNAME theta = xyta[2];
622 TNAME ca = (TNAME)cos(theta);
623 TNAME sa = (TNAME)sin(theta);
624 TNAME dx = xytb[0] - xyta[0];
625 TNAME dy = xytb[1] - xyta[1];
626
627 xytr[0] = ca*dx + sa*dy;
628 xytr[1] = -sa*dx + ca*dy;
629 xytr[2]= xytb[2] - xyta[2];
630}
631
632static inline void TFN(s_mat_add)(const TNAME *A, int Arows, int Acols,
633 const TNAME *B, int Brows, int Bcols,
634 TNAME *R, int Rrows, int Rcols)
635{
636 assert(Arows == Brows);
637 assert(Arows == Rrows);
638 assert(Bcols == Bcols);
639 assert(Bcols == Rcols);
640
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];
644}
645
646// matrix should be in row-major order, allocated in a single packed
647// array. (This is compatible with matd.)
648static inline void TFN(s_mat_AB)(const TNAME *A, int Arows, int Acols,
649 const TNAME *B, int Brows, int Bcols,
650 TNAME *R, int Rrows, int Rcols)
651{
652 assert(Acols == Brows);
653 assert(Rrows == Arows);
654 assert(Bcols == Rcols);
655
656 for (int Rrow = 0; Rrow < Rrows; Rrow++) {
657 for (int Rcol = 0; Rcol < Rcols; Rcol++) {
658 TNAME acc = 0;
659 for (int i = 0; i < Acols; i++)
660 acc += A[Rrow*Acols + i] * B[i*Bcols + Rcol];
661 R[Rrow*Rcols + Rcol] = acc;
662 }
663 }
664}
665
666// matrix should be in row-major order, allocated in a single packed
667// array. (This is compatible with matd.)
668static inline void TFN(s_mat_ABt)(const TNAME *A, int Arows, int Acols,
669 const TNAME *B, int Brows, int Bcols,
670 TNAME *R, int Rrows, int Rcols)
671{
672 assert(Acols == Bcols);
673 assert(Rrows == Arows);
674 assert(Brows == Rcols);
675
676 for (int Rrow = 0; Rrow < Rrows; Rrow++) {
677 for (int Rcol = 0; Rcol < Rcols; Rcol++) {
678 TNAME acc = 0;
679 for (int i = 0; i < Acols; i++)
680 acc += A[Rrow*Acols + i] * B[Rcol*Bcols + i];
681 R[Rrow*Rcols + Rcol] = acc;
682 }
683 }
684}
685
686static inline void TFN(s_mat_ABC)(const TNAME *A, int Arows, int Acols,
687 const TNAME *B, int Brows, int Bcols,
688 const TNAME *C, int Crows, int Ccols,
689 TNAME *R, int Rrows, int Rcols)
690{
691 TNAME *tmp = malloc(sizeof(TNAME)*Arows*Bcols);
692
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);
695 free(tmp);
696}
697
698static inline void TFN(s_mat_Ab)(const TNAME *A, int Arows, int Acols,
699 const TNAME *B, int Blength,
700 TNAME *R, int Rlength)
701{
702 assert(Acols == Blength);
703 assert(Arows == Rlength);
704
705 for (int Ridx = 0; Ridx < Rlength; Ridx++) {
706 TNAME acc = 0;
707 for (int i = 0; i < Blength; i++)
708 acc += A[Ridx*Acols + i] * B[i];
709 R[Ridx] = acc;
710 }
711}
712
713static inline void TFN(s_mat_AtB)(const TNAME *A, int Arows, int Acols,
714 const TNAME *B, int Brows, int Bcols,
715 TNAME *R, int Rrows, int Rcols)
716{
717 assert(Arows == Brows);
718 assert(Rrows == Acols);
719 assert(Bcols == Rcols);
720
721 for (int Rrow = 0; Rrow < Rrows; Rrow++) {
722 for (int Rcol = 0; Rcol < Rcols; Rcol++) {
723 TNAME acc = 0;
724 for (int i = 0; i < Acols; i++)
725 acc += A[i*Acols + Rrow] * B[i*Bcols + Rcol];
726 R[Rrow*Rcols + Rcol] = acc;
727 }
728 }
729}
730
731static inline void TFN(s_quat_slerp)(const TNAME q0[4], const TNAME _q1[4], TNAME r[4], TNAME w)
732{
733 TNAME dot = TFN(s_dot)(q0, _q1, 4);
734
735 TNAME q1[4];
736 memcpy(q1, _q1, sizeof(TNAME) * 4);
737
738 if (dot < 0) {
739 // flip sign on one of them so we don't spin the "wrong
740 // way" around. This doesn't change the rotation that the
741 // quaternion represents.
742 dot = -dot;
743 for (int i = 0; i < 4; i++)
744 q1[i] *= -1;
745 }
746
747 // if large dot product (1), slerp will scale both q0 and q1
748 // by 0, and normalization will blow up.
749 if (dot > 0.95) {
750
751 for (int i = 0; i < 4; i++)
752 r[i] = q0[i]*(1-w) + q1[i]*w;
753
754 } else {
755 TNAME angle = (TNAME)acos(dot);
756
757 TNAME w0 = (TNAME)sin(angle*(1-w)), w1 = (TNAME)sin(angle*w);
758
759 for (int i = 0; i < 4; i++)
760 r[i] = q0[i]*w0 + q1[i]*w1;
761
762 TFN(s_normalize)(r, 4, r);
763 }
764}
765
766static inline void TFN(s_cross_product)(const TNAME v1[3], const TNAME v2[3], TNAME r[3])
767{
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];
771}
772
773////////////////////
774static inline void TFN(s_mat44_identity)(TNAME out[16])
775{
776 memset(out, 0, 16 * sizeof(TNAME));
777 out[0] = 1;
778 out[5] = 1;
779 out[10] = 1;
780 out[15] = 1;
781}
782
783static inline void TFN(s_mat44_translate)(const TNAME txyz[3], TNAME out[16])
784{
785 TFN(s_mat44_identity)(out);
786
787 for (int i = 0; i < 3; i++)
788 out[4*i + 3] += txyz[i];
789}
790
791static inline void TFN(s_mat44_scale)(const TNAME sxyz[3], TNAME out[16])
792{
793 TFN(s_mat44_identity)(out);
794
795 for (int i = 0; i < 3; i++)
796 out[4*i + i] = sxyz[i];
797}
798
799static inline void TFN(s_mat44_rotate_z)(TNAME rad, TNAME out[16])
800{
801 TFN(s_mat44_identity)(out);
802 TNAME s = (TNAME)sin(rad), c = (TNAME)cos(rad);
803 out[0*4 + 0] = c;
804 out[0*4 + 1] = -s;
805 out[1*4 + 0] = s;
806 out[1*4 + 1] = c;
807}
808
809static inline void TFN(s_mat44_rotate_y)(TNAME rad, TNAME out[16])
810{
811 TFN(s_mat44_identity)(out);
812 TNAME s = (TNAME)sin(rad), c = (TNAME)cos(rad);
813 out[0*4 + 0] = c;
814 out[0*4 + 2] = s;
815 out[2*4 + 0] = -s;
816 out[2*4 + 2] = c;
817}
818
819static inline void TFN(s_mat44_rotate_x)(TNAME rad, TNAME out[16])
820{
821 TFN(s_mat44_identity)(out);
822 TNAME s = (TNAME)sin(rad), c = (TNAME)cos(rad);
823 out[1*4 + 1] = c;
824 out[1*4 + 2] = -s;
825 out[2*4 + 1] = s;
826 out[2*4 + 2] = c;
827}
828
829// out = out * translate(txyz)
830static inline void TFN(s_mat44_translate_self)(const TNAME txyz[3], TNAME out[16])
831{
832 TNAME tmp[16], prod[16];
833 TFN(s_mat44_translate(txyz, tmp));
834 TFN(s_mat_AB)(out, 4, 4, tmp, 4, 4, prod, 4, 4);
835 memcpy(out, prod, sizeof(TNAME)*16);
836}
837
838static inline void TFN(s_mat44_scale_self)(const TNAME sxyz[3], TNAME out[16])
839{
840 TNAME tmp[16], prod[16];
841 TFN(s_mat44_scale(sxyz, tmp));
842 TFN(s_mat_AB)(out, 4, 4, tmp, 4, 4, prod, 4, 4);
843 memcpy(out, prod, sizeof(TNAME)*16);
844}
845
846static inline void TFN(s_mat44_rotate_z_self)(TNAME rad, TNAME out[16])
847{
848 TNAME tmp[16], prod[16];
849 TFN(s_mat44_rotate_z(rad, tmp));
850 TFN(s_mat_AB)(out, 4, 4, tmp, 4, 4, prod, 4, 4);
851 memcpy(out, prod, sizeof(TNAME)*16);
852}
853
854// out = inv(M)*in. Note: this assumes that mat44 is a rigid-body transformation.
855static inline void TFN(s_mat44_inv)(const TNAME M[16], TNAME out[16])
856{
857// NB: M = T*R, inv(M) = inv(R) * inv(T)
858
859 // transpose of upper-left corner
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];
863
864 out[4*0 + 3] = 0;
865 out[4*1 + 3] = 0;
866 out[4*2 + 3] = 0;
867
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];
871
872 out[4*3 + 0] = 0;
873 out[4*3 + 1] = 0;
874 out[4*3 + 2] = 0;
875 out[4*3 + 3] = 1;
876
877/* TNAME tmp[16];
878 TFN(s_mat_AB)(M, 4, 4, out, 4, 4, tmp, 4, 4);
879 printf("identity: ");
880 TFN(s_print_mat)(tmp, 4, 4, "%15f"); */
881}
882
883// out = inv(M)*in
884static inline void TFN(s_mat44_inv_transform_xyz)(const TNAME M[16], const TNAME in[3], TNAME out[3])
885{
886 TNAME T[16];
887 TFN(s_mat44_inv)(M, T);
888
889 TFN(s_mat44_transform_xyz)(T, in, out);
890}
891
892// out = (upper 3x3 of inv(M)) * in
893static inline void TFN(s_mat44_inv_rotate_vector)(const TNAME M[16], const TNAME in[3], TNAME out[3])
894{
895 TNAME T[16];
896 TFN(s_mat44_inv)(M, T);
897
898 TFN(s_mat44_rotate_vector)(T, in, out);
899}
900
901static inline void TFN(s_elu_to_mat44)(const TNAME eye[3], const TNAME lookat[3], const TNAME _up[3],
902 TNAME M[16])
903{
904 TNAME f[3];
905 TFN(s_subtract)(lookat, eye, 3, f);
906 TFN(s_normalize)(f, 3, f);
907
908 TNAME up[3];
909
910 // remove any component of 'up' that isn't perpendicular to the look direction.
911 TFN(s_normalize)(_up, 3, up);
912
913 TNAME up_dot = TFN(s_dot)(f, up, 3);
914 for (int i = 0; i < 3; i++)
915 up[i] -= up_dot*f[i];
916
917 TFN(s_normalize_self)(up, 3);
918
919 TNAME s[3], u[3];
920 TFN(s_cross_product)(f, up, s);
921 TFN(s_cross_product)(s, f, u);
922
923 TNAME R[16] = { s[0], s[1], s[2], 0,
924 u[0], u[1], u[2], 0,
925 -f[0], -f[1], -f[2], 0,
926 0, 0, 0, 1};
927
928 TNAME T[16] = {1, 0, 0, -eye[0],
929 0, 1, 0, -eye[1],
930 0, 0, 1, -eye[2],
931 0, 0, 0, 1};
932
933 // M is the extrinsics matrix [R | t] where t = -R*c
934 TNAME tmp[16];
935 TFN(s_mat_AB)(R, 4, 4, T, 4, 4, tmp, 4, 4);
936 TFN(s_mat44_inv)(tmp, M);
937}
938
939// Computes the cholesky factorization of A, putting the lower
940// triangular matrix into R.
941static inline void TFN(s_mat33_chol)(const TNAME *A, int Arows, int Acols,
942 TNAME *R, int Brows, int Bcols)
943{
944 assert(Arows == Brows);
945 assert(Bcols == Bcols);
946
947 // A[0] = R[0]*R[0]
948 R[0] = (TNAME)sqrt(A[0]);
949
950 // A[1] = R[0]*R[3];
951 R[3] = A[1] / R[0];
952
953 // A[2] = R[0]*R[6];
954 R[6] = A[2] / R[0];
955
956 // A[4] = R[3]*R[3] + R[4]*R[4]
957 R[4] = (TNAME)sqrt(A[4] - R[3]*R[3]);
958
959 // A[5] = R[3]*R[6] + R[4]*R[7]
960 R[7] = (A[5] - R[3]*R[6]) / R[4];
961
962 // A[8] = R[6]*R[6] + R[7]*R[7] + R[8]*R[8]
963 R[8] = (TNAME)sqrt(A[8] - R[6]*R[6] - R[7]*R[7]);
964
965 R[1] = 0;
966 R[2] = 0;
967 R[5] = 0;
968}
969
970static inline void TFN(s_mat33_lower_tri_inv)(const TNAME *A, int Arows, int Acols,
971 TNAME *R, int Rrows, int Rcols)
972{
973 // A[0]*R[0] = 1
974 R[0] = 1 / A[0];
975
976 // A[3]*R[0] + A[4]*R[3] = 0
977 R[3] = -A[3]*R[0] / A[4];
978
979 // A[4]*R[4] = 1
980 R[4] = 1 / A[4];
981
982 // A[6]*R[0] + A[7]*R[3] + A[8]*R[6] = 0
983 R[6] = (-A[6]*R[0] - A[7]*R[3]) / A[8];
984
985 // A[7]*R[4] + A[8]*R[7] = 0
986 R[7] = -A[7]*R[4] / A[8];
987
988 // A[8]*R[8] = 1
989 R[8] = 1 / A[8];
990}
991
992
993static inline void TFN(s_mat33_sym_solve)(const TNAME *A, int Arows, int Acols,
994 const TNAME *B, int Brows, int Bcols,
995 TNAME *R, int Rrows, int Rcols)
996{
997 assert(Arows == Acols);
998 assert(Acols == 3);
999 assert(Brows == 3);
1000 assert(Bcols == 1);
1001 assert(Rrows == 3);
1002 assert(Rcols == 1);
1003
1004 TNAME L[9];
1005 TFN(s_mat33_chol)(A, 3, 3, L, 3, 3);
1006
1007 TNAME M[9];
1008 TFN(s_mat33_lower_tri_inv)(L, 3, 3, M, 3, 3);
1009
1010 double tmp[3];
1011 tmp[0] = M[0]*B[0];
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];
1014
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]);
1018}
1019
1020/*
1021// solve Ax = B. Assumes A is symmetric; uses cholesky factorization
1022static inline void TFN(s_mat_solve_chol)(const TNAME *A, int Arows, int Acols,
1023 const TNAME *B, int Brows, int Bcols,
1024 TNAME *R, int Rrows, int Rcols)
1025{
1026 assert(Arows == Acols);
1027 assert(Arows == Brows);
1028 assert(Acols == Rrows);
1029 assert(Bcols == Rcols);
1030
1031 //
1032}
1033*/
1034#undef TRRFN
1035#undef TRFN
1036#undef TFN
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