testRot3.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/geometry/Point3.h>
21 #include <gtsam/geometry/Rot3.h>
22 #include <gtsam/base/testLie.h>
23 #include <gtsam/base/Testable.h>
25 #include <gtsam/base/lieProxies.h>
26 
28 
29 using namespace std;
30 using namespace gtsam;
31 
34 
35 static Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2);
36 static Point3 P(0.2, 0.7, -2.0);
37 static double error = 1e-9, epsilon = 0.001;
38 
39 //******************************************************************************
40 TEST(Rot3 , Concept) {
42  GTSAM_CONCEPT_ASSERT(IsManifold<Rot3 >);
44 }
45 
46 /* ************************************************************************* */
47 TEST( Rot3, chart)
48 {
49  Matrix R = (Matrix(3, 3) << 0, 1, 0, 1, 0, 0, 0, 0, -1).finished();
50  Rot3 rot3(R);
51 }
52 
53 /* ************************************************************************* */
55 {
56  Rot3 expected((Matrix)I_3x3);
57  Point3 r1(1,0,0), r2(0,1,0), r3(0,0,1);
58  Rot3 actual(r1, r2, r3);
59  CHECK(assert_equal(actual,expected));
60 }
61 
62 /* ************************************************************************* */
63 TEST( Rot3, constructor2)
64 {
65  Matrix R = (Matrix(3, 3) << 0, 1, 0, 1, 0, 0, 0, 0, -1).finished();
66  Rot3 actual(R);
67  Rot3 expected(0, 1, 0, 1, 0, 0, 0, 0, -1);
68  CHECK(assert_equal(actual,expected));
69 }
70 
71 /* ************************************************************************* */
72 TEST( Rot3, constructor3)
73 {
74  Rot3 expected(0, 1, 0, 1, 0, 0, 0, 0, -1);
75  Point3 r1(0,1,0), r2(1,0,0), r3(0,0,-1);
77 }
78 
79 /* ************************************************************************* */
80 TEST( Rot3, transpose)
81 {
82  Point3 r1(0,1,0), r2(1,0,0), r3(0,0,-1);
83  Rot3 R(0, 1, 0, 1, 0, 0, 0, 0, -1);
85 }
86 
87 /* ************************************************************************* */
89 {
90  CHECK(R.equals(R));
91  Rot3 zero;
92  CHECK(!R.equals(zero));
93 }
94 
95 /* ************************************************************************* */
96 // Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + ....
98  double t = w.norm();
99  Matrix3 J = skewSymmetric(w / t);
100  if (t < 1e-5) return Rot3();
101  Matrix3 R = I_3x3 + sin(t) * J + (1.0 - cos(t)) * (J * J);
102  return Rot3(R);
103 }
104 
105 /* ************************************************************************* */
106 TEST( Rot3, AxisAngle)
107 {
108  Vector axis = Vector3(0., 1., 0.); // rotation around Y
109  double angle = 3.14 / 4.0;
110  Rot3 expected(0.707388, 0, 0.706825,
111  0, 1, 0,
112  -0.706825, 0, 0.707388);
113  Rot3 actual = Rot3::AxisAngle(axis, angle);
114  CHECK(assert_equal(expected,actual,1e-5));
115  Rot3 actual2 = Rot3::AxisAngle(axis, angle-2*M_PI);
116  CHECK(assert_equal(expected,actual2,1e-5));
117 
118  axis = Vector3(0, 50, 0);
119  Rot3 actual3 = Rot3::AxisAngle(axis, angle);
120  CHECK(assert_equal(expected,actual3,1e-5));
121 }
122 
123 /* ************************************************************************* */
124 TEST( Rot3, AxisAngle2)
125 {
126  // constructor from a rotation matrix, as doubles in *row-major* order.
127  Rot3 R1(-0.999957, 0.00922903, 0.00203116, 0.00926964, 0.999739, 0.0208927, -0.0018374, 0.0209105, -0.999781);
128 
129  // convert Rot3 to quaternion using GTSAM
130  const auto [actualAxis, actualAngle] = R1.axisAngle();
131 
132  double expectedAngle = 3.1396582;
133  CHECK(assert_equal(expectedAngle, actualAngle, 1e-5));
134 }
135 
136 /* ************************************************************************* */
137 TEST( Rot3, Rodrigues)
138 {
139  Rot3 R1 = Rot3::Rodrigues(epsilon, 0, 0);
140  Vector w = (Vector(3) << epsilon, 0., 0.).finished();
143 }
144 
145 /* ************************************************************************* */
146 TEST( Rot3, Rodrigues2)
147 {
148  Vector axis = Vector3(0., 1., 0.); // rotation around Y
149  double angle = 3.14 / 4.0;
150  Rot3 expected(0.707388, 0, 0.706825,
151  0, 1, 0,
152  -0.706825, 0, 0.707388);
153  Rot3 actual = Rot3::AxisAngle(axis, angle);
154  CHECK(assert_equal(expected,actual,1e-5));
155  Rot3 actual2 = Rot3::Rodrigues(angle*axis);
156  CHECK(assert_equal(expected,actual2,1e-5));
157 }
158 
159 /* ************************************************************************* */
160 TEST( Rot3, Rodrigues3)
161 {
162  Vector w = Vector3(0.1, 0.2, 0.3);
163  Rot3 R1 = Rot3::AxisAngle(w / w.norm(), w.norm());
166 }
167 
168 /* ************************************************************************* */
169 TEST( Rot3, Rodrigues4)
170 {
171  Vector axis = Vector3(0., 0., 1.); // rotation around Z
172  double angle = M_PI/2.0;
173  Rot3 actual = Rot3::AxisAngle(axis, angle);
174  double c=cos(angle),s=sin(angle);
175  Rot3 expected(c,-s, 0,
176  s, c, 0,
177  0, 0, 1);
178  CHECK(assert_equal(expected,actual));
179  CHECK(assert_equal(slow_but_correct_Rodrigues(axis*angle),actual));
180 }
181 
182 /* ************************************************************************* */
184 {
185  Vector v = Z_3x1;
187 
188 // // test Canonical coordinates
189 // Canonical<Rot3> chart;
190 // Vector v2 = chart.local(R);
191 // CHECK(assert_equal(R, chart.retract(v2)));
192 }
193 
194 /* ************************************************************************* */
196  static const double PI = std::acos(-1.0);
197  Vector w;
198  Rot3 R;
199 
200 #define CHECK_OMEGA(X, Y, Z) \
201  w = (Vector(3) << (X), (Y), (Z)).finished(); \
202  R = Rot3::Rodrigues(w); \
203  EXPECT(assert_equal(w, Rot3::Logmap(R), 1e-12));
204 
205  // Check zero
206  CHECK_OMEGA(0, 0, 0)
207 
208  // create a random direction:
209  double norm = sqrt(1.0 + 16.0 + 4.0);
210  double x = 1.0 / norm, y = 4.0 / norm, z = 2.0 / norm;
211 
212  // Check very small rotation for Taylor expansion
213  // Note that tolerance above is 1e-12, so Taylor is pretty good !
214  double d = 0.0001;
215  CHECK_OMEGA(d, 0, 0)
216  CHECK_OMEGA(0, d, 0)
217  CHECK_OMEGA(0, 0, d)
218  CHECK_OMEGA(x * d, y * d, z * d)
219 
220  // check normal rotation
221  d = 0.1;
222  CHECK_OMEGA(d, 0, 0)
223  CHECK_OMEGA(0, d, 0)
224  CHECK_OMEGA(0, 0, d)
225  CHECK_OMEGA(x * d, y * d, z * d)
226 
227  // Check 180 degree rotations
228  CHECK_OMEGA(PI, 0, 0)
229  CHECK_OMEGA(0, PI, 0)
230  CHECK_OMEGA(0, 0, PI)
231 
232  // Windows and Linux have flipped sign in quaternion mode
233 //#if !defined(__APPLE__) && defined(GTSAM_USE_QUATERNIONS)
234  w = (Vector(3) << x * PI, y * PI, z * PI).finished();
235  R = Rot3::Rodrigues(w);
236  EXPECT(assert_equal(Vector(-w), Rot3::Logmap(R), 1e-12));
237 //#else
238 // CHECK_OMEGA(x * PI, y * PI, z * PI)
239 //#endif
240 
241  // Check 360 degree rotations
242 #define CHECK_OMEGA_ZERO(X, Y, Z) \
243  w = (Vector(3) << (X), (Y), (Z)).finished(); \
244  R = Rot3::Rodrigues(w); \
245  EXPECT(assert_equal((Vector)Z_3x1, Rot3::Logmap(R)));
246 
247  CHECK_OMEGA_ZERO(2.0 * PI, 0, 0)
248  CHECK_OMEGA_ZERO(0, 2.0 * PI, 0)
249  CHECK_OMEGA_ZERO(0, 0, 2.0 * PI)
250  CHECK_OMEGA_ZERO(x * 2. * PI, y * 2. * PI, z * 2. * PI)
251 
252  // Check problematic case from Lund dataset vercingetorix.g2o
253  // This is an almost rotation with determinant not *quite* 1.
254  Rot3 Rlund(-0.98582676, -0.03958746, -0.16303092, //
255  -0.03997006, -0.88835923, 0.45740671, //
256  -0.16293753, 0.45743998, 0.87418537);
257 
258  // Rot3's Logmap returns different, but equivalent compacted
259  // axis-angle vectors depending on whether Rot3 is implemented
260  // by Quaternions or SO3.
261 #if defined(GTSAM_USE_QUATERNIONS)
262  // Quaternion bounds angle to [-pi, pi] resulting in ~179.9 degrees
263  EXPECT(assert_equal(Vector3(0.264451979, -0.742197651, -3.04098211),
264  (Vector)Rot3::Logmap(Rlund), 1e-8));
265 #else
266  // SO3 will be approximate because of the non-orthogonality
267  EXPECT(assert_equal(Vector3(0.264452, -0.742197708, -3.04098184),
268  (Vector)Rot3::Logmap(Rlund), 1e-8));
269 #endif
270 }
271 
272 /* ************************************************************************* */
273 TEST(Rot3, retract_localCoordinates)
274 {
275  Vector3 d12 = Vector3::Constant(0.1);
276  Rot3 R2 = R.retract(d12);
278 }
279 /* ************************************************************************* */
280 TEST(Rot3, expmap_logmap)
281 {
282  Vector d12 = Vector3::Constant(0.1);
283  Rot3 R2 = R.expmap(d12);
284  EXPECT(assert_equal(d12, R.logmap(R2)));
285 }
286 
287 /* ************************************************************************* */
288 TEST(Rot3, retract_localCoordinates2)
289 {
290  Rot3 t1 = R, t2 = R*R, origin;
291  Vector d12 = t1.localCoordinates(t2);
292  EXPECT(assert_equal(t2, t1.retract(d12)));
293  Vector d21 = t2.localCoordinates(t1);
294  EXPECT(assert_equal(t1, t2.retract(d21)));
295  EXPECT(assert_equal(d12, -d21));
296 }
297 /* ************************************************************************* */
298 TEST(Rot3, manifold_expmap)
299 {
300  Rot3 gR1 = Rot3::Rodrigues(0.1, 0.4, 0.2);
301  Rot3 gR2 = Rot3::Rodrigues(0.3, 0.1, 0.7);
302  Rot3 origin;
303 
304  // log behaves correctly
305  Vector d12 = Rot3::Logmap(gR1.between(gR2));
306  Vector d21 = Rot3::Logmap(gR2.between(gR1));
307 
308  // Check expmap
309  CHECK(assert_equal(gR2, gR1*Rot3::Expmap(d12)));
310  CHECK(assert_equal(gR1, gR2*Rot3::Expmap(d21)));
311 
312  // Check that log(t1,t2)=-log(t2,t1)
313  CHECK(assert_equal(d12,-d21));
314 
315  // lines in canonical coordinates correspond to Abelian subgroups in SO(3)
316  Vector d = Vector3(0.1, 0.2, 0.3);
317  // exp(-d)=inverse(exp(d))
319  // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d)
320  Rot3 R2 = Rot3::Expmap (2 * d);
321  Rot3 R3 = Rot3::Expmap (3 * d);
322  Rot3 R5 = Rot3::Expmap (5 * d);
323  CHECK(assert_equal(R5,R2*R3));
324  CHECK(assert_equal(R5,R3*R2));
325 }
326 
327 /* ************************************************************************* */
328 TEST(Rot3, HatAndVee) {
329  // Create a few test vectors
330  Vector3 v1(1, 2, 3);
331  Vector3 v2(0.1, -0.5, 1.0);
332  Vector3 v3(0.0, 0.0, 0.0);
333 
334  // Test that Vee(Hat(v)) == v for various inputs
335  EXPECT(assert_equal(v1, Rot3::Vee(Rot3::Hat(v1))));
336  EXPECT(assert_equal(v2, Rot3::Vee(Rot3::Hat(v2))));
337  EXPECT(assert_equal(v3, Rot3::Vee(Rot3::Hat(v3))));
338 
339  // Check the structure of the Lie Algebra element
340  Matrix3 expected;
341  expected << 0, -3, 2,
342  3, 0, -1,
343  -2, 1, 0;
344 
345  EXPECT(assert_equal(expected, Rot3::Hat(v1)));
346 }
347 
348 /* ************************************************************************* */
349 // Checks correct exponential map (Expmap) with brute force matrix exponential
350 TEST(Rot3, BruteForceExpmap) {
351  const Vector3 xi(0.1, 0.2, 0.3);
352  EXPECT(assert_equal(Rot3::Expmap(xi), expm<Rot3>(xi), 1e-6));
353 }
354 
355 /* ************************************************************************* */
356 class AngularVelocity : public Vector3 {
357  public:
358  template <typename Derived>
360  : Vector3(v) {}
361 
362  AngularVelocity(double wx, double wy, double wz) : Vector3(wx, wy, wz) {}
363 };
364 
366  return X.cross(Y);
367 }
368 
369 /* ************************************************************************* */
371 {
372  // Approximate exmap by BCH formula
373  AngularVelocity w1(0.2, -0.1, 0.1);
374  AngularVelocity w2(0.01, 0.02, -0.03);
375  Rot3 R1 = Rot3::Expmap (w1), R2 = Rot3::Expmap (w2);
376  Rot3 R3 = R1 * R2;
377  Vector expected = Rot3::Logmap(R3);
378  Vector actual = BCH(w1, w2);
379  CHECK(assert_equal(expected, actual,1e-5));
380 }
381 
382 /* ************************************************************************* */
383 TEST( Rot3, rotate_derivatives)
384 {
385  Matrix actualDrotate1a, actualDrotate1b, actualDrotate2;
386  R.rotate(P, actualDrotate1a, actualDrotate2);
387  R.inverse().rotate(P, actualDrotate1b, {});
388  Matrix numerical1 = numericalDerivative21(testing::rotate<Rot3,Point3>, R, P);
389  Matrix numerical2 = numericalDerivative21(testing::rotate<Rot3,Point3>, R.inverse(), P);
390  Matrix numerical3 = numericalDerivative22(testing::rotate<Rot3,Point3>, R, P);
391  EXPECT(assert_equal(numerical1,actualDrotate1a,error));
392  EXPECT(assert_equal(numerical2,actualDrotate1b,error));
393  EXPECT(assert_equal(numerical3,actualDrotate2, error));
394 }
395 
396 /* ************************************************************************* */
398 {
399  Point3 w = R * P;
400  Matrix H1,H2;
401  Point3 actual = R.unrotate(w,H1,H2);
402  CHECK(assert_equal(P,actual));
403 
404  Matrix numerical1 = numericalDerivative21(testing::unrotate<Rot3,Point3>, R, w);
405  CHECK(assert_equal(numerical1,H1,error));
406 
407  Matrix numerical2 = numericalDerivative22(testing::unrotate<Rot3,Point3>, R, w);
408  CHECK(assert_equal(numerical2,H2,error));
409 }
410 
411 /* ************************************************************************* */
413 {
414  Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3);
415  Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5);
416 
417  Rot3 expected = R1 * R2;
418  Matrix actualH1, actualH2;
419  Rot3 actual = R1.compose(R2, actualH1, actualH2);
420  CHECK(assert_equal(expected,actual));
421 
422  Matrix numericalH1 = numericalDerivative21(testing::compose<Rot3>, R1,
423  R2, 1e-2);
424  CHECK(assert_equal(numericalH1,actualH1));
425 
426  Matrix numericalH2 = numericalDerivative22(testing::compose<Rot3>, R1,
427  R2, 1e-2);
428  CHECK(assert_equal(numericalH2,actualH2));
429 }
430 
431 /* ************************************************************************* */
433 {
434  Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
435 
436  Rot3 I;
437  Matrix3 actualH;
438  Rot3 actual = R.inverse(actualH);
439  CHECK(assert_equal(I,R*actual));
440  CHECK(assert_equal(I,actual*R));
441  CHECK(assert_equal(actual.matrix(), R.transpose()));
442 
443  Matrix numericalH = numericalDerivative11(testing::inverse<Rot3>, R);
444  CHECK(assert_equal(numericalH,actualH));
445 }
446 
447 /* ************************************************************************* */
449 {
450  Rot3 r1 = Rot3::Rz(M_PI/3.0);
451  Rot3 r2 = Rot3::Rz(2.0*M_PI/3.0);
452 
453  Matrix expectedr1 = (Matrix(3, 3) <<
454  0.5, -sqrt(3.0)/2.0, 0.0,
455  sqrt(3.0)/2.0, 0.5, 0.0,
456  0.0, 0.0, 1.0).finished();
457  EXPECT(assert_equal(expectedr1, r1.matrix()));
458 
459  Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2);
460  Rot3 origin;
461  EXPECT(assert_equal(R, origin.between(R)));
463 
464  Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3);
465  Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5);
466 
467  Rot3 expected = R1.inverse() * R2;
468  Matrix actualH1, actualH2;
469  Rot3 actual = R1.between(R2, actualH1, actualH2);
470  EXPECT(assert_equal(expected,actual));
471 
472  Matrix numericalH1 = numericalDerivative21(testing::between<Rot3> , R1, R2);
473  CHECK(assert_equal(numericalH1,actualH1));
474 
475  Matrix numericalH2 = numericalDerivative22(testing::between<Rot3> , R1, R2);
476  CHECK(assert_equal(numericalH2,actualH2));
477 }
478 
479 /* ************************************************************************* */
480 TEST( Rot3, xyz )
481 {
482  double t = 0.1, st = sin(t), ct = cos(t);
483 
484  // Make sure all counterclockwise
485  // Diagrams below are all from from unchanging axis
486 
487  // z
488  // | * Y=(ct,st)
489  // x----y
490  Rot3 expected1(1, 0, 0, 0, ct, -st, 0, st, ct);
491  CHECK(assert_equal(expected1,Rot3::Rx(t)));
492 
493  // x
494  // | * Z=(ct,st)
495  // y----z
496  Rot3 expected2(ct, 0, st, 0, 1, 0, -st, 0, ct);
497  CHECK(assert_equal(expected2,Rot3::Ry(t)));
498 
499  // y
500  // | X=* (ct,st)
501  // z----x
502  Rot3 expected3(ct, -st, 0, st, ct, 0, 0, 0, 1);
503  CHECK(assert_equal(expected3,Rot3::Rz(t)));
504 
505  // Check compound rotation
506  Rot3 expected = Rot3::Rz(0.3) * Rot3::Ry(0.2) * Rot3::Rx(0.1);
507  CHECK(assert_equal(expected,Rot3::RzRyRx(0.1,0.2,0.3)));
508 }
509 
510 /* ************************************************************************* */
511 TEST( Rot3, yaw_pitch_roll )
512 {
513  double t = 0.1;
514 
515  // yaw is around z axis
516  CHECK(assert_equal(Rot3::Rz(t),Rot3::Yaw(t)));
517 
518  // pitch is around y axis
519  CHECK(assert_equal(Rot3::Ry(t),Rot3::Pitch(t)));
520 
521  // roll is around x axis
522  CHECK(assert_equal(Rot3::Rx(t),Rot3::Roll(t)));
523 
524  // Check compound rotation
525  Rot3 expected = Rot3::Yaw(0.1) * Rot3::Pitch(0.2) * Rot3::Roll(0.3);
526  CHECK(assert_equal(expected,Rot3::Ypr(0.1,0.2,0.3)));
527 
528  CHECK(assert_equal((Vector)Vector3(0.1, 0.2, 0.3),expected.ypr()));
529 }
530 
531 /* ************************************************************************* */
533 {
534  // Try RQ on a pure rotation
535  const auto [actualK, actual] = RQ(R.matrix());
536  Vector expected = Vector3(0.14715, 0.385821, 0.231671);
537  CHECK(assert_equal(I_3x3, (Matrix)actualK));
538  CHECK(assert_equal(expected,actual,1e-6));
539 
540  // Try using xyz call, asserting that Rot3::RzRyRx(x,y,z).xyz()==[x;y;z]
541  CHECK(assert_equal(expected,R.xyz(),1e-6));
542  CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz()));
543 
544  // Try using ypr call, asserting that Rot3::Ypr(y,p,r).ypr()==[y;p;r]
545  CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::Ypr(0.1,0.2,0.3).ypr()));
546  CHECK(assert_equal((Vector)Vector3(0.3,0.2,0.1),Rot3::Ypr(0.1,0.2,0.3).rpy()));
547 
548  // Try ypr for pure yaw-pitch-roll matrices
549  CHECK(assert_equal((Vector)Vector3(0.1,0.0,0.0),Rot3::Yaw (0.1).ypr()));
550  CHECK(assert_equal((Vector)Vector3(0.0,0.1,0.0),Rot3::Pitch(0.1).ypr()));
551  CHECK(assert_equal((Vector)Vector3(0.0,0.0,0.1),Rot3::Roll (0.1).ypr()));
552 
553  // Try RQ to recover calibration from 3*3 sub-block of projection matrix
554  Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0).finished();
555  Matrix A = K * R.matrix();
556  const auto [actualK2, actual2] = RQ(A);
557  CHECK(assert_equal(K, actualK2));
558  CHECK(assert_equal(expected, actual2, 1e-6));
559 }
560 
561 /* ************************************************************************* */
562 TEST( Rot3, expmapStability ) {
563  Vector w = Vector3(78e-9, 5e-8, 97e-7);
564  double theta = w.norm();
565  double theta2 = theta*theta;
566  Rot3 actualR = Rot3::Expmap(w);
567  Matrix W = (Matrix(3, 3) << 0.0, -w(2), w(1),
568  w(2), 0.0, -w(0),
569  -w(1), w(0), 0.0 ).finished();
570  Matrix W2 = W*W;
571  Matrix Rmat = I_3x3 + (1.0-theta2/6.0 + theta2*theta2/120.0
572  - theta2*theta2*theta2/5040.0)*W + (0.5 - theta2/24.0 + theta2*theta2/720.0)*W2 ;
573  Rot3 expectedR( Rmat );
574  CHECK(assert_equal(expectedR, actualR, 1e-10));
575 }
576 
577 /* ************************************************************************* */
578 TEST( Rot3, logmapStability ) {
579  Vector w = Vector3(1e-8, 0.0, 0.0);
580  Rot3 R = Rot3::Expmap(w);
581 // double tr = R.r1().x()+R.r2().y()+R.r3().z();
582 // std::cout.precision(5000);
583 // std::cout << "theta: " << w.norm() << std::endl;
584 // std::cout << "trace: " << tr << std::endl;
585 // R.print("R = ");
586  Vector actualw = Rot3::Logmap(R);
587  CHECK(assert_equal(w, actualw, 1e-15));
588 }
589 
590 /* ************************************************************************* */
592  // NOTE: This is also verifying the ability to convert Vector to Quaternion
593  Quaternion q1(0.710997408193224, 0.360544029310185, 0.594459869568306, 0.105395217842782);
594  Rot3 R1(0.271018623057411, 0.278786459830371, 0.921318086098018,
595  0.578529366719085, 0.717799701969298, -0.387385285854279,
596  -0.769319620053772, 0.637998195662053, 0.033250932803219);
597 
598  Quaternion q2(0.263360579192421, 0.571813128030932, 0.494678363680335,
599  0.599136268678053);
600  Rot3 R2(-0.207341903877828, 0.250149415542075, 0.945745528564780,
601  0.881304914479026, -0.371869043667957, 0.291573424846290,
602  0.424630407073532, 0.893945571198514, -0.143353873763946);
603 
604  // Check creating Rot3 from quaternion
605  EXPECT(assert_equal(R1, Rot3(q1)));
606  EXPECT(assert_equal(R1, Rot3::Quaternion(q1.w(), q1.x(), q1.y(), q1.z())));
607  EXPECT(assert_equal(R2, Rot3(q2)));
608  EXPECT(assert_equal(R2, Rot3::Quaternion(q2.w(), q2.x(), q2.y(), q2.z())));
609 
610  // Check converting Rot3 to quaterion
611  EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs())));
612  EXPECT(assert_equal(Vector(R2.toQuaternion().coeffs()), Vector(q2.coeffs())));
613 
614  // Check that quaternion and Rot3 represent the same rotation
615  Point3 p1(1.0, 2.0, 3.0);
616  Point3 p2(8.0, 7.0, 9.0);
617 
618  Point3 expected1 = R1*p1;
619  Point3 expected2 = R2*p2;
620 
621  Point3 actual1 = Point3(q1*p1);
622  Point3 actual2 = Point3(q2*p2);
623 
624  EXPECT(assert_equal(expected1, actual1));
625  EXPECT(assert_equal(expected2, actual2));
626 }
627 
628 /* ************************************************************************* */
629 TEST(Rot3, ConvertQuaternion) {
630  Eigen::Quaterniond eigenQuaternion;
631  eigenQuaternion.w() = 1.0;
632  eigenQuaternion.x() = 2.0;
633  eigenQuaternion.y() = 3.0;
634  eigenQuaternion.z() = 4.0;
635  EXPECT_DOUBLES_EQUAL(1, eigenQuaternion.w(), 1e-9);
636  EXPECT_DOUBLES_EQUAL(2, eigenQuaternion.x(), 1e-9);
637  EXPECT_DOUBLES_EQUAL(3, eigenQuaternion.y(), 1e-9);
638  EXPECT_DOUBLES_EQUAL(4, eigenQuaternion.z(), 1e-9);
639 
640  Rot3 R(eigenQuaternion);
641  EXPECT_DOUBLES_EQUAL(1, R.toQuaternion().w(), 1e-9);
642  EXPECT_DOUBLES_EQUAL(2, R.toQuaternion().x(), 1e-9);
643  EXPECT_DOUBLES_EQUAL(3, R.toQuaternion().y(), 1e-9);
644  EXPECT_DOUBLES_EQUAL(4, R.toQuaternion().z(), 1e-9);
645 }
646 
647 /* ************************************************************************* */
648 Matrix Cayley(const Matrix& A) {
649  Matrix::Index n = A.cols();
650  const Matrix I = Matrix::Identity(n,n);
651  return (I-A)*(I+A).inverse();
652 }
653 
654 TEST( Rot3, Cayley ) {
655  Matrix A = skewSymmetric(1,2,-3);
656  Matrix Q = Cayley(A);
657  EXPECT(assert_equal((Matrix)I_3x3, trans(Q)*Q));
659 }
660 
661 /* ************************************************************************* */
663 {
664  Rot3 R;
665  std::ostringstream os;
666  os << R;
667  string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]";
668  EXPECT(os.str() == expected);
669 }
670 
671 /* ************************************************************************* */
672 TEST( Rot3, slerp)
673 {
674  // A first simple test
675  Rot3 R1 = Rot3::Rz(1), R2 = Rot3::Rz(2), R3 = Rot3::Rz(1.5);
676  EXPECT(assert_equal(R1, R1.slerp(0.0,R2)));
677  EXPECT(assert_equal(R2, R1.slerp(1.0,R2)));
678  EXPECT(assert_equal(R3, R1.slerp(0.5,R2)));
679  // Make sure other can be *this
680  EXPECT(assert_equal(R1, R1.slerp(0.5,R1)));
681 }
682 
683 //******************************************************************************
684 namespace {
685 Rot3 id;
686 Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1));
687 Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2));
688 } // namespace
689 
690 //******************************************************************************
691 TEST(Rot3, Invariants) {
692  EXPECT(check_group_invariants(id, id));
693  EXPECT(check_group_invariants(id, T1));
694  EXPECT(check_group_invariants(T2, id));
695  EXPECT(check_group_invariants(T2, T1));
696  EXPECT(check_group_invariants(T1, T2));
697 
698  EXPECT(check_manifold_invariants(id, id));
699  EXPECT(check_manifold_invariants(id, T1));
700  EXPECT(check_manifold_invariants(T2, id));
701  EXPECT(check_manifold_invariants(T2, T1));
702  EXPECT(check_manifold_invariants(T1, T2));
703 }
704 
705 //******************************************************************************
706 TEST(Rot3, LieGroupDerivatives) {
712 }
713 
714 //******************************************************************************
715 TEST(Rot3, ChartDerivatives) {
716  if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) {
717  CHECK_CHART_DERIVATIVES(id, id);
722  }
723 }
724 
725 /* ************************************************************************* */
726 TEST(Rot3, ClosestTo) {
727  Matrix3 M;
728  M << 0.79067393, 0.6051136, -0.0930814, //
729  0.4155925, -0.64214347, -0.64324489, //
730  -0.44948549, 0.47046326, -0.75917576;
731 
732  Matrix expected(3, 3);
733  expected << 0.790687, 0.605096, -0.0931312, //
734  0.415746, -0.642355, -0.643844, //
735  -0.449411, 0.47036, -0.759468;
736 
737  auto actual = Rot3::ClosestTo(3*M);
738  EXPECT(assert_equal(expected, actual.matrix(), 1e-6));
739 }
740 
741 /* ************************************************************************* */
742 TEST(Rot3, axisAngle) {
743  Unit3 actualAxis;
744  double actualAngle;
745 
746 // not a lambda as otherwise we can't trace error easily
747 #define CHECK_AXIS_ANGLE(expectedAxis, expectedAngle, rotation) \
748  std::tie(actualAxis, actualAngle) = rotation.axisAngle(); \
749  EXPECT(assert_equal(expectedAxis, actualAxis, 1e-9)); \
750  EXPECT_DOUBLES_EQUAL(expectedAngle, actualAngle, 1e-9); \
751  EXPECT(assert_equal(rotation, Rot3::AxisAngle(expectedAxis, expectedAngle)))
752 
753  // CHECK R defined at top = Rot3::Rodrigues(0.1, 0.4, 0.2)
754  Vector3 omega(0.1, 0.4, 0.2);
755  Unit3 axis(omega), _axis(-omega);
756  CHECK_AXIS_ANGLE(axis, omega.norm(), R);
757 
758  // rotate by 90
759  CHECK_AXIS_ANGLE(Unit3(1, 0, 0), M_PI_2, Rot3::Ypr(0, 0, M_PI_2))
760  CHECK_AXIS_ANGLE(Unit3(0, 1, 0), M_PI_2, Rot3::Ypr(0, M_PI_2, 0))
761  CHECK_AXIS_ANGLE(Unit3(0, 0, 1), M_PI_2, Rot3::Ypr(M_PI_2, 0, 0))
762  CHECK_AXIS_ANGLE(axis, M_PI_2, Rot3::AxisAngle(axis, M_PI_2))
763 
764  // rotate by -90
765  CHECK_AXIS_ANGLE(Unit3(-1, 0, 0), M_PI_2, Rot3::Ypr(0, 0, -M_PI_2))
766  CHECK_AXIS_ANGLE(Unit3(0, -1, 0), M_PI_2, Rot3::Ypr(0, -M_PI_2, 0))
767  CHECK_AXIS_ANGLE(Unit3(0, 0, -1), M_PI_2, Rot3::Ypr(-M_PI_2, 0, 0))
768  CHECK_AXIS_ANGLE(_axis, M_PI_2, Rot3::AxisAngle(axis, -M_PI_2))
769 
770  // rotate by 270
771  const double theta270 = M_PI + M_PI / 2;
772  CHECK_AXIS_ANGLE(Unit3(-1, 0, 0), M_PI_2, Rot3::Ypr(0, 0, theta270))
773  CHECK_AXIS_ANGLE(Unit3(0, -1, 0), M_PI_2, Rot3::Ypr(0, theta270, 0))
774  CHECK_AXIS_ANGLE(Unit3(0, 0, -1), M_PI_2, Rot3::Ypr(theta270, 0, 0))
775  CHECK_AXIS_ANGLE(_axis, M_PI_2, Rot3::AxisAngle(axis, theta270))
776 
777  // rotate by -270
778  const double theta_270 = -(M_PI + M_PI / 2); // 90 (or -270) degrees
779  CHECK_AXIS_ANGLE(Unit3(1, 0, 0), M_PI_2, Rot3::Ypr(0, 0, theta_270))
780  CHECK_AXIS_ANGLE(Unit3(0, 1, 0), M_PI_2, Rot3::Ypr(0, theta_270, 0))
781  CHECK_AXIS_ANGLE(Unit3(0, 0, 1), M_PI_2, Rot3::Ypr(theta_270, 0, 0))
782  CHECK_AXIS_ANGLE(axis, M_PI_2, Rot3::AxisAngle(axis, theta_270))
783 
784  const double theta195 = 195 * M_PI / 180;
785  const double theta165 = 165 * M_PI / 180;
786 
788  CHECK_AXIS_ANGLE(Unit3(1, 0, 0), theta165, Rot3::Ypr(0, 0, theta165))
789  CHECK_AXIS_ANGLE(Unit3(0, 1, 0), theta165, Rot3::Ypr(0, theta165, 0))
790  CHECK_AXIS_ANGLE(Unit3(0, 0, 1), theta165, Rot3::Ypr(theta165, 0, 0))
791  CHECK_AXIS_ANGLE(axis, theta165, Rot3::AxisAngle(axis, theta165))
792 
793 
794  CHECK_AXIS_ANGLE(Unit3(-1, 0, 0), theta165, Rot3::Ypr(0, 0, theta195))
795  CHECK_AXIS_ANGLE(Unit3(0, -1, 0), theta165, Rot3::Ypr(0, theta195, 0))
796  CHECK_AXIS_ANGLE(Unit3(0, 0, -1), theta165, Rot3::Ypr(theta195, 0, 0))
797  CHECK_AXIS_ANGLE(_axis, theta165, Rot3::AxisAngle(axis, theta195))
798 }
799 
800 /* ************************************************************************* */
801 Rot3 RzRyRx_proxy(double const& a, double const& b, double const& c) {
802  return Rot3::RzRyRx(a, b, c);
803 }
804 
805 TEST(Rot3, RzRyRx_scalars_derivative) {
806  const auto x = 0.1, y = 0.4, z = 0.2;
807  const auto num_x = numericalDerivative31(RzRyRx_proxy, x, y, z);
808  const auto num_y = numericalDerivative32(RzRyRx_proxy, x, y, z);
809  const auto num_z = numericalDerivative33(RzRyRx_proxy, x, y, z);
810 
811  Vector3 act_x, act_y, act_z;
812  Rot3::RzRyRx(x, y, z, act_x, act_y, act_z);
813 
814  CHECK(assert_equal(num_x, act_x));
815  CHECK(assert_equal(num_y, act_y));
816  CHECK(assert_equal(num_z, act_z));
817 }
818 
819 /* ************************************************************************* */
820 Rot3 RzRyRx_proxy(Vector3 const& xyz) { return Rot3::RzRyRx(xyz); }
821 
822 TEST(Rot3, RzRyRx_vector_derivative) {
823  const auto xyz = Vector3{-0.3, 0.1, 0.7};
824  const auto num = numericalDerivative11(RzRyRx_proxy, xyz);
825 
826  Matrix3 act;
827  Rot3::RzRyRx(xyz, act);
828 
829  CHECK(assert_equal(num, act));
830 }
831 
832 /* ************************************************************************* */
833 Rot3 Ypr_proxy(double const& y, double const& p, double const& r) {
834  return Rot3::Ypr(y, p, r);
835 }
836 
837 TEST(Rot3, Ypr_derivative) {
838  const auto y = 0.7, p = -0.3, r = 0.1;
839  const auto num_y = numericalDerivative31(Ypr_proxy, y, p, r);
840  const auto num_p = numericalDerivative32(Ypr_proxy, y, p, r);
841  const auto num_r = numericalDerivative33(Ypr_proxy, y, p, r);
842 
843  Vector3 act_y, act_p, act_r;
844  Rot3::Ypr(y, p, r, act_y, act_p, act_r);
845 
846  CHECK(assert_equal(num_y, act_y));
847  CHECK(assert_equal(num_p, act_p));
848  CHECK(assert_equal(num_r, act_r));
849 }
850 
851 /* ************************************************************************* */
852 Vector3 RQ_proxy(Matrix3 const& R) {
853  const auto RQ_ypr = RQ(R);
854  return RQ_ypr.second;
855 }
856 
857 TEST(Rot3, RQ_derivative) {
858  using VecAndErr = std::pair<Vector3, double>;
859  std::vector<VecAndErr> test_xyz;
860  // Test zeros and a couple of random values
861  test_xyz.push_back(VecAndErr{{0, 0, 0}, error});
862  test_xyz.push_back(VecAndErr{{0, 0.5, -0.5}, error});
863  test_xyz.push_back(VecAndErr{{0.3, 0, 0.2}, error});
864  test_xyz.push_back(VecAndErr{{-0.6, 1.3, 0}, 1e-8});
865  test_xyz.push_back(VecAndErr{{1.0, 0.7, 0.8}, error});
866  test_xyz.push_back(VecAndErr{{3.0, 0.7, -0.6}, error});
867  test_xyz.push_back(VecAndErr{{M_PI / 2, 0, 0}, error});
868  test_xyz.push_back(VecAndErr{{0, 0, M_PI / 2}, error});
869 
870  // Test close to singularity
871  test_xyz.push_back(VecAndErr{{0, M_PI / 2 - 1e-1, 0}, 1e-7});
872  test_xyz.push_back(VecAndErr{{0, 3 * M_PI / 2 + 1e-1, 0}, 1e-7});
873  test_xyz.push_back(VecAndErr{{0, M_PI / 2 - 1.1e-2, 0}, 1e-4});
874  test_xyz.push_back(VecAndErr{{0, 3 * M_PI / 2 + 1.1e-2, 0}, 1e-4});
875 
876  for (auto const& vec_err : test_xyz) {
877  auto const& xyz = vec_err.first;
878 
879  const auto R = Rot3::RzRyRx(xyz).matrix();
880  const auto num = numericalDerivative11(RQ_proxy, R);
881  Matrix39 calc;
882  RQ(R, calc);
883 
884  const auto err = vec_err.second;
885  CHECK(assert_equal(num, calc, err));
886  }
887 }
888 
889 /* ************************************************************************* */
890 Vector3 xyz_proxy(Rot3 const& R) { return R.xyz(); }
891 
892 TEST(Rot3, xyz_derivative) {
893  const auto aa = Vector3{-0.6, 0.3, 0.2};
894  const auto R = Rot3::Expmap(aa);
895  const auto num = numericalDerivative11(xyz_proxy, R);
896  Matrix3 calc;
897  R.xyz(calc);
898 
899  CHECK(assert_equal(num, calc));
900 }
901 
902 /* ************************************************************************* */
903 Vector3 ypr_proxy(Rot3 const& R) { return R.ypr(); }
904 
905 TEST(Rot3, ypr_derivative) {
906  const auto aa = Vector3{0.1, -0.3, -0.2};
907  const auto R = Rot3::Expmap(aa);
908  const auto num = numericalDerivative11(ypr_proxy, R);
909  Matrix3 calc;
910  R.ypr(calc);
911 
912  CHECK(assert_equal(num, calc));
913 }
914 
915 /* ************************************************************************* */
916 Vector3 rpy_proxy(Rot3 const& R) { return R.rpy(); }
917 
918 TEST(Rot3, rpy_derivative) {
919  const auto aa = Vector3{1.2, 0.3, -0.9};
920  const auto R = Rot3::Expmap(aa);
921  const auto num = numericalDerivative11(rpy_proxy, R);
922  Matrix3 calc;
923  R.rpy(calc);
924 
925  CHECK(assert_equal(num, calc));
926 }
927 
928 /* ************************************************************************* */
929 double roll_proxy(Rot3 const& R) { return R.roll(); }
930 
931 TEST(Rot3, roll_derivative) {
932  const auto aa = Vector3{0.8, -0.8, 0.8};
933  const auto R = Rot3::Expmap(aa);
934  const auto num = numericalDerivative11(roll_proxy, R);
935  Matrix13 calc;
936  R.roll(calc);
937 
938  CHECK(assert_equal(num, calc));
939 }
940 
941 /* ************************************************************************* */
942 double pitch_proxy(Rot3 const& R) { return R.pitch(); }
943 
944 TEST(Rot3, pitch_derivative) {
945  const auto aa = Vector3{0.01, 0.1, 0.0};
946  const auto R = Rot3::Expmap(aa);
947  const auto num = numericalDerivative11(pitch_proxy, R);
948  Matrix13 calc;
949  R.pitch(calc);
950 
951  CHECK(assert_equal(num, calc));
952 }
953 
954 /* ************************************************************************* */
955 double yaw_proxy(Rot3 const& R) { return R.yaw(); }
956 
957 TEST(Rot3, yaw_derivative) {
958  const auto aa = Vector3{0.0, 0.1, 0.6};
959  const auto R = Rot3::Expmap(aa);
960  const auto num = numericalDerivative11(yaw_proxy, R);
961  Matrix13 calc;
962  R.yaw(calc);
963 
964  CHECK(assert_equal(num, calc));
965 }
966 
967 /* ************************************************************************* */
969  size_t degree = 1;
970  Rot3 R_w0; // Zero rotation
971  Rot3 R_w1 = Rot3::Ry(degree * M_PI / 180);
972 
973  Rot3 R_01, R_w2;
974  double actual, expected = 1.0;
975 
976  for (size_t i = 2; i < 360; ++i) {
977  R_01 = R_w0.between(R_w1);
978  R_w2 = R_w1 * R_01;
979  R_w0 = R_w1;
980  R_w1 = R_w2.normalized();
981  actual = R_w2.matrix().determinant();
982 
983  EXPECT_DOUBLES_EQUAL(expected, actual, 1e-7);
984  }
985 }
986 
987 /* ************************************************************************* */
988 TEST(Rot3, ExpmapChainRule) {
989  // Multiply with an arbitrary matrix and exponentiate
990  Matrix3 M;
991  M << 1, 2, 3, 4, 5, 6, 7, 8, 9;
992  auto g = [&](const Vector3& omega) {
993  return Rot3::Expmap(M*omega);
994  };
995 
996  // Test the derivatives at zero
997  const Matrix3 expected = numericalDerivative11<Rot3, Vector3>(g, Z_3x1);
998  EXPECT(assert_equal<Matrix3>(expected, M, 1e-5)); // SO3::ExpmapDerivative(Z_3x1) is identity
999 
1000  // Test the derivatives at another value
1001  const Vector3 delta{0.1,0.2,0.3};
1002  const Matrix3 expected2 = numericalDerivative11<Rot3, Vector3>(g, delta);
1003  EXPECT(assert_equal<Matrix3>(expected2, SO3::ExpmapDerivative(M*delta) * M, 1e-5));
1004 }
1005 
1006 /* ************************************************************************* */
1007 TEST(Rot3, expmapChainRule) {
1008  // Multiply an arbitrary rotation with exp(M*x)
1009  // Perhaps counter-intuitively, this has the same derivatives as above
1010  Matrix3 M;
1011  M << 1, 2, 3, 4, 5, 6, 7, 8, 9;
1012  const Rot3 R = Rot3::Expmap({1, 2, 3});
1013  auto g = [&](const Vector3& omega) {
1014  return R.expmap(M*omega);
1015  };
1016 
1017  // Test the derivatives at zero
1018  const Matrix3 expected = numericalDerivative11<Rot3, Vector3>(g, Z_3x1);
1019  EXPECT(assert_equal<Matrix3>(expected, M, 1e-5));
1020 
1021  // Test the derivatives at another value
1022  const Vector3 delta{0.1,0.2,0.3};
1023  const Matrix3 expected2 = numericalDerivative11<Rot3, Vector3>(g, delta);
1024  EXPECT(assert_equal<Matrix3>(expected2, SO3::ExpmapDerivative(M*delta) * M, 1e-5));
1025 }
1026 
1027 /* ************************************************************************* */
1028 int main() {
1029  TestResult tr;
1030  return TestRegistry::runAllTests(tr);
1031 }
1032 /* ************************************************************************* */
1033 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::Rot3::normalized
Rot3 normalized() const
Definition: Rot3M.cpp:111
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::numericalDerivative33
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:292
gtsam::Rot3::xyz
Vector3 xyz(OptionalJacobian< 3, 3 > H={}) const
Definition: Rot3.cpp:163
gtsam::Quaternion
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
Definition: geometry/Quaternion.h:190
gtsam::SO::inverse
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:199
pitch_proxy
double pitch_proxy(Rot3 const &R)
Definition: testRot3.cpp:942
Eigen::Quaternion::coeffs
EIGEN_DEVICE_FUNC Coefficients & coeffs()
Definition: 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h:340
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
gtsam::IsMatrixLieGroup
Definition: Lie.h:311
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
Testable.h
Concept check for values that can be used in unit tests.
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:47
gtsam::Rot3::rpy
Vector3 rpy(OptionalJacobian< 3, 3 > H={}) const
Definition: Rot3.cpp:194
TestHarness.h
gtsam.examples.SFMExample_bal.stream
stream
Definition: SFMExample_bal.py:24
r2
static const double r2
Definition: testSmartRangeFactor.cpp:32
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
AngularVelocity::AngularVelocity
AngularVelocity(const Eigen::MatrixBase< Derived > &v)
Definition: testRot3.cpp:359
trans
static char trans
Definition: blas_interface.hh:58
Cayley
Matrix Cayley(const Matrix &A)
Definition: testRot3.cpp:648
RQ_proxy
Vector3 RQ_proxy(Matrix3 const &R)
Definition: testRot3.cpp:852
xyz_proxy
Vector3 xyz_proxy(Rot3 const &R)
Definition: testRot3.cpp:890
simple::R3
static Rot3 R3
Definition: testInitializePose3.cpp:54
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::utils.numerical_derivative.retract
def retract(a, np.ndarray xi)
Definition: numerical_derivative.py:44
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
X
#define X
Definition: icosphere.cpp:20
Point3.h
3D Point
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
testLie.h
os
ofstream os("timeSchurFactors.csv")
gtsam::IsGroup
Definition: Group.h:42
r1
static const double r1
Definition: testSmartRangeFactor.cpp:32
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:381
gtsam::BCH
T BCH(const T &X, const T &Y)
AGC: bracket() only appears in Rot3 tests, should this be used elsewhere?
Definition: Lie.h:335
ceres::acos
Jet< T, N > acos(const Jet< T, N > &f)
Definition: jet.h:432
gtsam::Rot3::unrotate
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
screwPose2::expectedR
Rot2 expectedR
Definition: testPose2.cpp:170
determinant
void determinant(const MatrixType &m)
Definition: determinant.cpp:14
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
Rot3.h
3D rotation represented as a rotation matrix or quaternion
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
quaternion
void quaternion(void)
Definition: geo_quaternion.cpp:46
bracket
AngularVelocity bracket(const AngularVelocity &X, const AngularVelocity &Y)
Definition: testRot3.cpp:365
n
int n
Definition: BiCGSTAB_simple.cpp:1
epsilon
static double epsilon
Definition: testRot3.cpp:37
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
ceres::Matrix
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Definition: gtsam/3rdparty/ceres/eigen.h:42
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
gtsam::Rot3::ypr
Vector3 ypr(OptionalJacobian< 3, 3 > H={}) const
Definition: Rot3.cpp:186
CHECK_OMEGA
#define CHECK_OMEGA(X, Y, Z)
numericalDerivative.h
Some functions to compute numerical derivatives.
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
ypr_proxy
Vector3 ypr_proxy(Rot3 const &R)
Definition: testRot3.cpp:903
gtsam::Rot3::rotate
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Definition: Rot3M.cpp:148
I
#define I
Definition: main.h:112
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::numericalDerivative32
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:259
GTSAM_CONCEPT_LIE_INST
#define GTSAM_CONCEPT_LIE_INST(T)
Definition: Lie.h:410
gtsam::numericalDerivative31
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:226
zero
EIGEN_DONT_INLINE Scalar zero()
Definition: svd_common.h:296
gtsam::Rot3::toQuaternion
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:232
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
degree
const double degree
Definition: SimpleRotation.cpp:59
r3
static const double r3
Definition: testSmartRangeFactor.cpp:32
CHECK_LIE_GROUP_DERIVATIVES
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
gtsam::Rot3::yaw
double yaw(OptionalJacobian< 1, 3 > H={}) const
Definition: Rot3.cpp:221
gtsam::LieGroup::logmap
TangentVector logmap(const Class &g) const
Definition: Lie.h:84
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
M_PI_2
#define M_PI_2
Definition: mconf.h:118
RQ
static double RQ[8]
Definition: j0.c:171
AngularVelocity
Definition: testRot3.cpp:356
main
int main()
Definition: testRot3.cpp:1028
yaw_proxy
double yaw_proxy(Rot3 const &R)
Definition: testRot3.cpp:955
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
slow_but_correct_Rodrigues
Rot3 slow_but_correct_Rodrigues(const Vector &w)
Definition: testRot3.cpp:97
TEST
TEST(Rot3, Concept)
Definition: testRot3.cpp:40
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
K
#define K
Definition: igam.h:8
constructor
Definition: init.h:202
P
static Point3 P(0.2, 0.7, -2.0)
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
gtsam::testing::compose
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
roll_proxy
double roll_proxy(Rot3 const &R)
Definition: testRot3.cpp:929
std
Definition: BFloat16.h:88
origin
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
Definition: gnuplot_common_settings.hh:45
CHECK_OMEGA_ZERO
#define CHECK_OMEGA_ZERO(X, Y, Z)
p
float * p
Definition: Tutorial_Map_using.cpp:9
v2
Vector v2
Definition: testSerializationBase.cpp:39
AngularVelocity::AngularVelocity
AngularVelocity(double wx, double wy, double wz)
Definition: testRot3.cpp:362
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:218
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::testing::unrotate
P unrotate(const T &r, const P &pt)
Definition: lieProxies.h:50
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
R
static Rot3 R
Definition: testRot3.cpp:35
rpy_proxy
Vector3 rpy_proxy(Rot3 const &R)
Definition: testRot3.cpp:916
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
v3
Vector v3
Definition: testSerializationBase.cpp:40
gtsam::LieGroup::expmap
Class expmap(const TangentVector &v) const
Definition: Lie.h:78
M_PI
#define M_PI
Definition: mconf.h:117
RzRyRx_proxy
Rot3 RzRyRx_proxy(double const &a, double const &b, double const &c)
Definition: testRot3.cpp:801
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Rot3::roll
double roll(OptionalJacobian< 1, 3 > H={}) const
Definition: Rot3.cpp:197
Ypr_proxy
Rot3 Ypr_proxy(double const &y, double const &p, double const &r)
Definition: testRot3.cpp:833
lieProxies.h
Provides convenient mappings of common member functions for testing.
align_3::t
Point2 t(10, 10)
gtsam::Rot3::equals
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:100
CHECK_AXIS_ANGLE
#define CHECK_AXIS_ANGLE(expectedAxis, expectedAngle, rotation)
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
gtsam::Rot3::pitch
double pitch(OptionalJacobian< 1, 3 > H={}) const
Definition: Rot3.cpp:209
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:25
CHECK_CHART_DERIVATIVES
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
v1
Vector v1
Definition: testSerializationBase.cpp:38
ROT3_DEFAULT_COORDINATES_MODE
#define ROT3_DEFAULT_COORDINATES_MODE
Definition: Rot3.h:43
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:07:39