-
Notifications
You must be signed in to change notification settings - Fork 755
/
testBoundingConstraint.cpp
276 lines (232 loc) · 10.9 KB
/
testBoundingConstraint.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
/* ----------------------------------------------------------------------------
* 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 testBoundingConstraint.cpp
* @brief test of nonlinear inequality constraints on scalar bounds
* @author Alex Cunningham
*/
#include <tests/simulated2DConstraints.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <CppUnitLite/TestHarness.h>
namespace iq2D = simulated2D::inequality_constraints;
using namespace std;
using namespace gtsam;
static const double tol = 1e-5;
SharedDiagonal soft_model2 = noiseModel::Unit::Create(2);
SharedDiagonal soft_model2_alt = noiseModel::Isotropic::Sigma(2, 0.1);
SharedDiagonal hard_model1 = noiseModel::Constrained::All(1);
// some simple inequality constraints
gtsam::Key key = 1;
double mu = 10.0;
// greater than
iq2D::PoseXInequality constraint1(key, 1.0, true, mu);
iq2D::PoseYInequality constraint2(key, 2.0, true, mu);
// less than
iq2D::PoseXInequality constraint3(key, 1.0, false, mu);
iq2D::PoseYInequality constraint4(key, 2.0, false, mu);
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_basics_inactive1 ) {
Point2 pt1(2.0, 3.0);
Values config;
config.insert(key, pt1);
EXPECT(!constraint1.active(config));
EXPECT(!constraint2.active(config));
EXPECT_DOUBLES_EQUAL(1.0, constraint1.threshold(), tol);
EXPECT_DOUBLES_EQUAL(2.0, constraint2.threshold(), tol);
EXPECT(constraint1.isGreaterThan());
EXPECT(constraint2.isGreaterThan());
EXPECT(assert_equal(I_1x1, constraint1.evaluateError(pt1), tol));
EXPECT(assert_equal(I_1x1, constraint2.evaluateError(pt1), tol));
EXPECT(assert_equal(Z_1x1, constraint1.unwhitenedError(config), tol));
EXPECT(assert_equal(Z_1x1, constraint2.unwhitenedError(config), tol));
EXPECT_DOUBLES_EQUAL(0.0, constraint1.error(config), tol);
EXPECT_DOUBLES_EQUAL(0.0, constraint2.error(config), tol);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_basics_inactive2 ) {
Point2 pt2(-2.0, -3.0);
Values config;
config.insert(key, pt2);
EXPECT(!constraint3.active(config));
EXPECT(!constraint4.active(config));
EXPECT_DOUBLES_EQUAL(1.0, constraint3.threshold(), tol);
EXPECT_DOUBLES_EQUAL(2.0, constraint4.threshold(), tol);
EXPECT(!constraint3.isGreaterThan());
EXPECT(!constraint4.isGreaterThan());
EXPECT(assert_equal(Vector::Constant(1, 3.0), constraint3.evaluateError(pt2), tol));
EXPECT(assert_equal(Vector::Constant(1, 5.0), constraint4.evaluateError(pt2), tol));
EXPECT(assert_equal(Z_1x1, constraint3.unwhitenedError(config), tol));
EXPECT(assert_equal(Z_1x1, constraint4.unwhitenedError(config), tol));
EXPECT_DOUBLES_EQUAL(0.0, constraint3.error(config), tol);
EXPECT_DOUBLES_EQUAL(0.0, constraint4.error(config), tol);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_basics_active1 ) {
Point2 pt2(-2.0, -3.0);
Values config;
config.insert(key, pt2);
EXPECT(constraint1.active(config));
EXPECT(constraint2.active(config));
EXPECT(assert_equal(Vector::Constant(1,-3.0), constraint1.evaluateError(pt2), tol));
EXPECT(assert_equal(Vector::Constant(1,-5.0), constraint2.evaluateError(pt2), tol));
EXPECT(assert_equal(Vector::Constant(1,-3.0), constraint1.unwhitenedError(config), tol));
EXPECT(assert_equal(Vector::Constant(1,-5.0), constraint2.unwhitenedError(config), tol));
EXPECT_DOUBLES_EQUAL(45.0, constraint1.error(config), tol);
EXPECT_DOUBLES_EQUAL(125.0, constraint2.error(config), tol);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_basics_active2 ) {
Point2 pt1(2.0, 3.0);
Values config;
config.insert(key, pt1);
EXPECT(constraint3.active(config));
EXPECT(constraint4.active(config));
EXPECT(assert_equal(-1.0 * I_1x1, constraint3.evaluateError(pt1), tol));
EXPECT(assert_equal(-1.0 * I_1x1, constraint4.evaluateError(pt1), tol));
EXPECT(assert_equal(-1.0 * I_1x1, constraint3.unwhitenedError(config), tol));
EXPECT(assert_equal(-1.0 * I_1x1, constraint4.unwhitenedError(config), tol));
EXPECT_DOUBLES_EQUAL(5.0, constraint3.error(config), tol);
EXPECT_DOUBLES_EQUAL(5.0, constraint4.error(config), tol);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_linearization_inactive) {
Point2 pt1(2.0, 3.0);
Values config1;
config1.insert(key, pt1);
GaussianFactor::shared_ptr actual1 = constraint1.linearize(config1);
GaussianFactor::shared_ptr actual2 = constraint2.linearize(config1);
EXPECT(!actual1);
EXPECT(!actual2);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_linearization_active) {
Point2 pt2(-2.0, -3.0);
Values config2;
config2.insert(key, pt2);
GaussianFactor::shared_ptr actual1 = constraint1.linearize(config2);
GaussianFactor::shared_ptr actual2 = constraint2.linearize(config2);
JacobianFactor expected1(key, (Matrix(1, 2) << 1.0, 0.0).finished(), Vector::Constant(1, 3.0), hard_model1);
JacobianFactor expected2(key, (Matrix(1, 2) << 0.0, 1.0).finished(), Vector::Constant(1, 5.0), hard_model1);
EXPECT(assert_equal((const GaussianFactor&)expected1, *actual1, tol));
EXPECT(assert_equal((const GaussianFactor&)expected2, *actual2, tol));
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_simple_optimization1) {
// create a single-node graph with a soft and hard constraint to
// ensure that the hard constraint overrides the soft constraint
Point2 goal_pt(1.0, 2.0);
Point2 start_pt(0.0, 1.0);
NonlinearFactorGraph graph;
Symbol x1('x',1);
graph += iq2D::PoseXInequality(x1, 1.0, true);
graph += iq2D::PoseYInequality(x1, 2.0, true);
graph += simulated2D::Prior(start_pt, soft_model2, x1);
Values initValues;
initValues.insert(x1, start_pt);
Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
Values expected;
expected.insert(x1, goal_pt);
CHECK(assert_equal(expected, actual, tol));
}
/* ************************************************************************* */
TEST( testBoundingConstraint, unary_simple_optimization2) {
// create a single-node graph with a soft and hard constraint to
// ensure that the hard constraint overrides the soft constraint
Point2 goal_pt(1.0, 2.0);
Point2 start_pt(2.0, 3.0);
NonlinearFactorGraph graph;
graph += iq2D::PoseXInequality(key, 1.0, false);
graph += iq2D::PoseYInequality(key, 2.0, false);
graph += simulated2D::Prior(start_pt, soft_model2, key);
Values initValues;
initValues.insert(key, start_pt);
Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
Values expected;
expected.insert(key, goal_pt);
CHECK(assert_equal(expected, actual, tol));
}
/* ************************************************************************* */
TEST( testBoundingConstraint, MaxDistance_basics) {
gtsam::Key key1 = 1, key2 = 2;
Point2 pt1(0,0), pt2(1.0, 0.0), pt3(2.0, 0.0), pt4(3.0, 0.0);
iq2D::PoseMaxDistConstraint rangeBound(key1, key2, 2.0, mu);
EXPECT_DOUBLES_EQUAL(2.0, rangeBound.threshold(), tol);
EXPECT(!rangeBound.isGreaterThan());
EXPECT(rangeBound.dim() == 1);
EXPECT(assert_equal((Vector(1) << 2.0).finished(), rangeBound.evaluateError(pt1, pt1)));
EXPECT(assert_equal(I_1x1, rangeBound.evaluateError(pt1, pt2)));
EXPECT(assert_equal(Z_1x1, rangeBound.evaluateError(pt1, pt3)));
EXPECT(assert_equal(-1.0*I_1x1, rangeBound.evaluateError(pt1, pt4)));
Values config1;
config1.insert(key1, pt1);
config1.insert(key2, pt1);
EXPECT(!rangeBound.active(config1));
EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
EXPECT(!rangeBound.linearize(config1));
EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
config1.update(key2, pt2);
EXPECT(!rangeBound.active(config1));
EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
EXPECT(!rangeBound.linearize(config1));
EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
config1.update(key2, pt3);
EXPECT(rangeBound.active(config1));
EXPECT(assert_equal(Z_1x1, rangeBound.unwhitenedError(config1)));
EXPECT_DOUBLES_EQUAL(0.0, rangeBound.error(config1), tol);
config1.update(key2, pt4);
EXPECT(rangeBound.active(config1));
EXPECT(assert_equal(-1.0*I_1x1, rangeBound.unwhitenedError(config1)));
EXPECT_DOUBLES_EQUAL(0.5*mu, rangeBound.error(config1), tol);
}
/* ************************************************************************* */
TEST( testBoundingConstraint, MaxDistance_simple_optimization) {
Point2 pt1(0,0), pt2_init(5.0, 0.0), pt2_goal(2.0, 0.0);
Symbol x1('x',1), x2('x',2);
NonlinearFactorGraph graph;
graph += simulated2D::equality_constraints::UnaryEqualityConstraint(pt1, x1);
graph += simulated2D::Prior(pt2_init, soft_model2_alt, x2);
graph += iq2D::PoseMaxDistConstraint(x1, x2, 2.0);
Values initial_state;
initial_state.insert(x1, pt1);
initial_state.insert(x2, pt2_init);
Values expected;
expected.insert(x1, pt1);
expected.insert(x2, pt2_goal);
// FAILS: VectorValues assertion failure
// Optimizer::shared_values actual = Optimizer::optimizeLM(graph, initial_state);
// EXPECT(assert_equal(expected, *actual, tol));
}
/* ************************************************************************* */
TEST( testBoundingConstraint, avoid_demo) {
Symbol x1('x',1), x2('x',2), x3('x',3), l1('l',1);
double radius = 1.0;
Point2 x1_pt(0,0), x2_init(2.0, 0.5), x2_goal(2.0, 1.0), x3_pt(4.0, 0.0), l1_pt(2.0, 0.0);
Point2 odo(2.0, 0.0);
NonlinearFactorGraph graph;
graph += simulated2D::equality_constraints::UnaryEqualityConstraint(x1_pt, x1);
graph += simulated2D::Odometry(odo, soft_model2_alt, x1, x2);
graph += iq2D::LandmarkAvoid(x2, l1, radius);
graph += simulated2D::equality_constraints::UnaryEqualityPointConstraint(l1_pt, l1);
graph += simulated2D::Odometry(odo, soft_model2_alt, x2, x3);
graph += simulated2D::equality_constraints::UnaryEqualityConstraint(x3_pt, x3);
Values init, expected;
init.insert(x1, x1_pt);
init.insert(x3, x3_pt);
init.insert(l1, l1_pt);
expected = init;
init.insert(x2, x2_init);
expected.insert(x2, x2_goal);
// FAILS: segfaults on optimization
// Optimizer::shared_values actual = Optimizer::optimizeLM(graph, init);
// EXPECT(assert_equal(expected, *actual, tol));
}
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */