Skip to content

Commit 838e74d

Browse files
authored
Merge pull request #766 from borglab/refactor/ExpressionTests
refactor Expression tests and add comments
2 parents 4cd3eae + de68189 commit 838e74d

File tree

2 files changed

+78
-56
lines changed

2 files changed

+78
-56
lines changed

gtsam/nonlinear/tests/testExpression.cpp

Lines changed: 46 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -58,22 +58,23 @@ TEST(Expression, Constant) {
5858
/* ************************************************************************* */
5959
// Leaf
6060
TEST(Expression, Leaf) {
61-
Rot3_ R(100);
61+
const Key key = 100;
62+
Rot3_ R(key);
6263
Values values;
63-
values.insert(100, someR);
64+
values.insert(key, someR);
6465

6566
Rot3 actual2 = R.value(values);
6667
EXPECT(assert_equal(someR, actual2));
6768
}
6869

6970
/* ************************************************************************* */
70-
// Many Leaves
71+
// Test the function `createUnknowns` to create many leaves at once.
7172
TEST(Expression, Leaves) {
7273
Values values;
73-
Point3 somePoint(1, 2, 3);
74+
const Point3 somePoint(1, 2, 3);
7475
values.insert(Symbol('p', 10), somePoint);
75-
std::vector<Point3_> points = createUnknowns<Point3>(10, 'p', 1);
76-
EXPECT(assert_equal(somePoint, points.back().value(values)));
76+
std::vector<Point3_> pointExpressions = createUnknowns<Point3>(10, 'p', 1);
77+
EXPECT(assert_equal(somePoint, pointExpressions.back().value(values)));
7778
}
7879

7980
/* ************************************************************************* */
@@ -88,29 +89,34 @@ double f2(const Point3& p, OptionalJacobian<1, 3> H) {
8889
Vector f3(const Point3& p, OptionalJacobian<Eigen::Dynamic, 3> H) {
8990
return p;
9091
}
91-
Point3_ p(1);
92+
Point3_ pointExpression(1);
9293
set<Key> expected = list_of(1);
9394
} // namespace unary
9495

96+
// Create a unary expression that takes another expression as a single argument.
9597
TEST(Expression, Unary1) {
9698
using namespace unary;
97-
Expression<Point2> e(f1, p);
98-
EXPECT(expected == e.keys());
99+
Expression<Point2> unaryExpression(f1, pointExpression);
100+
EXPECT(expected == unaryExpression.keys());
99101
}
102+
103+
// Check that also works with a scalar return value.
100104
TEST(Expression, Unary2) {
101105
using namespace unary;
102-
Double_ e(f2, p);
103-
EXPECT(expected == e.keys());
106+
Double_ unaryExpression(f2, pointExpression);
107+
EXPECT(expected == unaryExpression.keys());
104108
}
105109

106-
/* ************************************************************************* */
107110
// Unary(Leaf), dynamic
108111
TEST(Expression, Unary3) {
109112
using namespace unary;
110-
// Expression<Vector> e(f3, p);
113+
// TODO(yetongumich): dynamic output arguments do not work yet!
114+
// Expression<Vector> unaryExpression(f3, pointExpression);
115+
// EXPECT(expected == unaryExpression.keys());
111116
}
112117

113118
/* ************************************************************************* */
119+
// Simple test class that implements the `VectorSpace` protocol.
114120
class Class : public Point3 {
115121
public:
116122
enum {dimension = 3};
@@ -133,26 +139,31 @@ template<> struct traits<Class> : public internal::VectorSpace<Class> {};
133139
// Nullary Method
134140
TEST(Expression, NullaryMethod) {
135141
// Create expression
136-
Expression<Class> p(67);
137-
Expression<double> norm_(p, &Class::norm);
142+
const Key key(67);
143+
Expression<Class> classExpression(key);
144+
145+
// Make expression from a class method, note how it differs from the function
146+
// expressions by leading with the class expression in the constructor.
147+
Expression<double> norm_(classExpression, &Class::norm);
138148

139149
// Create Values
140150
Values values;
141-
values.insert(67, Class(3, 4, 5));
151+
values.insert(key, Class(3, 4, 5));
142152

143153
// Check dims as map
144154
std::map<Key, int> map;
145-
norm_.dims(map);
155+
norm_.dims(map); // TODO(yetongumich): Change to google style pointer convention.
146156
LONGS_EQUAL(1, map.size());
147157

148158
// Get value and Jacobians
149159
std::vector<Matrix> H(1);
150160
double actual = norm_.value(values, H);
151161

152162
// Check all
153-
EXPECT(actual == sqrt(50));
163+
const double norm = sqrt(3*3 + 4*4 + 5*5);
164+
EXPECT(actual == norm);
154165
Matrix expected(1, 3);
155-
expected << 3.0 / sqrt(50.0), 4.0 / sqrt(50.0), 5.0 / sqrt(50.0);
166+
expected << 3.0 / norm, 4.0 / norm, 5.0 / norm;
156167
EXPECT(assert_equal(expected, H[0]));
157168
}
158169

@@ -170,29 +181,29 @@ Point3_ p_cam(x, &Pose3::transformTo, p);
170181
}
171182

172183
/* ************************************************************************* */
173-
// Check that creating an expression to double compiles
184+
// Check that creating an expression to double compiles.
174185
TEST(Expression, BinaryToDouble) {
175186
using namespace binary;
176187
Double_ p_cam(doubleF, x, p);
177188
}
178189

179190
/* ************************************************************************* */
180-
// keys
191+
// Check keys of an expression created from class method.
181192
TEST(Expression, BinaryKeys) {
182193
set<Key> expected = list_of(1)(2);
183194
EXPECT(expected == binary::p_cam.keys());
184195
}
185196

186197
/* ************************************************************************* */
187-
// dimensions
198+
// Check dimensions by calling `dims` method.
188199
TEST(Expression, BinaryDimensions) {
189200
map<Key, int> actual, expected = map_list_of<Key, int>(1, 6)(2, 3);
190201
binary::p_cam.dims(actual);
191202
EXPECT(actual == expected);
192203
}
193204

194205
/* ************************************************************************* */
195-
// dimensions
206+
// Check dimensions of execution trace.
196207
TEST(Expression, BinaryTraceSize) {
197208
typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary;
198209
size_t expectedTraceSize = sizeof(Binary::Record);
@@ -247,6 +258,7 @@ TEST(Expression, TreeTraceSize) {
247258
}
248259

249260
/* ************************************************************************* */
261+
// Test compose operation with * operator.
250262
TEST(Expression, compose1) {
251263
// Create expression
252264
Rot3_ R1(1), R2(2);
@@ -258,7 +270,7 @@ TEST(Expression, compose1) {
258270
}
259271

260272
/* ************************************************************************* */
261-
// Test compose with arguments referring to the same rotation
273+
// Test compose with arguments referring to the same rotation.
262274
TEST(Expression, compose2) {
263275
// Create expression
264276
Rot3_ R1(1), R2(1);
@@ -270,7 +282,7 @@ TEST(Expression, compose2) {
270282
}
271283

272284
/* ************************************************************************* */
273-
// Test compose with one arguments referring to constant rotation
285+
// Test compose with one arguments referring to constant rotation.
274286
TEST(Expression, compose3) {
275287
// Create expression
276288
Rot3_ R1(Rot3::identity()), R2(3);
@@ -282,7 +294,7 @@ TEST(Expression, compose3) {
282294
}
283295

284296
/* ************************************************************************* */
285-
// Test with ternary function
297+
// Test with ternary function.
286298
Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3, OptionalJacobian<3, 3> H1,
287299
OptionalJacobian<3, 3> H2, OptionalJacobian<3, 3> H3) {
288300
// return dummy derivatives (not correct, but that's ok for testing here)
@@ -306,6 +318,7 @@ TEST(Expression, ternary) {
306318
}
307319

308320
/* ************************************************************************* */
321+
// Test scalar multiplication with * operator.
309322
TEST(Expression, ScalarMultiply) {
310323
const Key key(67);
311324
const Point3_ expr = 23 * Point3_(key);
@@ -336,6 +349,7 @@ TEST(Expression, ScalarMultiply) {
336349
}
337350

338351
/* ************************************************************************* */
352+
// Test sum with + operator.
339353
TEST(Expression, BinarySum) {
340354
const Key key(67);
341355
const Point3_ sum_ = Point3_(key) + Point3_(Point3(1, 1, 1));
@@ -366,6 +380,7 @@ TEST(Expression, BinarySum) {
366380
}
367381

368382
/* ************************************************************************* */
383+
// Test sum of 3 variables with + operator.
369384
TEST(Expression, TripleSum) {
370385
const Key key(67);
371386
const Point3_ p1_(Point3(1, 1, 1)), p2_(key);
@@ -387,6 +402,7 @@ TEST(Expression, TripleSum) {
387402
}
388403

389404
/* ************************************************************************* */
405+
// Test sum with += operator.
390406
TEST(Expression, PlusEqual) {
391407
const Key key(67);
392408
const Point3_ p1_(Point3(1, 1, 1)), p2_(key);
@@ -461,11 +477,12 @@ TEST(Expression, WeightedSum) {
461477
EXPECT(actual_dims == expected_dims);
462478

463479
Values values;
464-
values.insert<Point3>(key1, Point3(1, 0, 0));
465-
values.insert<Point3>(key2, Point3(0, 1, 0));
480+
const Point3 point1(1, 0, 0), point2(0, 1, 0);
481+
values.insert<Point3>(key1, point1);
482+
values.insert<Point3>(key2, point2);
466483

467484
// Check value
468-
const Point3 expected = 17 * Point3(1, 0, 0) + 23 * Point3(0, 1, 0);
485+
const Point3 expected = 17 * point1 + 23 * point2;
469486
EXPECT(assert_equal(expected, weighted_sum_.value(values)));
470487

471488
// Check value + Jacobians

0 commit comments

Comments
 (0)