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


apriltags2
Author(s): Danylo Malyuta
autogenerated on Fri Oct 19 2018 04:02:32