testPose3.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 
17 #include <gtsam/geometry/Pose3.h>
18 #include <gtsam/geometry/Pose2.h>
19 #include <gtsam/base/testLie.h>
20 #include <gtsam/base/lieProxies.h>
22 #include <gtsam/slam/expressions.h>
23 
24 
26 #include <cmath>
27 #include <functional>
28 
29 using namespace std;
30 using namespace gtsam;
31 using namespace std::placeholders;
32 
35 
36 static const Point3 P(0.2,0.7,-2);
37 static const Rot3 R = Rot3::Rodrigues(0.3,0,0);
38 static const Point3 P2(3.5,-8.2,4.2);
39 static const Pose3 T(R,P2);
40 static const Pose3 T2(Rot3::Rodrigues(0.3,0.2,0.1),P2);
41 static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3));
42 static const double tol=1e-5;
43 
44 //******************************************************************************
45 TEST(Pose3 , Concept) {
47  GTSAM_CONCEPT_ASSERT(IsManifold<Pose3 >);
49 }
50 
51 /* ************************************************************************* */
53 {
54  Pose3 pose2 = T3;
56  Pose3 origin;
58 }
59 
60 /* ************************************************************************* */
61 TEST( Pose3, constructors)
62 {
63  Pose3 expected(Rot3::Rodrigues(0,0,3),Point3(1,2,0));
64  Pose2 pose2(1,2,3);
66 }
67 
68 /* ************************************************************************* */
69 #ifndef GTSAM_POSE3_EXPMAP
70 TEST( Pose3, retract_first_order)
71 {
72  Pose3 id;
73  Vector v = Z_6x1;
74  v(0) = 0.3;
75  EXPECT(assert_equal(Pose3(R, Point3(0,0,0)), id.retract(v),1e-2));
76  v(3)=0.2;v(4)=0.7;v(5)=-2;
77  EXPECT(assert_equal(Pose3(R, P),id.retract(v),1e-2));
78 }
79 #endif
80 /* ************************************************************************* */
81 TEST( Pose3, retract_expmap)
82 {
83  Vector v = Z_6x1; v(0) = 0.3;
85  EXPECT(assert_equal(Pose3(R, Point3(0,0,0)), pose, 1e-2));
86  EXPECT(assert_equal(v,Pose3::Logmap(pose),1e-2));
87 }
88 
89 /* ************************************************************************* */
90 TEST( Pose3, expmap_a_full)
91 {
92  Pose3 id;
93  Vector v = Z_6x1;
94  v(0) = 0.3;
95  EXPECT(assert_equal(expmap_default<Pose3>(id, v), Pose3(R, Point3(0,0,0))));
96  v(3)=0.2;v(4)=0.394742;v(5)=-2.08998;
97  EXPECT(assert_equal(Pose3(R, P),expmap_default<Pose3>(id, v),1e-5));
98 }
99 
100 /* ************************************************************************* */
101 TEST( Pose3, expmap_a_full2)
102 {
103  Pose3 id;
104  Vector v = Z_6x1;
105  v(0) = 0.3;
106  EXPECT(assert_equal(expmap_default<Pose3>(id, v), Pose3(R, Point3(0,0,0))));
107  v(3)=0.2;v(4)=0.394742;v(5)=-2.08998;
108  EXPECT(assert_equal(Pose3(R, P),expmap_default<Pose3>(id, v),1e-5));
109 }
110 
111 /* ************************************************************************* */
112 TEST(Pose3, expmap_b)
113 {
114  Pose3 p1(Rot3(), Point3(100, 0, 0));
115  Pose3 p2 = p1.retract((Vector(6) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0).finished());
116  Pose3 expected(Rot3::Rodrigues(0.0, 0.0, 0.1), Point3(100.0, 0.0, 0.0));
118 }
119 
120 /* ************************************************************************* */
121 // test case for screw motion in the plane
122 namespace screwPose3 {
123  double a=0.3, c=cos(a), s=sin(a), w=0.3;
124  Vector xi = (Vector(6) << 0.0, 0.0, w, w, 0.0, 1.0).finished();
125  Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1);
126  Point3 expectedT(0.29552, 0.0446635, 1);
128 }
129 
130 /* ************************************************************************* */
131 // Checks correct exponential map (Expmap) with brute force matrix exponential
132 TEST(Pose3, expmap_c_full)
133 {
136 }
137 
138 /* ************************************************************************* */
139 // assert that T*exp(xi)*T^-1 is equal to exp(Ad_T(xi))
140 TEST(Pose3, Adjoint_full)
141 {
142  Pose3 expected = T * Pose3::Expmap(screwPose3::xi) * T.inverse();
143  Vector xiprime = T.Adjoint(screwPose3::xi);
144  EXPECT(assert_equal(expected, Pose3::Expmap(xiprime), 1e-6));
145 
146  Pose3 expected2 = T2 * Pose3::Expmap(screwPose3::xi) * T2.inverse();
147  Vector xiprime2 = T2.Adjoint(screwPose3::xi);
148  EXPECT(assert_equal(expected2, Pose3::Expmap(xiprime2), 1e-6));
149 
150  Pose3 expected3 = T3 * Pose3::Expmap(screwPose3::xi) * T3.inverse();
151  Vector xiprime3 = T3.Adjoint(screwPose3::xi);
152  EXPECT(assert_equal(expected3, Pose3::Expmap(xiprime3), 1e-6));
153 }
154 
155 /* ************************************************************************* */
156 // Check Adjoint numerical derivatives
157 TEST(Pose3, Adjoint_jacobians)
158 {
159  Vector6 xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
160 
161  // Check evaluation sanity check
162  EQUALITY(static_cast<gtsam::Vector>(T.AdjointMap() * xi), T.Adjoint(xi));
163  EQUALITY(static_cast<gtsam::Vector>(T2.AdjointMap() * xi), T2.Adjoint(xi));
164  EQUALITY(static_cast<gtsam::Vector>(T3.AdjointMap() * xi), T3.Adjoint(xi));
165 
166  // Check jacobians
167  Matrix6 actualH1, actualH2, expectedH1, expectedH2;
168  std::function<Vector6(const Pose3&, const Vector6&)> Adjoint_proxy =
169  [&](const Pose3& T, const Vector6& xi) { return T.Adjoint(xi); };
170 
171  T.Adjoint(xi, actualH1, actualH2);
172  expectedH1 = numericalDerivative21(Adjoint_proxy, T, xi);
173  expectedH2 = numericalDerivative22(Adjoint_proxy, T, xi);
174  EXPECT(assert_equal(expectedH1, actualH1));
175  EXPECT(assert_equal(expectedH2, actualH2));
176 
177  T2.Adjoint(xi, actualH1, actualH2);
178  expectedH1 = numericalDerivative21(Adjoint_proxy, T2, xi);
179  expectedH2 = numericalDerivative22(Adjoint_proxy, T2, xi);
180  EXPECT(assert_equal(expectedH1, actualH1));
181  EXPECT(assert_equal(expectedH2, actualH2));
182 
183  T3.Adjoint(xi, actualH1, actualH2);
184  expectedH1 = numericalDerivative21(Adjoint_proxy, T3, xi);
185  expectedH2 = numericalDerivative22(Adjoint_proxy, T3, xi);
186  EXPECT(assert_equal(expectedH1, actualH1));
187  EXPECT(assert_equal(expectedH2, actualH2));
188 }
189 
190 /* ************************************************************************* */
191 // Check AdjointTranspose and jacobians
192 TEST(Pose3, AdjointTranspose)
193 {
194  Vector6 xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
195 
196  // Check evaluation
197  EQUALITY(static_cast<Vector>(T.AdjointMap().transpose() * xi),
198  T.AdjointTranspose(xi));
199  EQUALITY(static_cast<Vector>(T2.AdjointMap().transpose() * xi),
201  EQUALITY(static_cast<Vector>(T3.AdjointMap().transpose() * xi),
203 
204  // Check jacobians
205  Matrix6 actualH1, actualH2, expectedH1, expectedH2;
206  std::function<Vector6(const Pose3&, const Vector6&)> AdjointTranspose_proxy =
207  [&](const Pose3& T, const Vector6& xi) {
208  return T.AdjointTranspose(xi);
209  };
210 
211  T.AdjointTranspose(xi, actualH1, actualH2);
212  expectedH1 = numericalDerivative21(AdjointTranspose_proxy, T, xi);
213  expectedH2 = numericalDerivative22(AdjointTranspose_proxy, T, xi);
214  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
215  EXPECT(assert_equal(expectedH2, actualH2));
216 
217  T2.AdjointTranspose(xi, actualH1, actualH2);
218  expectedH1 = numericalDerivative21(AdjointTranspose_proxy, T2, xi);
219  expectedH2 = numericalDerivative22(AdjointTranspose_proxy, T2, xi);
220  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
221  EXPECT(assert_equal(expectedH2, actualH2));
222 
223  T3.AdjointTranspose(xi, actualH1, actualH2);
224  expectedH1 = numericalDerivative21(AdjointTranspose_proxy, T3, xi);
225  expectedH2 = numericalDerivative22(AdjointTranspose_proxy, T3, xi);
226  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
227  EXPECT(assert_equal(expectedH2, actualH2));
228 }
229 
230 /* ************************************************************************* */
231 TEST(Pose3, HatAndVee) {
232  // Create a few test vectors
233  Vector6 v1(1, 2, 3, 4, 5, 6);
234  Vector6 v2(0.1, -0.5, 1.0, -1.0, 0.5, 2.0);
235  Vector6 v3(0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
236 
237  // Test that Vee(Hat(v)) == v for various inputs
238  EXPECT(assert_equal(v1, Pose3::Vee(Pose3::Hat(v1))));
239  EXPECT(assert_equal(v2, Pose3::Vee(Pose3::Hat(v2))));
240  EXPECT(assert_equal(v3, Pose3::Vee(Pose3::Hat(v3))));
241 
242  // Check the structure of the Lie Algebra element
243  Matrix4 expected;
244  expected << 0, -3, 2, 4,
245  3, 0, -1, 5,
246  -2, 1, 0, 6,
247  0, 0, 0, 0;
248 
249  EXPECT(assert_equal(expected, Pose3::Hat(v1)));
250 }
251 
252 /* ************************************************************************* */
253 // assert that T*Hat(xi)*T^-1 is equal to Hat(Ad_T(xi))
254 TEST(Pose3, Adjoint_hat)
255 {
256  Matrix4 expected = T.matrix() * Pose3::Hat(screwPose3::xi) * T.matrix().inverse();
257  Matrix4 xiprime = Pose3::Hat(T.Adjoint(screwPose3::xi));
258  EXPECT(assert_equal(expected, xiprime, 1e-6));
259 
260  Matrix4 expected2 = T2.matrix() * Pose3::Hat(screwPose3::xi) * T2.matrix().inverse();
261  Matrix4 xiprime2 = Pose3::Hat(T2.Adjoint(screwPose3::xi));
262  EXPECT(assert_equal(expected2, xiprime2, 1e-6));
263 
264  Matrix4 expected3 = T3.matrix() * Pose3::Hat(screwPose3::xi) * T3.matrix().inverse();
265  Matrix4 xiprime3 = Pose3::Hat(T3.Adjoint(screwPose3::xi));
266  EXPECT(assert_equal(expected3, xiprime3, 1e-6));
267 }
268 
269 /* ************************************************************************* */
272  Vector w = xi.head(3);
273  Vector v = xi.tail(3);
274  double t = w.norm();
275  if (t < 1e-5)
276  return Pose3(Rot3(), Point3(v));
277  else {
278  Matrix W = skewSymmetric(w/t);
279  Matrix A = I_3x3 + ((1 - cos(t)) / t) * W + ((t - sin(t)) / t) * (W * W);
280  return Pose3(Rot3::Expmap (w), Point3(A * v));
281  }
282 }
283 
284 /* ************************************************************************* */
285 TEST(Pose3, expmaps_galore_full)
286 {
287  Vector xi; Pose3 actual;
288  xi = (Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
289  actual = Pose3::Expmap(xi);
290  EXPECT(assert_equal(expm<Pose3>(xi), actual,1e-6));
291  EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-6));
292  EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-6));
293 
294  xi = (Vector(6) << 0.1, -0.2, 0.3, -0.4, 0.5, -0.6).finished();
295  for (double theta=1.0;0.3*theta<=M_PI;theta*=2) {
296  Vector txi = xi*theta;
297  actual = Pose3::Expmap(txi);
298  EXPECT(assert_equal(expm<Pose3>(txi,30), actual,1e-6));
299  EXPECT(assert_equal(Agrawal06iros(txi), actual,1e-6));
300  Vector log = Pose3::Logmap(actual);
301  EXPECT(assert_equal(actual, Pose3::Expmap(log),1e-6));
302  EXPECT(assert_equal(txi,log,1e-6)); // not true once wraps
303  }
304 
305  // Works with large v as well, but expm needs 10 iterations!
306  xi = (Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished();
307  actual = Pose3::Expmap(xi);
308  EXPECT(assert_equal(expm<Pose3>(xi,10), actual,1e-5));
309  EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-9));
310  EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-9));
311 }
312 
313 /* ************************************************************************* */
314 // Check translation and its pushforward
316  Matrix actualH;
317  EXPECT(assert_equal(Point3(3.5, -8.2, 4.2), T.translation(actualH), 1e-8));
318 
319  std::function<Point3(const Pose3&)> f = [](const Pose3& T) { return T.translation(); };
320  Matrix numericalH = numericalDerivative11<Point3, Pose3>(f, T);
321  EXPECT(assert_equal(numericalH, actualH, 1e-6));
322 }
323 
324 /* ************************************************************************* */
325 // Check rotation and its pushforward
327  Matrix actualH;
328  EXPECT(assert_equal(R, T.rotation(actualH), 1e-8));
329 
330  std::function<Rot3(const Pose3&)> f = [](const Pose3& T) { return T.rotation(); };
331  Matrix numericalH = numericalDerivative11<Rot3, Pose3>(f, T);
332  EXPECT(assert_equal(numericalH, actualH, 1e-6));
333 }
334 
335 /* ************************************************************************* */
336 TEST(Pose3, Adjoint_compose_full)
337 {
338  // To debug derivatives of compose, assert that
339  // T1*T2*exp(Adjoint(inv(T2),x) = T1*exp(x)*T2
340  const Pose3& T1 = T;
341  Vector x = (Vector(6) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8).finished();
343  Vector y = T2.inverse().Adjoint(x);
344  Pose3 actual = T1 * T2 * Pose3::Expmap(y);
345  EXPECT(assert_equal(expected, actual, 1e-6));
346 }
347 
348 /* ************************************************************************* */
349 // Check compose and its pushforward
350 // NOTE: testing::compose<Pose3>(t1,t2) = t1.compose(t2) (see lieProxies.h)
352 {
353  Matrix actual = (T2*T2).matrix();
355  EXPECT(assert_equal(actual,expected,1e-8));
356 
357  Matrix actualDcompose1, actualDcompose2;
358  T2.compose(T2, actualDcompose1, actualDcompose2);
359 
360  Matrix numericalH1 = numericalDerivative21(testing::compose<Pose3>, T2, T2);
361  EXPECT(assert_equal(numericalH1,actualDcompose1,5e-3));
362  EXPECT(assert_equal(T2.inverse().AdjointMap(),actualDcompose1,5e-3));
363 
364  Matrix numericalH2 = numericalDerivative22(testing::compose<Pose3>, T2, T2);
365  EXPECT(assert_equal(numericalH2,actualDcompose2,1e-4));
366 }
367 
368 /* ************************************************************************* */
369 // Check compose and its pushforward, another case
370 TEST( Pose3, compose2 )
371 {
372  const Pose3& T1 = T;
373  Matrix actual = (T1*T2).matrix();
375  EXPECT(assert_equal(actual,expected,1e-8));
376 
377  Matrix actualDcompose1, actualDcompose2;
378  T1.compose(T2, actualDcompose1, actualDcompose2);
379 
380  Matrix numericalH1 = numericalDerivative21(testing::compose<Pose3>, T1, T2);
381  EXPECT(assert_equal(numericalH1,actualDcompose1,5e-3));
382  EXPECT(assert_equal(T2.inverse().AdjointMap(),actualDcompose1,5e-3));
383 
384  Matrix numericalH2 = numericalDerivative22(testing::compose<Pose3>, T1, T2);
385  EXPECT(assert_equal(numericalH2,actualDcompose2,1e-5));
386 }
387 
388 /* ************************************************************************* */
390 {
391  Matrix actualDinverse;
392  Matrix actual = T.inverse(actualDinverse).matrix();
393  Matrix expected = T.matrix().inverse();
394  EXPECT(assert_equal(actual,expected,1e-8));
395 
396  Matrix numericalH = numericalDerivative11(testing::inverse<Pose3>, T);
397  EXPECT(assert_equal(numericalH,actualDinverse,5e-3));
398  EXPECT(assert_equal(-T.AdjointMap(),actualDinverse,5e-3));
399 }
400 
401 /* ************************************************************************* */
402 TEST( Pose3, inverseDerivatives2)
403 {
404  Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
405  Point3 t(3.5,-8.2,4.2);
406  Pose3 T(R,t);
407 
408  Matrix numericalH = numericalDerivative11(testing::inverse<Pose3>, T);
409  Matrix actualDinverse;
410  T.inverse(actualDinverse);
411  EXPECT(assert_equal(numericalH,actualDinverse,5e-3));
412  EXPECT(assert_equal(-T.AdjointMap(),actualDinverse,5e-3));
413 }
414 
415 /* ************************************************************************* */
416 TEST( Pose3, compose_inverse)
417 {
418  Matrix actual = (T*T.inverse()).matrix();
419  Matrix expected = I_4x4;
420  EXPECT(assert_equal(actual,expected,1e-8));
421 }
422 
423 /* ************************************************************************* */
425  return pose.transformFrom(point);
426 }
427 TEST(Pose3, Dtransform_from1_a) {
428  Matrix actualDtransform_from1;
429  T.transformFrom(P, actualDtransform_from1, {});
431  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
432 }
433 
434 TEST(Pose3, Dtransform_from1_b) {
435  Pose3 origin;
436  Matrix actualDtransform_from1;
437  origin.transformFrom(P, actualDtransform_from1, {});
439  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
440 }
441 
442 TEST(Pose3, Dtransform_from1_c) {
443  Point3 origin(0, 0, 0);
444  Pose3 T0(R, origin);
445  Matrix actualDtransform_from1;
446  T0.transformFrom(P, actualDtransform_from1, {});
447  Matrix numerical = numericalDerivative21(transformFrom_, T0, P);
448  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
449 }
450 
451 TEST(Pose3, Dtransform_from1_d) {
452  Rot3 I;
453  Point3 t0(100, 0, 0);
454  Pose3 T0(I, t0);
455  Matrix actualDtransform_from1;
456  T0.transformFrom(P, actualDtransform_from1, {});
457  // print(computed, "Dtransform_from1_d computed:");
458  Matrix numerical = numericalDerivative21(transformFrom_, T0, P);
459  // print(numerical, "Dtransform_from1_d numerical:");
460  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
461 }
462 
463 /* ************************************************************************* */
464 TEST(Pose3, Dtransform_from2) {
465  Matrix actualDtransform_from2;
466  T.transformFrom(P, {}, actualDtransform_from2);
468  EXPECT(assert_equal(numerical, actualDtransform_from2, 1e-8));
469 }
470 
471 /* ************************************************************************* */
473  return pose.transformTo(point);
474 }
475 TEST(Pose3, Dtransform_to1) {
476  Matrix computed;
477  T.transformTo(P, computed, {});
479  EXPECT(assert_equal(numerical, computed, 1e-8));
480 }
481 
482 /* ************************************************************************* */
483 TEST(Pose3, Dtransform_to2) {
484  Matrix computed;
485  T.transformTo(P, {}, computed);
487  EXPECT(assert_equal(numerical, computed, 1e-8));
488 }
489 
490 /* ************************************************************************* */
491 TEST(Pose3, transform_to_with_derivatives) {
492  Matrix actH1, actH2;
493  T.transformTo(P, actH1, actH2);
496  EXPECT(assert_equal(expH1, actH1, 1e-8));
497  EXPECT(assert_equal(expH2, actH2, 1e-8));
498 }
499 
500 /* ************************************************************************* */
501 TEST(Pose3, transform_from_with_derivatives) {
502  Matrix actH1, actH2;
503  T.transformFrom(P, actH1, actH2);
506  EXPECT(assert_equal(expH1, actH1, 1e-8));
507  EXPECT(assert_equal(expH2, actH2, 1e-8));
508 }
509 
510 /* ************************************************************************* */
511 TEST(Pose3, transform_to_translate) {
512  Point3 actual =
513  Pose3(Rot3(), Point3(1, 2, 3)).transformTo(Point3(10., 20., 30.));
514  Point3 expected(9., 18., 27.);
515  EXPECT(assert_equal(expected, actual));
516 }
517 
518 /* ************************************************************************* */
519 TEST(Pose3, transform_to_rotate) {
520  Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(0, 0, 0));
521  Point3 actual = transform.transformTo(Point3(2, 1, 10));
522  Point3 expected(-1, 2, 10);
523  EXPECT(assert_equal(expected, actual, 0.001));
524 }
525 
526 /* ************************************************************************* */
527 // Check transformPoseFrom and its pushforward
528 Pose3 transformPoseFrom_(const Pose3& wTa, const Pose3& aTb) {
529  return wTa.transformPoseFrom(aTb);
530 }
531 
532 TEST(Pose3, transformPoseFrom)
533 {
534  Matrix actual = (T2*T2).matrix();
536  EXPECT(assert_equal(actual, expected, 1e-8));
537 
538  Matrix H1, H2;
539  T2.transformPoseFrom(T2, H1, H2);
540 
542  EXPECT(assert_equal(numericalH1, H1, 5e-3));
543  EXPECT(assert_equal(T2.inverse().AdjointMap(), H1, 5e-3));
544 
546  EXPECT(assert_equal(numericalH2, H2, 1e-4));
547 }
548 
549 /* ************************************************************************* */
551  Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(2, 4, 0));
552  Point3 actual = transform.transformTo(Point3(3, 2, 10));
553  Point3 expected(2, 1, 10);
554  EXPECT(assert_equal(expected, actual, 0.001));
555 }
556 
558  return pose.transformPoseTo(pose2);
559 }
560 
561 /* ************************************************************************* */
563  Pose3 origin = T.transformPoseTo(T);
565 }
566 
567 /* ************************************************************************* */
568 TEST(Pose3, transformPoseTo_with_derivatives) {
569  Matrix actH1, actH2;
570  Pose3 res = T.transformPoseTo(T2, actH1, actH2);
571  EXPECT(assert_equal(res, T.inverse().compose(T2)));
572 
575  EXPECT(assert_equal(expH1, actH1, 1e-8));
576  EXPECT(assert_equal(expH2, actH2, 1e-8));
577 }
578 
579 /* ************************************************************************* */
580 TEST(Pose3, transformPoseTo_with_derivatives2) {
581  Matrix actH1, actH2;
582  Pose3 res = T.transformPoseTo(T3, actH1, actH2);
583  EXPECT(assert_equal(res, T.inverse().compose(T3)));
584 
587  EXPECT(assert_equal(expH1, actH1, 1e-8));
588  EXPECT(assert_equal(expH2, actH2, 1e-8));
589 }
590 
591 /* ************************************************************************* */
593  Point3 actual = T3.transformFrom(Point3(0, 0, 0));
594  Point3 expected = Point3(1., 2., 3.);
595  EXPECT(assert_equal(expected, actual));
596 }
597 
598 /* ************************************************************************* */
599 TEST(Pose3, transform_roundtrip) {
600  Point3 actual = T3.transformFrom(T3.transformTo(Point3(12., -0.11, 7.0)));
601  Point3 expected(12., -0.11, 7.0);
602  EXPECT(assert_equal(expected, actual));
603 }
604 
605 /* ************************************************************************* */
606 TEST(Pose3, Retract_LocalCoordinates)
607 {
608  Vector6 d;
609  d << 1,2,3,4,5,6; d/=10;
610  const Rot3 R = Rot3::Retract(d.head<3>());
611  Pose3 t = Pose3::Retract(d);
612  EXPECT(assert_equal(d, Pose3::LocalCoordinates(t)));
613 }
614 /* ************************************************************************* */
615 TEST(Pose3, retract_localCoordinates)
616 {
617  Vector6 d12;
618  d12 << 1,2,3,4,5,6; d12/=10;
619  Pose3 t1 = T, t2 = t1.retract(d12);
620  EXPECT(assert_equal(d12, t1.localCoordinates(t2)));
621 }
622 /* ************************************************************************* */
623 TEST(Pose3, expmap_logmap)
624 {
625  Vector d12 = Vector6::Constant(0.1);
626  Pose3 t1 = T, t2 = t1.expmap(d12);
627  EXPECT(assert_equal(d12, t1.logmap(t2)));
628 }
629 
630 /* ************************************************************************* */
631 TEST(Pose3, retract_localCoordinates2)
632 {
633  Pose3 t1 = T;
634  Pose3 t2 = T3;
635  Pose3 origin;
636  Vector d12 = t1.localCoordinates(t2);
637  EXPECT(assert_equal(t2, t1.retract(d12)));
638  Vector d21 = t2.localCoordinates(t1);
639  EXPECT(assert_equal(t1, t2.retract(d21)));
640  // TODO(hayk): This currently fails!
641  // EXPECT(assert_equal(d12, -d21));
642 }
643 /* ************************************************************************* */
644 TEST(Pose3, manifold_expmap)
645 {
646  Pose3 t1 = T;
647  Pose3 t2 = T3;
648  Pose3 origin;
649  Vector d12 = t1.logmap(t2);
650  EXPECT(assert_equal(t2, t1.expmap(d12)));
651  Vector d21 = t2.logmap(t1);
652  EXPECT(assert_equal(t1, t2.expmap(d21)));
653 
654  // Check that log(t1,t2)=-log(t2,t1)
655  EXPECT(assert_equal(d12,-d21));
656 }
657 
658 /* ************************************************************************* */
659 TEST(Pose3, subgroups)
660 {
661  // Frank - Below only works for correct "Agrawal06iros style expmap
662  // lines in canonical coordinates correspond to Abelian subgroups in SE(3)
663  Vector d = (Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
664  // exp(-d)=inverse(exp(d))
666  // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d)
667  Pose3 T2 = Pose3::Expmap(2*d);
668  Pose3 T3 = Pose3::Expmap(3*d);
669  Pose3 T5 = Pose3::Expmap(5*d);
672 }
673 
674 /* ************************************************************************* */
676 {
677  Pose3 expected = T2.inverse() * T3;
678  Matrix actualDBetween1,actualDBetween2;
679  Pose3 actual = T2.between(T3, actualDBetween1,actualDBetween2);
680  EXPECT(assert_equal(expected,actual));
681 
682  Matrix numericalH1 = numericalDerivative21(testing::between<Pose3> , T2, T3);
683  EXPECT(assert_equal(numericalH1,actualDBetween1,5e-3));
684 
685  Matrix numericalH2 = numericalDerivative22(testing::between<Pose3> , T2, T3);
686  EXPECT(assert_equal(numericalH2,actualDBetween2,1e-5));
687 }
688 
689 /* ************************************************************************* */
690 // some shared test values - pulled from equivalent test in Pose2
691 Point3 l1(1, 0, 0), l2(1, 1, 0), l3(2, 2, 0), l4(1, 4,-4);
692 Pose3 x1, x2(Rot3::Ypr(0.0, 0.0, 0.0), l2), x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2);
693 Pose3
694  xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)),
695  xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)),
696  xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)),
697  xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4));
698 
699 /* ************************************************************************* */
700 double range_proxy(const Pose3& pose, const Point3& point) {
701  return pose.range(point);
702 }
704 {
705  Matrix expectedH1, actualH1, expectedH2, actualH2;
706 
707  // establish range is indeed zero
709 
710  // establish range is indeed sqrt2
711  EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(l2),1e-9);
712 
713  // Another pair
714  double actual23 = x2.range(l3, actualH1, actualH2);
715  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
716 
717  // Check numerical derivatives
718  expectedH1 = numericalDerivative21(range_proxy, x2, l3);
719  expectedH2 = numericalDerivative22(range_proxy, x2, l3);
720  EXPECT(assert_equal(expectedH1,actualH1));
721  EXPECT(assert_equal(expectedH2,actualH2));
722 
723  // Another test
724  double actual34 = x3.range(l4, actualH1, actualH2);
725  EXPECT_DOUBLES_EQUAL(5,actual34,1e-9);
726 
727  // Check numerical derivatives
728  expectedH1 = numericalDerivative21(range_proxy, x3, l4);
729  expectedH2 = numericalDerivative22(range_proxy, x3, l4);
730  EXPECT(assert_equal(expectedH1,actualH1));
731  EXPECT(assert_equal(expectedH2,actualH2));
732 }
733 
734 /* ************************************************************************* */
735 double range_pose_proxy(const Pose3& pose, const Pose3& point) {
736  return pose.range(point);
737 }
738 TEST( Pose3, range_pose )
739 {
740  Matrix expectedH1, actualH1, expectedH2, actualH2;
741 
742  // establish range is indeed zero
744 
745  // establish range is indeed sqrt2
747 
748  // Another pair
749  double actual23 = x2.range(xl3, actualH1, actualH2);
750  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
751 
752  // Check numerical derivatives
755  EXPECT(assert_equal(expectedH1,actualH1));
756  EXPECT(assert_equal(expectedH2,actualH2));
757 
758  // Another test
759  double actual34 = x3.range(xl4, actualH1, actualH2);
760  EXPECT_DOUBLES_EQUAL(5,actual34,1e-9);
761 
762  // Check numerical derivatives
765  EXPECT(assert_equal(expectedH1,actualH1));
766  EXPECT(assert_equal(expectedH2,actualH2));
767 }
768 
769 /* ************************************************************************* */
771  return pose.bearing(point);
772 }
774  Matrix expectedH1, actualH1, expectedH2, actualH2;
775  EXPECT(assert_equal(Unit3(1, 0, 0), x1.bearing(l1, actualH1, actualH2), 1e-9));
776 
777  // Check numerical derivatives
778  expectedH1 = numericalDerivative21(bearing_proxy, x1, l1);
779  expectedH2 = numericalDerivative22(bearing_proxy, x1, l1);
780  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
781  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
782 }
783 
784 TEST(Pose3, Bearing2) {
785  Matrix expectedH1, actualH1, expectedH2, actualH2;
786  EXPECT(assert_equal(Unit3(0,0.6,-0.8), x2.bearing(l4, actualH1, actualH2), 1e-9));
787 
788  // Check numerical derivatives
789  expectedH1 = numericalDerivative21(bearing_proxy, x2, l4);
790  expectedH2 = numericalDerivative22(bearing_proxy, x2, l4);
791  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
792  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
793 }
794 
795 TEST(Pose3, PoseToPoseBearing) {
796  Matrix expectedH1, actualH1, expectedH2, actualH2, H2block;
797  EXPECT(assert_equal(Unit3(0,1,0), xl1.bearing(xl2, actualH1, actualH2), 1e-9));
798 
799  // Check numerical derivatives
800  std::function<Unit3(const Pose3&, const Pose3&)> f = [](const Pose3& a, const Pose3& b) { return a.bearing(b); };
801  expectedH1 = numericalDerivative21(f, xl1, xl2);
802  expectedH2 = numericalDerivative22(f, xl1, xl2);
803  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
804  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
805 }
806 
807 /* ************************************************************************* */
808 TEST( Pose3, unicycle )
809 {
810  // velocity in X should be X in inertial frame, rather than global frame
811  Vector x_step = Vector::Unit(6,3)*1.0;
812  EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), l1), expmap_default<Pose3>(x1, x_step), tol));
813  EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), Point3(2,1,0)), expmap_default<Pose3>(x2, x_step), tol));
814  EXPECT(assert_equal(Pose3(Rot3::Ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default<Pose3>(x3, sqrt(2.0) * x_step), tol));
815 }
816 
817 /* ************************************************************************* */
818 TEST( Pose3, adjointMap) {
819  Matrix res = Pose3::adjointMap(screwPose3::xi);
823  expected << wh, Z_3x3, vh, wh;
825 }
826 
827 /* ************************************************************************* */
828 TEST(Pose3, Align1) {
829  Pose3 expected(Rot3(), Point3(10,10,0));
830 
831  Point3Pair ab1(Point3(10,10,0), Point3(0,0,0));
832  Point3Pair ab2(Point3(30,20,0), Point3(20,10,0));
833  Point3Pair ab3(Point3(20,30,0), Point3(10,20,0));
834  const vector<Point3Pair> correspondences{ab1, ab2, ab3};
835 
836  std::optional<Pose3> actual = Pose3::Align(correspondences);
837  EXPECT(assert_equal(expected, *actual));
838 }
839 
840 /* ************************************************************************* */
841 TEST(Pose3, Align2) {
842  Point3 t(20,10,5);
843  Rot3 R = Rot3::RzRyRx(0.3, 0.2, 0.1);
844  Pose3 expected(R, t);
845 
846  Point3 p1(0,0,1), p2(10,0,2), p3(20,-10,30);
848  q2 = expected.transformFrom(p2),
849  q3 = expected.transformFrom(p3);
850  const Point3Pair ab1{q1, p1}, ab2{q2, p2}, ab3{q3, p3};
851  const vector<Point3Pair> correspondences{ab1, ab2, ab3};
852 
853  std::optional<Pose3> actual = Pose3::Align(correspondences);
854  EXPECT(assert_equal(expected, *actual, 1e-5));
855 }
856 
857 /* ************************************************************************* */
858 TEST(Pose3, ExpmapDerivative) {
859  // Iserles05an (Lie-group Methods) says:
860  // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t)
861  // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t)
862  // where A(t): T -> se(3) is a trajectory in the tangent space of SE(3)
863  // and dexp[A] is a linear map from 4*4 to 4*4 derivatives of se(3)
864  // Hence, the above matrix equation is typed: 4*4 = SE(3) * linear_map(4*4)
865 
866  // In GTSAM, we don't work with the Lie-algebra elements A directly, but with 6-vectors.
867  // xi is easy: d Expmap(xi(t)) / dt = ExmapDerivative[xi(t)] * xi'(t)
868 
869  // Let's verify the above formula.
870 
871  auto xi = [](double t) {
872  Vector6 v;
873  v << 2 * t, sin(t), 4 * t * t, 2 * t, sin(t), 4 * t * t;
874  return v;
875  };
876  auto xi_dot = [](double t) {
877  Vector6 v;
878  v << 2, cos(t), 8 * t, 2, cos(t), 8 * t;
879  return v;
880  };
881 
882  // We define a function T
883  auto T = [xi](double t) { return Pose3::Expmap(xi(t)); };
884 
885  for (double t = -2.0; t < 2.0; t += 0.3) {
886  const Matrix expected = numericalDerivative11<Pose3, double>(T, t);
887  const Matrix actual = Pose3::ExpmapDerivative(xi(t)) * xi_dot(t);
888  CHECK(assert_equal(expected, actual, 1e-7));
889  }
890 }
891 
892 //******************************************************************************
893 namespace test_cases {
894 std::vector<Vector3> small{{0, 0, 0}, //
895  {1e-5, 0, 0}, {0, 1e-5, 0}, {0, 0, 1e-5}, //,
896  {1e-4, 0, 0}, {0, 1e-4, 0}, {0, 0, 1e-4}};
897 std::vector<Vector3> large{{0, 0, 0}, {1, 0, 0}, {0, 1, 0},
898  {0, 0, 1}, {.1, .2, .3}, {1, -2, 3}};
899 auto omegas = [](bool nearZero) { return nearZero ? small : large; };
900 std::vector<Vector3> vs{{1, 0, 0}, {0, 1, 0}, {0, 0, 1},
901  {.4, .3, .2}, {4, 5, 6}, {-10, -20, 30}};
902 } // namespace test_cases
903 
904 //******************************************************************************
905 TEST(Pose3, ExpmapDerivatives) {
906  for (bool nearZero : {true, false}) {
907  for (const Vector3& w : test_cases::omegas(nearZero)) {
908  for (Vector3 v : test_cases::vs) {
909  const Vector6 xi = (Vector6() << w, v).finished();
910  const Matrix6 expectedH =
911  numericalDerivative21<Pose3, Vector6, OptionalJacobian<6, 6> >(
912  &Pose3::Expmap, xi, {});
913  Matrix actualH;
914  Pose3::Expmap(xi, actualH);
915  EXPECT(assert_equal(expectedH, actualH));
916  }
917  }
918  }
919 }
920 
921 //******************************************************************************
922 // Check logmap for all small values, as we don't want wrapping.
923 TEST(Pose3, Logmap) {
924  static constexpr bool nearZero = true;
925  for (const Vector3& w : test_cases::omegas(nearZero)) {
926  for (Vector3 v : test_cases::vs) {
927  const Vector6 xi = (Vector6() << w, v).finished();
929  EXPECT(assert_equal(xi, Pose3::Logmap(pose)));
930  }
931  }
932 }
933 
934 //******************************************************************************
935 // Check logmap derivatives for all values
936 TEST(Pose3, LogmapDerivatives) {
937  for (bool nearZero : {true, false}) {
938  for (const Vector3& w : test_cases::omegas(nearZero)) {
939  for (Vector3 v : test_cases::vs) {
940  const Vector6 xi = (Vector6() << w, v).finished();
942  const Matrix6 expectedH =
943  numericalDerivative21<Vector6, Pose3, OptionalJacobian<6, 6> >(
944  &Pose3::Logmap, pose, {});
945  Matrix actualH;
946  Pose3::Logmap(pose, actualH);
947 #ifdef GTSAM_USE_QUATERNIONS
948  // TODO(Frank): Figure out why quaternions are not as accurate.
949  // Hint: 6 cases fail on Ubuntu 22.04, but none on MacOS.
950  EXPECT(assert_equal(expectedH, actualH, 1e-7));
951 #else
952  EXPECT(assert_equal(expectedH, actualH));
953 #endif
954  }
955  }
956  }
957 }
958 
959 /* ************************************************************************* */
960 Vector6 testDerivAdjoint(const Vector6& xi, const Vector6& v) {
961  return Pose3::adjointMap(xi) * v;
962 }
963 
965  Vector6 v = (Vector6() << 1, 2, 3, 4, 5, 6).finished();
967 
968  Matrix actualH1, actualH2;
969  Vector actual = Pose3::adjoint(screwPose3::xi, v, actualH1, actualH2);
970 
971  Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
973  Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
975 
976  EXPECT(assert_equal(expected,actual,1e-5));
977  EXPECT(assert_equal(numericalH1,actualH1,1e-5));
978  EXPECT(assert_equal(numericalH2,actualH2,1e-5));
979 }
980 
981 /* ************************************************************************* */
982 Vector6 testDerivAdjointTranspose(const Vector6& xi, const Vector6& v) {
983  return Pose3::adjointMap(xi).transpose() * v;
984 }
985 
986 TEST( Pose3, adjointTranspose) {
987  Vector xi = (Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
988  Vector v = (Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
990 
991  Matrix actualH1, actualH2;
992  Vector actual = Pose3::adjointTranspose(xi, v, actualH1, actualH2);
993 
994  Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
996  Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
998 
999  EXPECT(assert_equal(expected,actual,1e-15));
1000  EXPECT(assert_equal(numericalH1,actualH1,1e-5));
1001  EXPECT(assert_equal(numericalH2,actualH2,1e-5));
1002 }
1003 
1004 /* ************************************************************************* */
1006  std::ostringstream os;
1007  os << Pose3();
1008 
1009  string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
1010  EXPECT(os.str() == expected);
1011 }
1012 
1013 //******************************************************************************
1014 TEST(Pose3 , Invariants) {
1015  Pose3 id;
1016 
1017  EXPECT(check_group_invariants(id,id));
1018  EXPECT(check_group_invariants(id,T3));
1019  EXPECT(check_group_invariants(T2,id));
1020  EXPECT(check_group_invariants(T2,T3));
1021 
1022  EXPECT(check_manifold_invariants(id,id));
1023  EXPECT(check_manifold_invariants(id,T3));
1024  EXPECT(check_manifold_invariants(T2,id));
1025  EXPECT(check_manifold_invariants(T2,T3));
1026 }
1027 
1028 //******************************************************************************
1029 TEST(Pose3 , LieGroupDerivatives) {
1030  Pose3 id;
1031 
1036 }
1037 
1038 //******************************************************************************
1039 TEST(Pose3 , ChartDerivatives) {
1040  Pose3 id;
1041  if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) {
1042  CHECK_CHART_DERIVATIVES(id,id);
1046  }
1047 }
1048 
1049 //******************************************************************************
1050 #include "testPoseAdjointMap.h"
1051 
1052 TEST(Pose3, TransformCovariance6MapTo2d) {
1053  // Create 3d scenarios that map to 2d configurations and compare with Pose2 results.
1054  using namespace test_pose_adjoint_map;
1055 
1056  Vector3 s2{0.1, 0.3, 0.7};
1057  Pose2 p2{1.1, 1.5, 31. * degree};
1058  auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
1059  auto transformed2 = TransformCovariance<Pose2>{p2}(cov2);
1060 
1061  auto match_cov3_to_cov2 = [&](int spatial_axis0, int spatial_axis1, int r_axis,
1062  const Pose2::Jacobian &cov2, const Pose3::Jacobian &cov3) -> void
1063  {
1065  Vector3{cov2.diagonal()},
1066  Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
1068  Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
1069  Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
1070  };
1071 
1072  // rotate around x axis
1073  {
1074  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
1075  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(p2.theta(), 0., 0.), {0., p2.x(), p2.y()}}}(cov3);
1076  match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
1077  }
1078 
1079  // rotate around y axis
1080  {
1081  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
1082  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., p2.theta(), 0.), {p2.y(), 0., p2.x()}}}(cov3);
1083  match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
1084  }
1085 
1086  // rotate around z axis
1087  {
1088  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
1089  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 0., p2.theta()), {p2.x(), p2.y(), 0.}}}(cov3);
1090  match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
1091  }
1092 }
1093 
1094 /* ************************************************************************* */
1095 TEST(Pose3, TransformCovariance6) {
1096  // Use simple covariance matrices and transforms to create tests that can be
1097  // validated with simple computations.
1098  using namespace test_pose_adjoint_map;
1099 
1100  // rotate 90 around z axis and then 90 around y axis
1101  {
1102  auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
1103  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 90 * degree, 90 * degree), {0., 0., 0.}}}(cov);
1104  // x from y, y from z, z from x
1106  (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
1107  Vector6{transformed.diagonal()}));
1108  // Both the x and z axes are pointing in the negative direction.
1110  (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
1111  (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
1112  transformed(4, 0), transformed(5, 0)).finished()));
1113  }
1114 
1115  // translate along the x axis with uncertainty in roty and rotz
1116  {
1117  auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
1118  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 0., 0.), {20., 0., 0.}}}(cov);
1119  // The uncertainty in roty and rotz causes off-diagonal covariances
1120  EXPECT(assert_equal(0.7 * 0.7 * 20., transformed(5, 1)));
1121  EXPECT(assert_equal(0.7 * 0.7 * 20. * 20., transformed(5, 5)));
1122  EXPECT(assert_equal(-0.3 * 0.3 * 20., transformed(4, 2)));
1123  EXPECT(assert_equal(0.3 * 0.3 * 20. * 20., transformed(4, 4)));
1124  EXPECT(assert_equal(-0.3 * 0.7 * 20., transformed(4, 1)));
1125  EXPECT(assert_equal(0.3 * 0.7 * 20., transformed(5, 2)));
1126  EXPECT(assert_equal(-0.3 * 0.7 * 20. * 20., transformed(5, 4)));
1127  }
1128 
1129  // rotate around x axis and translate along the x axis with uncertainty in rotx
1130  {
1131  auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
1132  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(90 * degree, 0., 0.), {20., 0., 0.}}}(cov);
1133  // No change
1134  EXPECT(assert_equal(cov, transformed));
1135  }
1136 
1137  // rotate around x axis and translate along the x axis with uncertainty in roty
1138  {
1139  auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1140  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(90 * degree, 0., 0.), {20., 0., 0.}}}(cov);
1141  // Uncertainty is spread to other dimensions.
1143  (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1144  Vector6{transformed.diagonal()}));
1145  }
1146 }
1147 
1148 /* ************************************************************************* */
1152 
1153  // Trivial example: start at origin and move to (1, 0, 0) while rotating pi/2
1154  // about z-axis.
1155  Pose3 start;
1156  Pose3 end(Rot3::Rz(M_PI_2), Point3(1, 0, 0));
1157  // This interpolation is easy to calculate by hand.
1158  double t = 0.5;
1159  Pose3 expected0(Rot3::Rz(M_PI_4), Point3(0.5, 0, 0));
1160  EXPECT(assert_equal(expected0, start.interpolateRt(end, t)));
1161 
1162  // Example from Peter Corke
1163  // https://robotacademy.net.au/lesson/interpolating-pose-in-3d/
1164  t = 0.0759; // corresponds to the 10th element when calling `ctraj` in
1165  // the video
1166  Pose3 O;
1167  Pose3 F(Rot3::Roll(0.6).compose(Rot3::Pitch(0.8)).compose(Rot3::Yaw(1.4)),
1168  Point3(1, 2, 3));
1169 
1170  // The expected answer matches the result presented in the video.
1171  Pose3 expected1(interpolate(O.rotation(), F.rotation(), t),
1172  interpolate(O.translation(), F.translation(), t));
1173  EXPECT(assert_equal(expected1, O.interpolateRt(F, t)));
1174 
1175  // Non-trivial interpolation, translation value taken from output.
1176  Pose3 expected2(interpolate(T2.rotation(), T3.rotation(), t),
1178  EXPECT(assert_equal(expected2, T2.interpolateRt(T3, t)));
1179 }
1180 
1181 /* ************************************************************************* */
1182 Pose3 testing_interpolate(const Pose3& t1, const Pose3& t2, double gamma) { return interpolate(t1,t2,gamma); }
1183 
1184 TEST(Pose3, interpolateJacobians) {
1185  {
1186  Pose3 X = Pose3::Identity();
1187  Pose3 Y(Rot3::Rz(M_PI_2), Point3(1, 0, 0));
1188  double t = 0.5;
1189  Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4), Point3(0.5, -0.207107, 0)); // note: different from test above: this is full Pose3 interpolation
1190  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1191  EXPECT(assert_equal(expectedPoseInterp, interpolate(X, Y, t, actualJacobianX, actualJacobianY, actualJacobianT), 1e-5));
1192 
1193  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1194  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1195 
1196  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1197  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1198 
1199  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1200  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1201  }
1202  {
1203  Pose3 X = Pose3::Identity();
1204  Pose3 Y(Rot3::Identity(), Point3(1, 0, 0));
1205  double t = 0.3;
1206  Pose3 expectedPoseInterp(Rot3::Identity(), Point3(0.3, 0, 0));
1207  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1208  EXPECT(assert_equal(expectedPoseInterp, interpolate(X, Y, t, actualJacobianX, actualJacobianY, actualJacobianT), 1e-5));
1209 
1210  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1211  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1212 
1213  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1214  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1215 
1216  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1217  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1218  }
1219  {
1220  Pose3 X = Pose3::Identity();
1221  Pose3 Y(Rot3::Rz(M_PI_2), Point3(0, 0, 0));
1222  double t = 0.5;
1223  Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4), Point3(0, 0, 0));
1224  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1225  EXPECT(assert_equal(expectedPoseInterp, interpolate(X, Y, t, actualJacobianX, actualJacobianY, actualJacobianT), 1e-5));
1226 
1227  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1228  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1229 
1230  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1231  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1232 
1233  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1234  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1235  }
1236  {
1237  Pose3 X(Rot3::Ypr(0.1,0.2,0.3), Point3(10, 5, -2));
1238  Pose3 Y(Rot3::Ypr(1.1,-2.2,-0.3), Point3(-5, 1, 1));
1239  double t = 0.3;
1240  Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4), Point3(0, 0, 0));
1241  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1242  interpolate(X, Y, t, actualJacobianX, actualJacobianY, actualJacobianT);
1243 
1244  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1245  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1246 
1247  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1248  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1249 
1250  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate, X, Y, t);
1251  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1252  }
1253 }
1254 /* ************************************************************************* */
1255 Pose3 testing_interpolate_rt(const Pose3& t1, const Pose3& t2, double gamma) { return t1.interpolateRt(t2, gamma); }
1256 
1257 TEST(Pose3, interpolateRtJacobians) {
1258  {
1259  Pose3 X = Pose3::Identity();
1260  Pose3 Y(Rot3::Rz(M_PI_2), Point3(1, 0, 0));
1261  double t = 0.5;
1262  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1263  X.interpolateRt(Y, t, actualJacobianX, actualJacobianY, actualJacobianT);
1264 
1265  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1266  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1267 
1268  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1269  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1270 
1271  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1272  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1273  }
1274  {
1275  Pose3 X = Pose3::Identity();
1276  Pose3 Y(Rot3::Identity(), Point3(1, 0, 0));
1277  double t = 0.3;
1278  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1279  X.interpolateRt(Y, t, actualJacobianX, actualJacobianY, actualJacobianT);
1280 
1281  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1282  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1283 
1284  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1285  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1286 
1287  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1288  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1289  }
1290  {
1291  Pose3 X = Pose3::Identity();
1292  Pose3 Y(Rot3::Rz(M_PI_2), Point3(0, 0, 0));
1293  double t = 0.5;
1294  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1295  X.interpolateRt(Y, t, actualJacobianX, actualJacobianY, actualJacobianT);
1296 
1297  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1298  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1299 
1300  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1301  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1302 
1303  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1304  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1305  }
1306  {
1307  Pose3 X(Rot3::Ypr(0.1,0.2,0.3), Point3(10, 5, -2));
1308  Pose3 Y(Rot3::Ypr(1.1,-2.2,-0.3), Point3(-5, 1, 1));
1309  double t = 0.3;
1310  Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1311  X.interpolateRt(Y, t, actualJacobianX, actualJacobianY, actualJacobianT);
1312 
1313  Matrix expectedJacobianX = numericalDerivative31<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1314  EXPECT(assert_equal(expectedJacobianX,actualJacobianX,1e-6));
1315 
1316  Matrix expectedJacobianY = numericalDerivative32<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1317  EXPECT(assert_equal(expectedJacobianY,actualJacobianY,1e-6));
1318 
1319  Matrix expectedJacobianT = numericalDerivative33<Pose3,Pose3,Pose3,double>(testing_interpolate_rt, X, Y, t);
1320  EXPECT(assert_equal(expectedJacobianT,actualJacobianT,1e-6));
1321  }
1322 }
1323 
1324 TEST(Pose3, expressionWrappers) {
1325  Pose3 X(Rot3::Ypr(0.1,0.2,0.3), Point3(10, 5, -2));
1326  Pose3 Y(Rot3::Ypr(1.1,-2.2,-0.3), Point3(-5, 1, 1));
1327  double t = 0.3;
1328  Values vals;
1329  vals.insert(0,X);
1330  vals.insert(1,Y);
1331  vals.insert(2,t);
1332 
1333  { // interpolate (templated wrapper applies to all classes)
1334  Matrix expectedJacobianX, expectedJacobianY, expectedJacobianT;
1335  std::vector<Matrix> Hlist = {{},{},{}};
1336  Pose3 expected = interpolate(X, Y, t, expectedJacobianX, expectedJacobianY, expectedJacobianT);
1337  Pose3 actual = interpolate(Pose3_(Key(0)), Pose3_(Key(1)), Double_(Key(2))).value(vals, Hlist);
1338 
1339  EXPECT(assert_equal(expected,actual,1e-6));
1340  EXPECT(assert_equal(expectedJacobianX,Hlist[0],1e-6));
1341  EXPECT(assert_equal(expectedJacobianY,Hlist[1],1e-6));
1342  EXPECT(assert_equal(expectedJacobianT,Hlist[2],1e-6));
1343  }
1344  { // interpolateRt (Pose3 specialisation)
1345  Matrix expectedJacobianX, expectedJacobianY, expectedJacobianT;
1346  std::vector<Matrix> Hlist = {{},{},{}};
1347  Pose3 expected = X.interpolateRt(Y, t, expectedJacobianX, expectedJacobianY, expectedJacobianT);
1348  Pose3 actual = interpolateRt(Pose3_(Key(0)), Pose3_(Key(1)), Double_(Key(2))).value(vals, Hlist);
1349 
1350  EXPECT(assert_equal(expected,actual,1e-6));
1351  EXPECT(assert_equal(expectedJacobianX,Hlist[0],1e-6));
1352  EXPECT(assert_equal(expectedJacobianY,Hlist[1],1e-6));
1353  EXPECT(assert_equal(expectedJacobianT,Hlist[2],1e-6));
1354  }
1355 }
1356 
1357 /* ************************************************************************* */
1358 TEST(Pose3, Create) {
1359  Matrix63 actualH1, actualH2;
1360  Pose3 actual = Pose3::Create(R, P2, actualH1, actualH2);
1361  EXPECT(assert_equal(T, actual));
1362  std::function<Pose3(Rot3, Point3)> create = [](Rot3 R, Point3 t) {
1363  return Pose3::Create(R, t);
1364  };
1365  EXPECT(assert_equal(numericalDerivative21<Pose3,Rot3,Point3>(create, R, P2), actualH1, 1e-9));
1366  EXPECT(assert_equal(numericalDerivative22<Pose3,Rot3,Point3>(create, R, P2), actualH2, 1e-9));
1367 }
1368 
1369 /* ************************************************************************* */
1371  Pose3 pose(Rot3::Identity(), Point3(1, 2, 3));
1372 
1373  // Generate the expected output
1374  std::string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
1375 
1377 }
1378 
1379 /* ************************************************************************* */
1380 TEST(Pose3, ExpmapChainRule) {
1381  // Muliply with an arbitrary matrix and exponentiate
1382  Matrix6 M;
1383  M << 1, 2, 3, 4, 5, 6, //
1384  7, 8, 9, 1, 2, 3, //
1385  4, 5, 6, 7, 8, 9, //
1386  1, 2, 3, 4, 5, 6, //
1387  7, 8, 9, 1, 2, 3, //
1388  4, 5, 6, 7, 8, 9;
1389  auto g = [&](const Vector6& omega) {
1390  return Pose3::Expmap(M*omega);
1391  };
1392 
1393  // Test the derivatives at zero
1394  const Matrix6 expected = numericalDerivative11<Pose3, Vector6>(g, Z_6x1);
1395  EXPECT(assert_equal<Matrix6>(expected, M, 1e-5)); // Pose3::ExpmapDerivative(Z_6x1) is identity
1396 
1397  // Test the derivatives at another value
1398  const Vector6 delta{0.1, 0.2, 0.3, 0.4, 0.5, 0.6};
1399  const Matrix6 expected2 = numericalDerivative11<Pose3, Vector6>(g, delta);
1400  const Matrix6 analytic = Pose3::ExpmapDerivative(M*delta) * M;
1401  EXPECT(assert_equal<Matrix6>(expected2, analytic, 1e-5)); // note tolerance
1402 }
1403 
1404 /* ************************************************************************* */
1405 TEST(Pose3, vec) {
1406  // Test the 'vec' method
1408  Vector16 expected_vec = Eigen::Map<Vector16>(T.matrix().data());
1409  Matrix actualH;
1410  Vector16 actual_vec = T.vec(actualH);
1411  EXPECT(assert_equal(expected_vec, actual_vec));
1412 
1413  // Verify Jacobian with numerical derivatives
1414  std::function<Vector16(const Pose3&)> f = [](const Pose3& p) { return p.vec(); };
1415  Matrix numericalH = numericalDerivative11<Vector16, Pose3>(f, T);
1416  EXPECT(assert_equal(numericalH, actualH, 1e-9));
1417 }
1418 
1419 /* ************************************************************************* */
1420 int main() {
1421  TestResult tr;
1422  return TestRegistry::runAllTests(tr);
1423 }
1424 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::internal::rotation
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Definition: slam/expressions.h:84
create
ADT create(const Signature &signature)
Definition: testAlgebraicDecisionTree.cpp:145
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::Point3Pair
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:42
Pose2.h
2D Pose
gtsam::TransformCovariance
Definition: Lie.h:390
l3
Point3 l3(2, 2, 0)
gtsam::Expression::value
T value(const Values &values, std::vector< Matrix > *H=nullptr) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient,...
Definition: Expression-inl.h:143
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::Double_
Expression< double > Double_
Definition: nonlinear/expressions.h:28
gtsam::Pose3::transformTo
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:413
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
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam.examples.SFMExample_bal.stream
stream
Definition: SFMExample_bal.py:24
b
Scalar * b
Definition: benchVecAdd.cpp:17
test_cases::omegas
auto omegas
Definition: testPose3.cpp:899
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
screwPose3::w
double w
Definition: testPose3.cpp:123
gtsam::assert_print_equal
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Definition: TestableAssertions.h:353
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
screwPose3::xi
Vector xi
Definition: testPose3.cpp:124
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
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
bearing_proxy
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:770
transformPoseTo_
Pose3 transformPoseTo_(const Pose3 &pose, const Pose3 &pose2)
Definition: testPose3.cpp:557
T3
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
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
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
X
#define X
Definition: icosphere.cpp:20
gtsam::interpolateRt
Pose3_ interpolateRt(const Pose3_ &p, const Pose3_ &q, const Double_ &t)
Definition: slam/expressions.h:61
test_cases::vs
std::vector< Vector3 > vs
Definition: testPose3.cpp:900
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
testLie.h
test_pose_adjoint_map
Definition: testPoseAdjointMap.h:24
res
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Definition: PartialRedux_count.cpp:3
os
ofstream os("timeSchurFactors.csv")
tol
static const double tol
Definition: testPose3.cpp:42
TEST
TEST(Pose3, Concept)
Definition: testPose3.cpp:45
gtsam::IsGroup
Definition: Group.h:42
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:381
screwPose3::c
double c
Definition: testPose3.cpp:123
gtsam::Pose3::matrix
Matrix4 matrix() const
Definition: Pose3.cpp:365
x3
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
EQUALITY
#define EQUALITY(expected, actual)
Definition: Test.h:127
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
TestableAssertions.h
Provides additional testing facilities for common data structures.
Eigen::Triplet::value
const Scalar & value() const
Definition: SparseUtil.h:178
gtsam::Pose3::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Definition: Pose3.cpp:441
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
l2
Point3 l2(1, 1, 0)
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
gtsam::Pose3::transformPoseFrom
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const
Definition: Pose3.cpp:373
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam::Pose3::AdjointTranspose
Vector6 AdjointTranspose(const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const
The dual version of Adjoint.
Definition: Pose3.cpp:97
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::Pose3::transformPoseTo
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const
Definition: Pose3.cpp:380
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::Pose3::Adjoint
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
Definition: Pose3.cpp:79
transformPoseFrom_
Pose3 transformPoseFrom_(const Pose3 &wTa, const Pose3 &aTb)
Definition: testPose3.cpp:528
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
gtsam::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
testPoseAdjointMap.h
Support utilities for using AdjointMap for transforming Pose2 and Pose3 covariance matrices.
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
xl4
Pose3 xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4))
screwPose3::expectedT
Point3 expectedT(0.29552, 0.0446635, 1)
xl2
Pose3 xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0))
I
#define I
Definition: main.h:112
gtsam::transformTo
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
x1
Pose3 x1
Definition: testPose3.cpp:692
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
GTSAM_CONCEPT_LIE_INST
#define GTSAM_CONCEPT_LIE_INST(T)
Definition: Lie.h:410
M_PI_4
#define M_PI_4
Definition: mconf.h:119
screwPose3::expected
Pose3 expected(expectedR, expectedT)
Agrawal06iros
Pose3 Agrawal06iros(const Vector &xi)
Definition: testPose3.cpp:271
gtsam::Pose3::inverse
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:61
gtsam::Pose3::interpolateRt
Pose3 interpolateRt(const Pose3 &T, double t, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > Harg={}, OptionalJacobian< 6, 1 > Ht={}) const
Definition: Pose3.cpp:189
gtsam::Pose3::equals
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:184
degree
const double degree
Definition: SimpleRotation.cpp:59
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:351
l4
Point3 l4(1, 4,-4)
screwPose3::expectedR
Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1)
gtsam::Pose3::AdjointMap
Matrix6 AdjointMap() const
Definition: Pose3.cpp:69
CHECK_LIE_GROUP_DERIVATIVES
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
T5
static const Similarity3 T5(R, P, 10)
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:585
simple::p3
static Point3 p3
Definition: testInitializePose3.cpp:53
test_cases::large
std::vector< Vector3 > large
Definition: testPose3.cpp:897
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
transform
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
Eigen::Triplet< double >
R
static const Rot3 R
Definition: testPose3.cpp:37
gamma
#define gamma
Definition: mconf.h:85
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::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
range_proxy
double range_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:700
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
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
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
M_PI_2
#define M_PI_2
Definition: mconf.h:118
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
screwPose3
Definition: testPose3.cpp:122
gtsam::Vector16
Eigen::Matrix< double, 16, 1 > Vector16
Definition: Pose3.cpp:540
gtsam::symbol_shorthand::O
Key O(std::uint64_t j)
Definition: inference/Symbol.h:162
gtsam::Pose3::bearing
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
Definition: Pose3.cpp:469
gtsam::interpolate
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={}, typename MakeOptionalJacobian< T, double >::type Ht={})
Definition: Lie.h:363
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:357
pose2
Definition: testFrobeniusFactor.cpp:193
xl3
Pose3 xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0))
gtsam
traits
Definition: SFMdata.h:40
gtsam::Values
Definition: Values.h:65
test_cases::small
std::vector< Vector3 > small
Definition: testPose3.cpp:894
expressions.h
Common expressions for solving geometry/slam/sfm problems.
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
Pose3_
Expression< Pose3 > Pose3_
Definition: testExpression.cpp:32
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::internal::translation
Point3 translation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Definition: slam/expressions.h:88
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
std
Definition: BFloat16.h:88
gtsam::Pose3::transformFrom
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:389
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
xl1
Pose3 xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0))
p
float * p
Definition: Tutorial_Map_using.cpp:9
testing_interpolate_rt
Pose3 testing_interpolate_rt(const Pose3 &t1, const Pose3 &t2, double gamma)
Definition: testPose3.cpp:1255
transformFrom_
Point3 transformFrom_(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:424
v2
Vector v2
Definition: testSerializationBase.cpp:39
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
main
int main()
Definition: testPose3.cpp:1420
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Similarity3::matrix
Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
Definition: Similarity3.cpp:291
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
transform_to_
Point3 transform_to_(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:472
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
Eigen::Matrix< double, 6, 6 >
P
static const Point3 P(0.2, 0.7,-2)
l1
Point3 l1(1, 0, 0)
testDerivAdjointTranspose
Vector6 testDerivAdjointTranspose(const Vector6 &xi, const Vector6 &v)
Definition: testPose3.cpp:982
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
v3
Vector v3
Definition: testSerializationBase.cpp:40
gtsam::internal::Align
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair &centroids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
Definition: Similarity2.cpp:74
gtsam::LieGroup::expmap
Class expmap(const TangentVector &v) const
Definition: Lie.h:78
M_PI
#define M_PI
Definition: mconf.h:117
screwPose3::a
double a
Definition: testPose3.cpp:123
Eigen::placeholders::end
static const EIGEN_DEPRECATED end_t end
Definition: IndexedViewHelper.h:181
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Bearing
Definition: BearingRange.h:35
gtsam::transformPoseTo
Pose3_ transformPoseTo(const Pose3_ &p, const Pose3_ &q)
Definition: slam/expressions.h:57
lieProxies.h
Provides convenient mappings of common member functions for testing.
align_3::t
Point2 t(10, 10)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
testDerivAdjoint
Vector6 testDerivAdjoint(const Vector6 &xi, const Vector6 &v)
Definition: testPose3.cpp:960
test_cases
Definition: testPose3.cpp:893
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:25
adjoint
void adjoint(const MatrixType &m)
Definition: adjoint.cpp:67
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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
T
static const Pose3 T(R, P2)
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
P2
static const Point3 P2(3.5,-8.2, 4.2)
testing_interpolate
Pose3 testing_interpolate(const Pose3 &t1, const Pose3 &t2, double gamma)
Definition: testPose3.cpp:1182
v1
Vector v1
Definition: testSerializationBase.cpp:38
gtsam::Pose2
Definition: Pose2.h:39
ROT3_DEFAULT_COORDINATES_MODE
#define ROT3_DEFAULT_COORDINATES_MODE
Definition: Rot3.h:43
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
range_pose_proxy
double range_pose_proxy(const Pose3 &pose, const Pose3 &point)
Definition: testPose3.cpp:735


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