testSimilarity3.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 
23 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/inference/Symbol.h>
28 #include <gtsam/base/testLie.h>
29 #include <gtsam/base/Testable.h>
30 
32 
33 #include <boost/function.hpp>
34 #include <boost/bind.hpp>
35 
36 using namespace gtsam;
37 using namespace std;
39 
41 
42 static const Point3 P(0.2, 0.7, -2);
43 static const Rot3 R = Rot3::Rodrigues(0.3, 0, 0);
44 static const double s = 4;
45 static const Similarity3 id;
46 static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1);
47 static const Similarity3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1),
48  Point3(3.5, -8.2, 4.2), 1);
49 static const Similarity3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3), 1);
50 static const Similarity3 T4(R, P, s);
51 static const Similarity3 T5(R, P, 10);
52 static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2); // Simpler transform
53 
54 const double degree = M_PI / 180;
55 
56 //******************************************************************************
57 TEST(Similarity3, Concepts) {
59  BOOST_CONCEPT_ASSERT((IsManifold<Similarity3 >));
61 }
62 
63 //******************************************************************************
64 TEST(Similarity3, Constructors) {
65  Similarity3 sim3_Construct1;
66  Similarity3 sim3_Construct2(s);
67  Similarity3 sim3_Construct3(R, P, s);
68  Similarity3 sim4_Construct4(R.matrix(), P, s);
69 }
70 
71 //******************************************************************************
72 TEST(Similarity3, Getters) {
73  Similarity3 sim3_default;
74  EXPECT(assert_equal(Rot3(), sim3_default.rotation()));
75  EXPECT(assert_equal(Point3(0,0,0), sim3_default.translation()));
76  EXPECT_DOUBLES_EQUAL(1.0, sim3_default.scale(), 1e-9);
77 
78  Similarity3 sim3(Rot3::Ypr(1, 2, 3), Point3(4, 5, 6), 7);
79  EXPECT(assert_equal(Rot3::Ypr(1, 2, 3), sim3.rotation()));
80  EXPECT(assert_equal(Point3(4, 5, 6), sim3.translation()));
81  EXPECT_DOUBLES_EQUAL(7.0, sim3.scale(), 1e-9);
82 }
83 
84 //******************************************************************************
85 TEST(Similarity3, AdjointMap) {
86  const Matrix4 T = T2.matrix();
87  // Check Ad with actual definition
88  Vector7 delta;
89  delta << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7;
90  Matrix4 W = Similarity3::wedge(delta);
91  Matrix4 TW = Similarity3::wedge(T2.AdjointMap() * delta);
92  EXPECT(assert_equal(TW, Matrix4(T * W * T.inverse()), 1e-9));
93 }
94 
95 //******************************************************************************
97  Similarity3 sim3(Rot3::Ypr(1, 2, 3).inverse(), Point3(4, 5, 6), 7);
98  Matrix3 Re; // some values from matlab
99  Re << -0.2248, 0.9024, -0.3676, -0.3502, -0.4269, -0.8337, -0.9093, -0.0587, 0.4120;
100  Vector3 te(-9.8472, 59.7640, 10.2125);
101  Similarity3 expected(Re, te, 1.0 / 7.0);
102  EXPECT(assert_equal(expected, sim3.inverse(), 1e-4));
103  EXPECT(assert_equal(sim3, sim3.inverse().inverse(), 1e-8));
104 
105  // test lie group inverse
106  Matrix H1, H2;
107  EXPECT(assert_equal(expected, sim3.inverse(H1), 1e-4));
108  EXPECT(assert_equal(sim3, sim3.inverse().inverse(H2), 1e-8));
109 }
110 
111 //******************************************************************************
112 TEST(Similarity3, Multiplication) {
113  Similarity3 test1(Rot3::Ypr(1, 2, 3).inverse(), Point3(4, 5, 6), 7);
114  Similarity3 test2(Rot3::Ypr(1, 2, 3).inverse(), Point3(8, 9, 10), 11);
115  Matrix3 re;
116  re << 0.0688, 0.9863, -0.1496, -0.5665, -0.0848, -0.8197, -0.8211, 0.1412, 0.5530;
117  Vector3 te(-13.6797, 3.2441, -5.7794);
118  Similarity3 expected(re, te, 77);
119  EXPECT(assert_equal(expected, test1 * test2, 1e-2));
120 }
121 
122 //******************************************************************************
123 TEST(Similarity3, Manifold) {
125  Vector z = Vector7::Zero();
126  Similarity3 sim;
127  EXPECT(sim.retract(z) == sim);
128 
129  Vector7 v = Vector7::Zero();
130  v(6) = 2;
131  Similarity3 sim2;
132  EXPECT(sim2.retract(z) == sim2);
133 
134  EXPECT(assert_equal(z, sim2.localCoordinates(sim)));
135 
136  Similarity3 sim3 = Similarity3(Rot3(), Point3(1, 2, 3), 1);
137  Vector v3(7);
138  v3 << 0, 0, 0, 1, 2, 3, 0;
139  EXPECT(assert_equal(v3, sim2.localCoordinates(sim3)));
140 
141  Similarity3 other = Similarity3(Rot3::Ypr(0.1, 0.2, 0.3), Point3(4, 5, 6), 1);
142 
143  Vector vlocal = sim.localCoordinates(other);
144 
145  EXPECT(assert_equal(sim.retract(vlocal), other, 1e-2));
146 
147  Similarity3 other2 = Similarity3(Rot3::Ypr(0.3, 0, 0), Point3(4, 5, 6), 1);
148  Rot3 R = Rot3::Rodrigues(0.3, 0, 0);
149 
150  Vector vlocal2 = sim.localCoordinates(other2);
151 
152  EXPECT(assert_equal(sim.retract(vlocal2), other2, 1e-2));
153 
154  // TODO add unit tests for retract and localCoordinates
155 }
156 
157 //******************************************************************************
158 TEST( Similarity3, retract_first_order) {
159  Similarity3 id;
160  Vector v = Z_7x1;
161  v(0) = 0.3;
162  EXPECT(assert_equal(Similarity3(R, Point3(0,0,0), 1), id.retract(v), 1e-2));
163 // v(3) = 0.2;
164 // v(4) = 0.7;
165 // v(5) = -2;
166 // EXPECT(assert_equal(Similarity3(R, P, 1), id.retract(v), 1e-2));
167 }
168 
169 //******************************************************************************
170 TEST(Similarity3, localCoordinates_first_order) {
171  Vector7 d12 = Vector7::Constant(0.1);
172  d12(6) = 1.0;
173  Similarity3 t1 = T1, t2 = t1.retract(d12);
174  EXPECT(assert_equal(d12, t1.localCoordinates(t2)));
175 }
176 
177 //******************************************************************************
178 TEST(Similarity3, manifold_first_order) {
179  Similarity3 t1 = T1;
180  Similarity3 t2 = T3;
182  Vector d12 = t1.localCoordinates(t2);
183  EXPECT(assert_equal(t2, t1.retract(d12)));
184  Vector d21 = t2.localCoordinates(t1);
185  EXPECT(assert_equal(t1, t2.retract(d21)));
186 }
187 
188 //******************************************************************************
189 // Return as a 4*4 Matrix
191  Matrix4 expected;
192  expected << 1, 0, 0, 1, 0, 1, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0.5;
193  Matrix4 actual = T6.matrix();
194  EXPECT(assert_equal(expected, actual));
195 }
196 
197 //*****************************************************************************
198 // Exponential and log maps
199 TEST(Similarity3, ExpLogMap) {
200  Vector7 delta;
201  delta << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7;
202  Vector7 actual = Similarity3::Logmap(Similarity3::Expmap(delta));
203  EXPECT(assert_equal(delta, actual));
204 
205  Vector7 zeros;
206  zeros << 0, 0, 0, 0, 0, 0, 0;
207  Vector7 logIdentity = Similarity3::Logmap(Similarity3::identity());
208  EXPECT(assert_equal(zeros, logIdentity));
209 
210  Similarity3 expZero = Similarity3::Expmap(zeros);
212  EXPECT(assert_equal(expZero, ident));
213 
214  // Compare to matrix exponential, using expm in Lie.h
215  EXPECT(
216  assert_equal(expm<Similarity3>(delta), Similarity3::Expmap(delta), 1e-3));
217 }
218 
219 //******************************************************************************
220 // Group action on Point3 (with simpler transform)
221 TEST(Similarity3, GroupAction) {
222  EXPECT(assert_equal(Point3(2, 2, 0), T6 * Point3(0, 0, 0)));
223  EXPECT(assert_equal(Point3(4, 2, 0), T6 * Point3(1, 0, 0)));
224 
225  // Test group action on R^4 via matrix representation
226  Vector4 qh;
227  qh << 1, 0, 0, 1;
228  Vector4 ph;
229  ph << 2, 1, 0, 0.5; // equivalent to Point3(4, 2, 0)
230  EXPECT(assert_equal((Vector )ph, T6.matrix() * qh));
231 
232  // Test some more...
233  Point3 pa = Point3(1, 0, 0);
234  Similarity3 Ta(Rot3(), Point3(1, 2, 3), 1.0);
235  Similarity3 Tb(Rot3(), Point3(1, 2, 3), 2.0);
236  EXPECT(assert_equal(Point3(2, 2, 3), Ta.transformFrom(pa)));
237  EXPECT(assert_equal(Point3(4, 4, 6), Tb.transformFrom(pa)));
238 
239  Similarity3 Tc(Rot3::Rz(M_PI / 2.0), Point3(1, 2, 3), 1.0);
240  Similarity3 Td(Rot3::Rz(M_PI / 2.0), Point3(1, 2, 3), 2.0);
241  EXPECT(assert_equal(Point3(1, 3, 3), Tc.transformFrom(pa)));
242  EXPECT(assert_equal(Point3(2, 6, 6), Td.transformFrom(pa)));
243 
244  // Test derivative
245  boost::function<Point3(Similarity3, Point3)> f = boost::bind(
246  &Similarity3::transformFrom, _1, _2, boost::none, boost::none);
247 
248  Point3 q(1, 2, 3);
249  for (const auto& T : { T1, T2, T3, T4, T5, T6 }) {
250  Point3 q(1, 0, 0);
251  Matrix H1 = numericalDerivative21<Point3, Similarity3, Point3>(f, T, q);
252  Matrix H2 = numericalDerivative22<Point3, Similarity3, Point3>(f, T, q);
253  Matrix actualH1, actualH2;
254  T.transformFrom(q, actualH1, actualH2);
255  EXPECT(assert_equal(H1, actualH1));
256  EXPECT(assert_equal(H2, actualH2));
257  }
258 }
259 
260 //******************************************************************************
261 // Group action on Pose3
262 // Estimate Sim(3) object "aSb" from pose pairs {(aTi, bTi)}
263 // In the example below, let the "a" frame be the "world" frame below,
264 // and let the "b" frame be the "egovehicle" frame.
265 // Suppose within the egovehicle frame, we know the poses of two objects "o1" and "o2"
266 TEST(Similarity3, GroupActionPose3) {
267  // Suppose we know the pose of the egovehicle in the world frame
268  Similarity3 wSe(Rot3::Ry(180 * degree), Point3(2, 3, 5), 2.0);
269 
270  // Create source poses (two objects o1 and o2 living in the egovehicle "e" frame)
271  // Suppose they are 3d cuboids detected by onboard sensor, in the egovehicle frame
272  Pose3 eTo1(Rot3(), Point3(0, 0, 0));
273  Pose3 eTo2(Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1), Point3(4, 0, 0));
274 
275  // Create destination poses (two objects now living in the world/city "w" frame)
276  // Desired to place the objects into the world frame for tracking
277  Pose3 expected_wTo1(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(4, 6, 10));
278  Pose3 expected_wTo2(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(-4, 6, 10));
279 
280  // objects now live in the world frame, instead of in the egovehicle frame
281  EXPECT(assert_equal(expected_wTo1, wSe.transformFrom(eTo1)));
282  EXPECT(assert_equal(expected_wTo2, wSe.transformFrom(eTo2)));
283 }
284 
285 // Test left group action compatibility.
286 // cSa*Ta = cSb*bSa*Ta
287 TEST(Similarity3, GroupActionPose3_Compatibility) {
288  Similarity3 bSa(Rot3::Ry(180 * degree), Point3(2, 3, 5), 2.0);
289  Similarity3 cSb(Rot3::Ry(90 * degree), Point3(-10, -4, 0), 3.0);
290  Similarity3 cSa(Rot3::Ry(270 * degree), Point3(0, 1, -2), 6.0);
291 
292  // Create poses
293  Pose3 Ta1(Rot3(), Point3(0, 0, 0));
294  Pose3 Ta2(Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1), Point3(4, 0, 0));
295  Pose3 Tb1(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(4, 6, 10));
296  Pose3 Tb2(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(-4, 6, 10));
297  Pose3 Tc1(Rot3(0, 0, -1, 0, 1, 0, 1, 0, 0), Point3(0, 6, -12));
298  Pose3 Tc2(Rot3(0, 0, -1, 0, -1, 0, -1, 0, 0), Point3(0, 6, 12));
299 
300  EXPECT(assert_equal(Tc1, cSb.transformFrom(Tb1)));
301  EXPECT(assert_equal(Tc2, cSb.transformFrom(Tb2)));
302 
303  EXPECT(assert_equal(cSa.transformFrom(Ta1), cSb.transformFrom(Tb1)));
304  EXPECT(assert_equal(cSa.transformFrom(Ta2), cSb.transformFrom(Tb2)));
305 }
306 
307 //******************************************************************************
308 // Align with Point3 Pairs
309 TEST(Similarity3, AlignPoint3_1) {
310  Similarity3 expected_aSb(Rot3::Rz(-90 * degree), Point3(3, 4, 5), 2.0);
311 
312  Point3 b1(0, 0, 0), b2(3, 0, 0), b3(3, 0, 4);
313 
314  Point3Pair ab1(make_pair(expected_aSb.transformFrom(b1), b1));
315  Point3Pair ab2(make_pair(expected_aSb.transformFrom(b2), b2));
316  Point3Pair ab3(make_pair(expected_aSb.transformFrom(b3), b3));
317 
318  vector<Point3Pair> correspondences{ab1, ab2, ab3};
319 
320  Similarity3 actual_aSb = Similarity3::Align(correspondences);
321  EXPECT(assert_equal(expected_aSb, actual_aSb));
322 }
323 
324 TEST(Similarity3, AlignPoint3_2) {
325  Similarity3 expected_aSb(Rot3(), Point3(10, 10, 0), 1.0);
326 
327  Point3 b1(0, 0, 0), b2(20, 10, 0), b3(10, 20, 0);
328 
329  Point3Pair ab1(make_pair(expected_aSb.transformFrom(b1), b1));
330  Point3Pair ab2(make_pair(expected_aSb.transformFrom(b2), b2));
331  Point3Pair ab3(make_pair(expected_aSb.transformFrom(b3), b3));
332 
333  vector<Point3Pair> correspondences{ab1, ab2, ab3};
334 
335  Similarity3 actual_aSb = Similarity3::Align(correspondences);
336  EXPECT(assert_equal(expected_aSb, actual_aSb));
337 }
338 
339 TEST(Similarity3, AlignPoint3_3) {
340  Similarity3 expected_aSb(Rot3::RzRyRx(0.3, 0.2, 0.1), Point3(20, 10, 5), 1.0);
341 
342  Point3 b1(0, 0, 1), b2(10, 0, 2), b3(20, -10, 30);
343 
344  Point3Pair ab1(make_pair(expected_aSb.transformFrom(b1), b1));
345  Point3Pair ab2(make_pair(expected_aSb.transformFrom(b2), b2));
346  Point3Pair ab3(make_pair(expected_aSb.transformFrom(b3), b3));
347 
348  vector<Point3Pair> correspondences{ab1, ab2, ab3};
349 
350  Similarity3 actual_aSb = Similarity3::Align(correspondences);
351  EXPECT(assert_equal(expected_aSb, actual_aSb));
352 }
353 
354 //******************************************************************************
355 // Align with Pose3 Pairs
356 TEST(Similarity3, AlignPose3) {
357  Similarity3 expected_wSe(Rot3::Ry(180 * degree), Point3(2, 3, 5), 2.0);
358 
359  // Create source poses (two objects o1 and o2 living in the egovehicle "e" frame)
360  // Suppose they are 3d cuboids detected by an onboard sensor in the egovehicle frame
361  Pose3 eTo1(Rot3(), Point3(0, 0, 0));
362  Pose3 eTo2(Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1), Point3(4, 0, 0));
363 
364  // Create destination poses (same two objects, but instead living in the world/city "w" frame)
365  Pose3 wTo1(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(4, 6, 10));
366  Pose3 wTo2(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(-4, 6, 10));
367 
368  Pose3Pair wTe1(make_pair(wTo1, eTo1));
369  Pose3Pair wTe2(make_pair(wTo2, eTo2));
370 
371  vector<Pose3Pair> correspondences{wTe1, wTe2};
372 
373  // Cayley transform cannot accommodate 180 degree rotations,
374  // hence we only test for Expmap
375 #ifdef GTSAM_ROT3_EXPMAP
376  // Recover the transformation wSe (i.e. world_S_egovehicle)
377  Similarity3 actual_wSe = Similarity3::Align(correspondences);
378  EXPECT(assert_equal(expected_wSe, actual_wSe));
379 #endif
380 }
381 
382 //******************************************************************************
383 // Test very simple prior optimization example
384 TEST(Similarity3, Optimization) {
385  // Create a PriorFactor with a Sim3 prior
386  Similarity3 prior = Similarity3(Rot3::Ypr(0.1, 0.2, 0.3), Point3(1, 2, 3), 4);
388  Symbol key('x', 1);
389 
390  // Create graph
392  graph.addPrior(key, prior, model);
393 
394  // Create initial estimate with identity transform
395  Values initial;
396  initial.insert<Similarity3>(key, Similarity3());
397 
398  // Optimize
399  Values result;
401  params.setVerbosityLM("TRYCONFIG");
402  result = LevenbergMarquardtOptimizer(graph, initial).optimize();
403 
404  // After optimization, result should be prior
405  EXPECT(assert_equal(prior, result.at<Similarity3>(key), 1e-4));
406 }
407 
408 //******************************************************************************
409 // Test optimization with both Prior and BetweenFactors
410 TEST(Similarity3, Optimization2) {
412  Similarity3 m1 = Similarity3(Rot3::Ypr(M_PI / 4.0, 0, 0), Point3(2.0, 0, 0),
413  1.0);
414  Similarity3 m2 = Similarity3(Rot3::Ypr(M_PI / 2.0, 0, 0),
415  Point3(sqrt(8) * 0.9, 0, 0), 1.0);
416  Similarity3 m3 = Similarity3(Rot3::Ypr(3 * M_PI / 4.0, 0, 0),
417  Point3(sqrt(32) * 0.8, 0, 0), 1.0);
418  Similarity3 m4 = Similarity3(Rot3::Ypr(M_PI / 2.0, 0, 0),
419  Point3(6 * 0.7, 0, 0), 1.0);
420  Similarity3 loop = Similarity3(1.42);
421 
422  //prior.print("Goal Transform");
424  0.01);
426  (Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10).finished());
428  (Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0).finished());
429  BetweenFactor<Similarity3> b1(X(1), X(2), m1, betweenNoise);
430  BetweenFactor<Similarity3> b2(X(2), X(3), m2, betweenNoise);
431  BetweenFactor<Similarity3> b3(X(3), X(4), m3, betweenNoise);
432  BetweenFactor<Similarity3> b4(X(4), X(5), m4, betweenNoise);
433  BetweenFactor<Similarity3> lc(X(5), X(1), loop, betweenNoise2);
434 
435  // Create graph
437  graph.addPrior(X(1), prior, model); // Prior !
438  graph.push_back(b1);
439  graph.push_back(b2);
440  graph.push_back(b3);
441  graph.push_back(b4);
442  graph.push_back(lc);
443 
444  //graph.print("Full Graph\n");
445  Values initial;
446  initial.insert<Similarity3>(X(1), Similarity3());
447  initial.insert<Similarity3>(X(2),
448  Similarity3(Rot3::Ypr(M_PI / 2.0, 0, 0), Point3(1, 0, 0), 1.1));
449  initial.insert<Similarity3>(X(3),
450  Similarity3(Rot3::Ypr(2.0 * M_PI / 2.0, 0, 0), Point3(0.9, 1.1, 0), 1.2));
451  initial.insert<Similarity3>(X(4),
452  Similarity3(Rot3::Ypr(3.0 * M_PI / 2.0, 0, 0), Point3(0, 1, 0), 1.3));
453  initial.insert<Similarity3>(X(5),
454  Similarity3(Rot3::Ypr(4.0 * M_PI / 2.0, 0, 0), Point3(0, 0, 0), 1.0));
455 
456  //initial.print("Initial Estimate\n");
457 
458  Values result;
459  result = LevenbergMarquardtOptimizer(graph, initial).optimize();
460  //result.print("Optimized Estimate\n");
461  Pose3 p1, p2, p3, p4, p5;
462  p1 = Pose3(result.at<Similarity3>(X(1)));
463  p2 = Pose3(result.at<Similarity3>(X(2)));
464  p3 = Pose3(result.at<Similarity3>(X(3)));
465  p4 = Pose3(result.at<Similarity3>(X(4)));
466  p5 = Pose3(result.at<Similarity3>(X(5)));
467 
468  //p1.print("Pose1");
469  //p2.print("Pose2");
470  //p3.print("Pose3");
471  //p4.print("Pose4");
472  //p5.print("Pose5");
473 
474  Similarity3 expected(0.7);
475  EXPECT(assert_equal(expected, result.at<Similarity3>(X(5)), 0.4));
476 }
477 
478 //******************************************************************************
479 // Align points (p,q) assuming that p = T*q + noise
480 TEST(Similarity3, AlignScaledPointClouds) {
481 // Create ground truth
482  Point3 q1(0, 0, 0), q2(1, 0, 0), q3(0, 1, 0);
483 
484  // Create transformed cloud (noiseless)
485 // Point3 p1 = T4 * q1, p2 = T4 * q2, p3 = T4 * q3;
486 
487  // Create an unknown expression
488  Expression<Similarity3> unknownT(0); // use key 0
489 
490  // Create constant expressions for the ground truth points
491  Expression<Point3> q1_(q1), q2_(q2), q3_(q3);
492 
493  // Create prediction expressions
494  Expression<Point3> predict1(unknownT, &Similarity3::transformFrom, q1_);
495  Expression<Point3> predict2(unknownT, &Similarity3::transformFrom, q2_);
496  Expression<Point3> predict3(unknownT, &Similarity3::transformFrom, q3_);
497 
499 // ExpressionFactorGraph graph;
500 // graph.addExpressionFactor(predict1, p1, R); // |T*q1 - p1|
501 // graph.addExpressionFactor(predict2, p2, R); // |T*q2 - p2|
502 // graph.addExpressionFactor(predict3, p3, R); // |T*q3 - p3|
503 }
504 
505 //******************************************************************************
506 TEST(Similarity3 , Invariants) {
507  Similarity3 id;
508 
509  EXPECT(check_group_invariants(id, id));
510  EXPECT(check_group_invariants(id, T3));
511  EXPECT(check_group_invariants(T2, id));
512  EXPECT(check_group_invariants(T2, T3));
513 
514  EXPECT(check_manifold_invariants(id, id));
515  EXPECT(check_manifold_invariants(id, T3));
516  EXPECT(check_manifold_invariants(T2, id));
517  EXPECT(check_manifold_invariants(T2, T3));
518 }
519 
520 //******************************************************************************
521 TEST(Similarity3 , LieGroupDerivatives) {
522  Similarity3 id;
523 
528 }
529 
530 //******************************************************************************
531 int main() {
532  TestResult tr;
533  return TestRegistry::runAllTests(tr);
534 }
535 //******************************************************************************
536 
static const Similarity3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3), 1)
static const Rot3 R
Point2 q2
Definition: testPose2.cpp:753
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
static const Similarity3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), Point3(3.5,-8.2, 4.2), 1)
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
Definition: Similarity3.h:205
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
virtual const Values & optimize()
Point2 q1
Definition: testPose2.cpp:753
static Point3 p3
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Vector3f p1
Factor Graph consisting of non-linear factors.
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
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
KeyInt p4(x4, 4)
MatrixType m2(n_dims)
ArrayXcf v
Definition: Cwise_arg.cpp:1
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
double scale() const
Return the scale.
Definition: Similarity3.h:196
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Values initial
Vector2 b3(3,-6)
Definition: Half.h:150
Key W(std::uint64_t j)
Some functions to compute numerical derivatives.
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
Matrix3 matrix() const
Definition: Rot3M.cpp:219
Key X(std::uint64_t j)
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
Definition: Rot3M.cpp:85
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
const double degree
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
int main()
static const Similarity3 id
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
Definition: Rot3.h:199
static const Similarity3 T4(R, P, s)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
static const double s
Vector v3
static Rot3 Rodrigues(const Vector3 &w)
Definition: Rot3.h:243
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
static const Point3 P(0.2, 0.7,-2)
Factor graph that supports adding ExpressionFactors directly.
Matrix3d m1
Definition: IOFormat.cpp:2
#define EXPECT(condition)
Definition: Test.h:151
Vector2 b2(4,-5)
static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2)
const Point3 & translation() const
Return a GTSAM translation.
Definition: Similarity3.h:191
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
Point2 q3
Definition: testPose2.cpp:753
KeyInt p5(x5, 5)
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
static SmartStereoProjectionParams params
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
Vector2 b1(2,-1)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
Definition: Similarity3.h:186
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
GTSAM_EXPORT Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Action on a point p is s*(R*p+t)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:75
TEST(LPInitSolver, InfiniteLoopSingleVar)
void setVerbosityLM(const std::string &s)
static const Similarity3 T5(R, P, 10)
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
static Point3 p2
static const Similarity3 T1(R, Point3(3.5,-8.2, 4.2), 1)
Vector3 Point3
Definition: Point3.h:35
std::pair< Pose3, Pose3 > Pose3Pair
Definition: Pose3.h:391
#define X
Definition: icosphere.cpp:20
Implementation of Similarity3 transform.
3D Pose
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
static Rot3 Ry(double t)
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:66
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:38
void test2(OptionalJacobian<-1,-1 > H=boost::none)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:32