-
Notifications
You must be signed in to change notification settings - Fork 795
/
Copy pathtestNonlinearEquality.cpp
587 lines (470 loc) · 19 KB
/
testNonlinearEquality.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/*
* @file testNonlinearEquality.cpp
* @author Alex Cunningham
*/
#include <tests/simulated2DConstraints.h>
#include <gtsam/nonlinear/PriorFactor.h>
#include <gtsam/slam/ProjectionFactor.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;
using namespace gtsam;
namespace eq2D = simulated2D::equality_constraints;
static const double tol = 1e-5;
typedef PriorFactor<Pose2> PosePrior;
typedef NonlinearEquality<Pose2> PoseNLE;
typedef boost::shared_ptr<PoseNLE> shared_poseNLE;
static Symbol key('x', 1);
//******************************************************************************
TEST ( NonlinearEquality, linearization ) {
Pose2 value = Pose2(2.1, 1.0, 2.0);
Values linearize;
linearize.insert(key, value);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
// check linearize
SharedDiagonal constraintModel = noiseModel::Constrained::All(3);
JacobianFactor expLF(key, I_3x3, Z_3x1, constraintModel);
GaussianFactor::shared_ptr actualLF = nle->linearize(linearize);
EXPECT(assert_equal((const GaussianFactor&)expLF, *actualLF));
}
//******************************************************************************
TEST ( NonlinearEquality, linearization_pose ) {
Symbol key('x', 1);
Pose2 value;
Values config;
config.insert(key, value);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
GaussianFactor::shared_ptr actualLF = nle->linearize(config);
EXPECT(true);
}
//******************************************************************************
TEST ( NonlinearEquality, linearization_fail ) {
Pose2 value = Pose2(2.1, 1.0, 2.0);
Pose2 wrong = Pose2(2.1, 3.0, 4.0);
Values bad_linearize;
bad_linearize.insert(key, wrong);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
// check linearize to ensure that it fails for bad linearization points
CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
}
//******************************************************************************
TEST ( NonlinearEquality, linearization_fail_pose ) {
Symbol key('x', 1);
Pose2 value(2.0, 1.0, 2.0), wrong(2.0, 3.0, 4.0);
Values bad_linearize;
bad_linearize.insert(key, wrong);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
// check linearize to ensure that it fails for bad linearization points
CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
}
//******************************************************************************
TEST ( NonlinearEquality, linearization_fail_pose_origin ) {
Symbol key('x', 1);
Pose2 value, wrong(2.0, 3.0, 4.0);
Values bad_linearize;
bad_linearize.insert(key, wrong);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
// check linearize to ensure that it fails for bad linearization points
CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
}
//******************************************************************************
TEST ( NonlinearEquality, error ) {
Pose2 value = Pose2(2.1, 1.0, 2.0);
Pose2 wrong = Pose2(2.1, 3.0, 4.0);
Values feasible, bad_linearize;
feasible.insert(key, value);
bad_linearize.insert(key, wrong);
// create a nonlinear equality constraint
shared_poseNLE nle(new PoseNLE(key, value));
// check error function outputs
Vector actual = nle->unwhitenedError(feasible);
EXPECT(assert_equal(actual, Z_3x1));
actual = nle->unwhitenedError(bad_linearize);
EXPECT(
assert_equal(actual, Vector::Constant(3, std::numeric_limits<double>::infinity())));
}
//******************************************************************************
TEST ( NonlinearEquality, equals ) {
Pose2 value1 = Pose2(2.1, 1.0, 2.0);
Pose2 value2 = Pose2(2.1, 3.0, 4.0);
// create some constraints to compare
shared_poseNLE nle1(new PoseNLE(key, value1));
shared_poseNLE nle2(new PoseNLE(key, value1));
shared_poseNLE nle3(new PoseNLE(key, value2));
// verify
EXPECT(nle1->equals(*nle2));
// basic equality = true
EXPECT(nle2->equals(*nle1));
// test symmetry of equals()
EXPECT(!nle1->equals(*nle3));
// test config
}
//******************************************************************************
TEST ( NonlinearEquality, allow_error_pose ) {
Symbol key1('x', 1);
Pose2 feasible1(1.0, 2.0, 3.0);
double error_gain = 500.0;
PoseNLE nle(key1, feasible1, error_gain);
// the unwhitened error should provide logmap to the feasible state
Pose2 badPoint1(0.0, 2.0, 3.0);
Vector actVec = nle.evaluateError(badPoint1);
Vector expVec = Vector3(-0.989992, -0.14112, 0.0);
EXPECT(assert_equal(expVec, actVec, 1e-5));
// the actual error should have a gain on it
Values config;
config.insert(key1, badPoint1);
double actError = nle.error(config);
DOUBLES_EQUAL(500.0, actError, 1e-9);
// check linearization
GaussianFactor::shared_ptr actLinFactor = nle.linearize(config);
Matrix A1 = I_3x3;
Vector b = expVec;
SharedDiagonal model = noiseModel::Constrained::All(3);
GaussianFactor::shared_ptr expLinFactor(
new JacobianFactor(key1, A1, b, model));
EXPECT(assert_equal(*expLinFactor, *actLinFactor, 1e-5));
}
//******************************************************************************
TEST ( NonlinearEquality, allow_error_optimize ) {
Symbol key1('x', 1);
Pose2 feasible1(1.0, 2.0, 3.0);
double error_gain = 500.0;
PoseNLE nle(key1, feasible1, error_gain);
// add to a graph
NonlinearFactorGraph graph;
graph += nle;
// initialize away from the ideal
Pose2 initPose(0.0, 2.0, 3.0);
Values init;
init.insert(key1, initPose);
// optimize
Ordering ordering;
ordering.push_back(key1);
Values result = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
// verify
Values expected;
expected.insert(key1, feasible1);
EXPECT(assert_equal(expected, result));
}
//******************************************************************************
TEST ( NonlinearEquality, allow_error_optimize_with_factors ) {
// create a hard constraint
Symbol key1('x', 1);
Pose2 feasible1(1.0, 2.0, 3.0);
// initialize away from the ideal
Values init;
Pose2 initPose(0.0, 2.0, 3.0);
init.insert(key1, initPose);
double error_gain = 500.0;
PoseNLE nle(key1, feasible1, error_gain);
// create a soft prior that conflicts
PosePrior prior(key1, initPose, noiseModel::Isotropic::Sigma(3, 0.1));
// add to a graph
NonlinearFactorGraph graph;
graph += nle;
graph += prior;
// optimize
Ordering ordering;
ordering.push_back(key1);
Values actual = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
// verify
Values expected;
expected.insert(key1, feasible1);
EXPECT(assert_equal(expected, actual));
}
//******************************************************************************
static SharedDiagonal hard_model = noiseModel::Constrained::All(2);
static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0);
//******************************************************************************
TEST( testNonlinearEqualityConstraint, unary_basics ) {
Point2 pt(1.0, 2.0);
Symbol key1('x', 1);
double mu = 1000.0;
eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
Values config1;
config1.insert(key, pt);
EXPECT(constraint.active(config1));
EXPECT(assert_equal(Z_2x1, constraint.evaluateError(pt), tol));
EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
Values config2;
Point2 ptBad1(2.0, 2.0);
config2.insert(key, ptBad1);
EXPECT(constraint.active(config2));
EXPECT(
assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol));
EXPECT(
assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol));
EXPECT_DOUBLES_EQUAL(500.0, constraint.error(config2), tol);
}
//******************************************************************************
TEST( testNonlinearEqualityConstraint, unary_linearization ) {
Point2 pt(1.0, 2.0);
Symbol key1('x', 1);
double mu = 1000.0;
eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
Values config1;
config1.insert(key, pt);
GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
GaussianFactor::shared_ptr expected1(
new JacobianFactor(key, I_2x2, Z_2x1, hard_model));
EXPECT(assert_equal(*expected1, *actual1, tol));
Values config2;
Point2 ptBad(2.0, 2.0);
config2.insert(key, ptBad);
GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
GaussianFactor::shared_ptr expected2(
new JacobianFactor(key, I_2x2, Vector2(-1.0, 0.0), hard_model));
EXPECT(assert_equal(*expected2, *actual2, tol));
}
//******************************************************************************
TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) {
// create a single-node graph with a soft and hard constraint to
// ensure that the hard constraint overrides the soft constraint
Point2 truth_pt(1.0, 2.0);
Symbol key('x', 1);
double mu = 10.0;
eq2D::UnaryEqualityConstraint::shared_ptr constraint(
new eq2D::UnaryEqualityConstraint(truth_pt, key, mu));
Point2 badPt(100.0, -200.0);
simulated2D::Prior::shared_ptr factor(
new simulated2D::Prior(badPt, soft_model, key));
NonlinearFactorGraph graph;
graph.push_back(constraint);
graph.push_back(factor);
Values initValues;
initValues.insert(key, badPt);
// verify error values
EXPECT(constraint->active(initValues));
Values expected;
expected.insert(key, truth_pt);
EXPECT(constraint->active(expected));
EXPECT_DOUBLES_EQUAL(0.0, constraint->error(expected), tol);
Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
EXPECT(assert_equal(expected, actual, tol));
}
//******************************************************************************
TEST( testNonlinearEqualityConstraint, odo_basics ) {
Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
Symbol key1('x', 1), key2('x', 2);
double mu = 1000.0;
eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
Values config1;
config1.insert(key1, x1);
config1.insert(key2, x2);
EXPECT(constraint.active(config1));
EXPECT(assert_equal(Z_2x1, constraint.evaluateError(x1, x2), tol));
EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
Values config2;
Point2 x1bad(2.0, 2.0);
Point2 x2bad(2.0, 2.0);
config2.insert(key1, x1bad);
config2.insert(key2, x2bad);
EXPECT(constraint.active(config2));
EXPECT(
assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol));
EXPECT(
assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol));
EXPECT_DOUBLES_EQUAL(1000.0, constraint.error(config2), tol);
}
//******************************************************************************
TEST( testNonlinearEqualityConstraint, odo_linearization ) {
Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
Symbol key1('x', 1), key2('x', 2);
double mu = 1000.0;
eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
Values config1;
config1.insert(key1, x1);
config1.insert(key2, x2);
GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
GaussianFactor::shared_ptr expected1(
new JacobianFactor(key1, -I_2x2, key2, I_2x2, Z_2x1,
hard_model));
EXPECT(assert_equal(*expected1, *actual1, tol));
Values config2;
Point2 x1bad(2.0, 2.0);
Point2 x2bad(2.0, 2.0);
config2.insert(key1, x1bad);
config2.insert(key2, x2bad);
GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
GaussianFactor::shared_ptr expected2(
new JacobianFactor(key1, -I_2x2, key2, I_2x2, Vector2(1.0, 1.0),
hard_model));
EXPECT(assert_equal(*expected2, *actual2, tol));
}
//******************************************************************************
TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) {
// create a two-node graph, connected by an odometry constraint, with
// a hard prior on one variable, and a conflicting soft prior
// on the other variable - the constraints should override the soft constraint
Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0);
Symbol key1('x', 1), key2('x', 2);
// hard prior on x1
eq2D::UnaryEqualityConstraint::shared_ptr constraint1(
new eq2D::UnaryEqualityConstraint(truth_pt1, key1));
// soft prior on x2
Point2 badPt(100.0, -200.0);
simulated2D::Prior::shared_ptr factor(
new simulated2D::Prior(badPt, soft_model, key2));
// odometry constraint
eq2D::OdoEqualityConstraint::shared_ptr constraint2(
new eq2D::OdoEqualityConstraint(truth_pt2-truth_pt1, key1, key2));
NonlinearFactorGraph graph;
graph.push_back(constraint1);
graph.push_back(constraint2);
graph.push_back(factor);
Values initValues;
initValues.insert(key1, Point2(0,0));
initValues.insert(key2, badPt);
Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
Values expected;
expected.insert(key1, truth_pt1);
expected.insert(key2, truth_pt2);
CHECK(assert_equal(expected, actual, tol));
}
//******************************************************************************
TEST (testNonlinearEqualityConstraint, two_pose ) {
/*
* Determining a ground truth linear system
* with two poses seeing one landmark, with each pose
* constrained to a particular value
*/
NonlinearFactorGraph graph;
Symbol x1('x', 1), x2('x', 2);
Symbol l1('l', 1), l2('l', 2);
Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0);
graph += eq2D::UnaryEqualityConstraint(pt_x1, x1);
graph += eq2D::UnaryEqualityConstraint(pt_x2, x2);
Point2 z1(0.0, 5.0);
SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2, 0.1));
graph += simulated2D::Measurement(z1, sigma, x1, l1);
Point2 z2(-4.0, 0.0);
graph += simulated2D::Measurement(z2, sigma, x2, l2);
graph += eq2D::PointEqualityConstraint(l1, l2);
Values initialEstimate;
initialEstimate.insert(x1, pt_x1);
initialEstimate.insert(x2, Point2(0,0));
initialEstimate.insert(l1, Point2(1.0, 6.0)); // ground truth
initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
Values actual =
LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
Values expected;
expected.insert(x1, pt_x1);
expected.insert(l1, Point2(1.0, 6.0));
expected.insert(l2, Point2(1.0, 6.0));
expected.insert(x2, Point2(5.0, 6.0));
CHECK(assert_equal(expected, actual, 1e-5));
}
//******************************************************************************
TEST (testNonlinearEqualityConstraint, map_warp ) {
// get a graph
NonlinearFactorGraph graph;
// keys
Symbol x1('x', 1), x2('x', 2);
Symbol l1('l', 1), l2('l', 2);
// constant constraint on x1
Point2 pose1(1.0, 1.0);
graph += eq2D::UnaryEqualityConstraint(pose1, x1);
SharedDiagonal sigma = noiseModel::Isotropic::Sigma(2, 0.1);
// measurement from x1 to l1
Point2 z1(0.0, 5.0);
graph += simulated2D::Measurement(z1, sigma, x1, l1);
// measurement from x2 to l2
Point2 z2(-4.0, 0.0);
graph += simulated2D::Measurement(z2, sigma, x2, l2);
// equality constraint between l1 and l2
graph += eq2D::PointEqualityConstraint(l1, l2);
// create an initial estimate
Values initialEstimate;
initialEstimate.insert(x1, Point2(1.0, 1.0));
initialEstimate.insert(l1, Point2(1.0, 6.0));
initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
initialEstimate.insert(x2, Point2(0.0, 0.0)); // other pose starts at origin
// optimize
Values actual =
LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
Values expected;
expected.insert(x1, Point2(1.0, 1.0));
expected.insert(l1, Point2(1.0, 6.0));
expected.insert(l2, Point2(1.0, 6.0));
expected.insert(x2, Point2(5.0, 6.0));
CHECK(assert_equal(expected, actual, tol));
}
//******************************************************************************
TEST (testNonlinearEqualityConstraint, stereo_constrained ) {
// make a realistic calibration matrix
static double fov = 60; // degrees
static int w = 640, h = 480;
static Cal3_S2 K(fov, w, h);
static boost::shared_ptr<Cal3_S2> shK(new Cal3_S2(K));
// create initial estimates
Rot3 faceTowardsY(Point3(1, 0, 0), Point3(0, 0, -1), Point3(0, 1, 0));
Pose3 poseLeft(faceTowardsY, Point3(0, 0, 0)); // origin, left camera
PinholeCamera<Cal3_S2> leftCamera(poseLeft, K);
Pose3 poseRight(faceTowardsY, Point3(2, 0, 0)); // 2 units to the right
PinholeCamera<Cal3_S2> rightCamera(poseRight, K);
Point3 landmark(1, 5, 0); //centered between the cameras, 5 units away
// keys
Symbol key_x1('x', 1), key_x2('x', 2);
Symbol key_l1('l', 1), key_l2('l', 2);
// create graph
NonlinearFactorGraph graph;
// create equality constraints for poses
graph += NonlinearEquality<Pose3>(key_x1, leftCamera.pose());
graph += NonlinearEquality<Pose3>(key_x2, rightCamera.pose());
// create factors
SharedDiagonal vmodel = noiseModel::Unit::Create(2);
graph += GenericProjectionFactor<Pose3, Point3, Cal3_S2>(
leftCamera.project(landmark), vmodel, key_x1, key_l1, shK);
graph += GenericProjectionFactor<Pose3, Point3, Cal3_S2>(
rightCamera.project(landmark), vmodel, key_x2, key_l2, shK);
// add equality constraint saying there is only one point
graph += NonlinearEquality2<Point3>(key_l1, key_l2);
// create initial data
Point3 landmark1(0.5, 5, 0);
Point3 landmark2(1.5, 5, 0);
Values initValues;
initValues.insert(key_x1, poseLeft);
initValues.insert(key_x2, poseRight);
initValues.insert(key_l1, landmark1);
initValues.insert(key_l2, landmark2);
// optimize
Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
// create config
Values truthValues;
truthValues.insert(key_x1, leftCamera.pose());
truthValues.insert(key_x2, rightCamera.pose());
truthValues.insert(key_l1, landmark);
truthValues.insert(key_l2, landmark);
// check if correct
CHECK(assert_equal(truthValues, actual, 1e-5));
}
//******************************************************************************
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
//******************************************************************************