testExpression.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  * -------------------------------1------------------------------------------- */
11 
21 #include <gtsam/geometry/Cal3_S2.h>
23 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/base/Testable.h>
25 
27 
28 using namespace std;
29 using namespace gtsam;
30 
34 
35 /* ************************************************************************* */
36 template <class CAL>
39  return K.uncalibrate(p, Dcal, Dp);
40 }
41 
42 static const Rot3 someR = Rot3::RzRyRx(1, 2, 3);
43 
44 /* ************************************************************************* */
45 // Constant
46 TEST(Expression, Constant) {
47  Rot3_ R(someR);
48  Values values;
49  Rot3 actual = R.value(values);
50  EXPECT(assert_equal(someR, actual))
51  EXPECT_LONGS_EQUAL(0, R.traceSize())
52 }
53 
54 /* ************************************************************************* */
55 // Leaf
57  const Key key = 100;
58  Rot3_ R(key);
59  Values values;
61 
62  Rot3 actual2 = R.value(values);
63  EXPECT(assert_equal(someR, actual2))
64 }
65 
66 /* ************************************************************************* */
67 // Test the function `createUnknowns` to create many leaves at once.
68 TEST(Expression, Leaves) {
69  Values values;
70  const Point3 somePoint(1, 2, 3);
71  values.insert(Symbol('p', 10), somePoint);
72  std::vector<Point3_> pointExpressions = createUnknowns<Point3>(10, 'p', 1);
73  EXPECT(assert_equal(somePoint, pointExpressions.back().value(values)))
74 }
75 
76 /* ************************************************************************* */
77 // Unary(Leaf)
78 namespace unary {
80  return Point2(0,0);
81 }
82 double f2(const Point3& p, OptionalJacobian<1, 3> H) {
83  return 0.0;
84 }
86  return p;
87 }
89 const set<Key> expected{1};
90 } // namespace unary
91 
92 // Create a unary expression that takes another expression as a single argument.
93 TEST(Expression, Unary1) {
94  using namespace unary;
95  Expression<Point2> unaryExpression(f1, pointExpression);
96  EXPECT(expected == unaryExpression.keys())
97 }
98 
99 // Check that also works with a scalar return value.
100 TEST(Expression, Unary2) {
101  using namespace unary;
102  Double_ unaryExpression(f2, pointExpression);
103  EXPECT(expected == unaryExpression.keys())
104 }
105 
106 // Unary(Leaf), dynamic
107 TEST(Expression, Unary3) {
108  using namespace unary;
109  // TODO(yetongumich): dynamic output arguments do not work yet!
110  // Expression<Vector> unaryExpression(f3, pointExpression);
111  // EXPECT(expected == unaryExpression.keys())
112 }
113 
114 /* ************************************************************************* */
115 // Simple test class that implements the `VectorSpace` protocol.
116 class Class : public Point3 {
117  public:
118  inline constexpr static auto dimension = 3;
119  using Point3::Point3;
120  const Vector3& vector() const { return *this; }
121  inline static Class Identity() { return Class(0,0,0); }
122  double norm(OptionalJacobian<1,3> H = {}) const {
123  return norm3(*this, H);
124  }
125  bool equals(const Class &q, double tol) const {
126  return (std::abs(x() - q.x()) < tol && std::abs(y() - q.y()) < tol && std::abs(z() - q.z()) < tol);
127  }
128  void print(const string& s) const { cout << s << *this << endl;}
129 };
130 
131 namespace gtsam {
132 template<> struct traits<Class> : public internal::VectorSpace<Class> {};
133 }
134 
135 // Nullary Method
136 TEST(Expression, NullaryMethod) {
137  // Create expression
138  const Key key(67);
139  Expression<Class> classExpression(key);
140 
141  // Make expression from a class method, note how it differs from the function
142  // expressions by leading with the class expression in the constructor.
143  Expression<double> norm_(classExpression, &Class::norm);
144 
145  // Create Values
146  Values values;
147  values.insert(key, Class(3, 4, 5));
148 
149  // Check dims as map
150  std::map<Key, int> map;
151  norm_.dims(map); // TODO(yetongumich): Change to google style pointer convention.
152  LONGS_EQUAL(1, map.size())
153 
154  // Get value and Jacobians
155  std::vector<Matrix> H(1);
156  double actual = norm_.value(values, H);
157 
158  // Check all
159  const double norm = sqrt(3*3 + 4*4 + 5*5);
160  EXPECT(actual == norm)
161  Matrix expected(1, 3);
162  expected << 3.0 / norm, 4.0 / norm, 5.0 / norm;
164 }
165 
166 /* ************************************************************************* */
167 // Binary(Leaf,Leaf)
168 namespace binary {
169 // Create leaves
170 double doubleF(const Pose3& pose, //
172  return 0.0;
173 }
174 Pose3_ x(1);
175 Point3_ p(2);
177 }
178 
179 /* ************************************************************************* */
180 // Check that creating an expression to double compiles.
181 TEST(Expression, BinaryToDouble) {
182  using namespace binary;
183  Double_ p_cam(doubleF, x, p);
184 }
185 
186 /* ************************************************************************* */
187 // Check keys of an expression created from class method.
188 TEST(Expression, BinaryKeys) {
189  const set<Key> expected{1, 2};
191 }
192 
193 /* ************************************************************************* */
194 // Check dimensions by calling `dims` method.
195 TEST(Expression, BinaryDimensions) {
196  map<Key, int> actual, expected{{1, 6}, {2, 3}};
197  binary::p_cam.dims(actual);
198  EXPECT(actual == expected)
199 }
200 
201 /* ************************************************************************* */
202 // Check dimensions of execution trace.
203 TEST(Expression, BinaryTraceSize) {
204  typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary;
205  size_t expectedTraceSize = sizeof(Binary::Record);
206  internal::upAlign(expectedTraceSize);
207  EXPECT_LONGS_EQUAL(expectedTraceSize, binary::p_cam.traceSize())
208 }
209 
210 /* ************************************************************************* */
211 // Binary(Leaf,Unary(Binary(Leaf,Leaf)))
212 namespace tree {
213 using namespace binary;
214 // Create leaves
216 
217 // Create expression tree
220 Expression<Point2> uv_hat(uncalibrate<Cal3_S2>, K, projection);
221 }
222 
223 /* ************************************************************************* */
224 // keys
225 TEST(Expression, TreeKeys) {
226  const set<Key> expected{1, 2, 3};
228 }
229 
230 /* ************************************************************************* */
231 // dimensions
232 TEST(Expression, TreeDimensions) {
233  map<Key, int> actual, expected{{1, 6}, {2, 3}, {3, 5}};
234  tree::uv_hat.dims(actual);
235  EXPECT(actual == expected)
236 }
237 
238 /* ************************************************************************* */
239 // TraceSize
240 TEST(Expression, TreeTraceSize) {
241  typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary1;
242  EXPECT_LONGS_EQUAL(internal::upAligned(sizeof(Binary1::Record)), tree::p_cam.traceSize())
243 
244  typedef internal::UnaryExpression<Point2, Point3> Unary;
245  EXPECT_LONGS_EQUAL(internal::upAligned(sizeof(Unary::Record)) + tree::p_cam.traceSize(),
246  tree::projection.traceSize())
247 
248  EXPECT_LONGS_EQUAL(0, tree::K.traceSize())
249 
250  typedef internal::BinaryExpression<Point2, Cal3_S2, Point2> Binary2;
251  EXPECT_LONGS_EQUAL(internal::upAligned(sizeof(Binary2::Record)) + tree::K.traceSize() +
252  tree::projection.traceSize(),
253  tree::uv_hat.traceSize())
254 }
255 
256 /* ************************************************************************* */
257 // Test compose operation with * operator.
258 TEST(Expression, compose1) {
259  // Create expression
260  Rot3_ R1(1), R2(2);
261  Rot3_ R3 = R1 * R2;
262 
263  // Check keys
264  const set<Key> expected{1, 2};
265  EXPECT(expected == R3.keys())
266 }
267 
268 /* ************************************************************************* */
269 // Test compose with arguments referring to the same rotation.
270 TEST(Expression, compose2) {
271  // Create expression
272  Rot3_ R1(1), R2(1);
273  Rot3_ R3 = R1 * R2;
274 
275  // Check keys
276  const set<Key> expected{1};
277  EXPECT(expected == R3.keys())
278 }
279 
280 /* ************************************************************************* */
281 // Test compose with one arguments referring to constant rotation.
282 TEST(Expression, compose3) {
283  // Create expression
284  Rot3_ R1(Rot3::Identity()), R2(3);
285  Rot3_ R3 = R1 * R2;
286 
287  // Check keys
288  const set<Key> expected{3};
289  EXPECT(expected == R3.keys())
290 }
291 
292 /* ************************************************************************* */
293 // Test compose with double type (should be multiplication).
294 TEST(Expression, compose4) {
295  // Create expression
296  gtsam::Key key = 1;
297  Double_ R1(key), R2(key);
298  Double_ R3 = R1 * R2;
299 
300  // Check keys
301  const set<Key> expected{1};
302  EXPECT(expected == R3.keys())
303 }
304 
305 /* ************************************************************************* */
306 // Test with ternary function.
309  // return dummy derivatives (not correct, but that's ok for testing here)
310  if (H1)
311  *H1 = I_3x3;
312  if (H2)
313  *H2 = I_3x3;
314  if (H3)
315  *H3 = I_3x3;
316  return R1 * (R2 * R3);
317 }
318 
319 TEST(Expression, ternary) {
320  // Create expression
321  Rot3_ A(1), B(2), C(3);
322  Rot3_ ABC(composeThree, A, B, C);
323 
324  // Check keys
325  const set<Key> expected {1, 2, 3};
326  EXPECT(expected == ABC.keys())
327 }
328 
329 /* ************************************************************************* */
330 // Test scalar multiplication with * operator.
331 TEST(Expression, ScalarMultiply) {
332  const Key key(67);
333  const Point3_ expr = 23 * Point3_(key);
334 
335  const set<Key> expected_keys{key};
336  EXPECT(expected_keys == expr.keys())
337 
338  map<Key, int> actual_dims, expected_dims {{key, 3}};
339  expr.dims(actual_dims);
340  EXPECT(actual_dims == expected_dims)
341 
342  // Check dims as map
343  std::map<Key, int> map;
344  expr.dims(map);
345  LONGS_EQUAL(1, map.size())
346 
347  Values values;
348  values.insert<Point3>(key, Point3(1, 0, 2));
349 
350  // Check value
351  const Point3 expected(23, 0, 46);
353 
354  // Check value + Jacobians
355  std::vector<Matrix> H(1);
357  EXPECT(assert_equal(23 * I_3x3, H[0]))
358 }
359 
360 /* ************************************************************************* */
361 // Test sum with + operator.
362 TEST(Expression, BinarySum) {
363  const Key key(67);
364  const Point3_ sum_ = Point3_(key) + Point3_(Point3(1, 1, 1));
365 
366  const set<Key> expected_keys{key};
367  EXPECT(expected_keys == sum_.keys())
368 
369  map<Key, int> actual_dims, expected_dims {{key, 3}};
370  sum_.dims(actual_dims);
371  EXPECT(actual_dims == expected_dims)
372 
373  // Check dims as map
374  std::map<Key, int> map;
375  sum_.dims(map);
376  LONGS_EQUAL(1, map.size())
377 
378  Values values;
379  values.insert<Point3>(key, Point3(2, 2, 2));
380 
381  // Check value
382  const Point3 expected(3, 3, 3);
384 
385  // Check value + Jacobians
386  std::vector<Matrix> H(1);
388  EXPECT(assert_equal(I_3x3, H[0]))
389 }
390 
391 /* ************************************************************************* */
392 // Test sum of 3 variables with + operator.
393 TEST(Expression, TripleSum) {
394  const Key key(67);
395  const Point3_ p1_(Point3(1, 1, 1)), p2_(key);
396  const Expression<Point3> sum_ = p1_ + p2_ + p1_;
397 
398  LONGS_EQUAL(1, sum_.keys().size())
399 
400  Values values;
401  values.insert<Point3>(key, Point3(2, 2, 2));
402 
403  // Check value
404  const Point3 expected(4, 4, 4);
406 
407  // Check value + Jacobians
408  std::vector<Matrix> H(1);
410  EXPECT(assert_equal(I_3x3, H[0]))
411 }
412 
413 /* ************************************************************************* */
414 // Test sum with += operator.
415 TEST(Expression, PlusEqual) {
416  const Key key(67);
417  const Point3_ p1_(Point3(1, 1, 1)), p2_(key);
418  Expression<Point3> sum_ = p1_;
419  sum_ += p2_;
420  sum_ += p1_;
421 
422  LONGS_EQUAL(1, sum_.keys().size())
423 
424  Values values;
425  values.insert<Point3>(key, Point3(2, 2, 2));
426 
427  // Check value
428  const Point3 expected(4, 4, 4);
430 
431  // Check value + Jacobians
432  std::vector<Matrix> H(1);
434  EXPECT(assert_equal(I_3x3, H[0]))
435 }
436 
437 /* ************************************************************************* */
438 TEST(Expression, SumOfUnaries) {
439  const Key key(67);
440  const Double_ norm_(&gtsam::norm3, Point3_(key));
441  const Double_ sum_ = norm_ + norm_;
442 
443  Values values;
444  values.insert<Point3>(key, Point3(6, 0, 0));
445 
446  // Check value
447  EXPECT_DOUBLES_EQUAL(12, sum_.value(values), 1e-9)
448 
449  // Check value + Jacobians
450  std::vector<Matrix> H(1);
451  EXPECT_DOUBLES_EQUAL(12, sum_.value(values, H), 1e-9)
452  EXPECT(assert_equal(Vector3(2, 0, 0).transpose(), H[0]))
453 }
454 
455 /* ************************************************************************* */
456 TEST(Expression, UnaryOfSum) {
457  const Key key1(42), key2(67);
458  const Point3_ sum_ = Point3_(key1) + Point3_(key2);
459  const Double_ norm_(&gtsam::norm3, sum_);
460 
461  map<Key, int> actual_dims, expected_dims = {{key1, 3}, {key2, 3}};
462  norm_.dims(actual_dims);
463  EXPECT(actual_dims == expected_dims)
464 
465  Values values;
466  values.insert<Point3>(key1, Point3(1, 0, 0));
467  values.insert<Point3>(key2, Point3(0, 1, 0));
468 
469  // Check value
470  EXPECT_DOUBLES_EQUAL(sqrt(2), norm_.value(values), 1e-9)
471 
472  // Check value + Jacobians
473  std::vector<Matrix> H(2);
474  EXPECT_DOUBLES_EQUAL(sqrt(2), norm_.value(values, H), 1e-9)
475  EXPECT(assert_equal(0.5 * sqrt(2) * Vector3(1, 1, 0).transpose(), H[0]))
476  EXPECT(assert_equal(0.5 * sqrt(2) * Vector3(1, 1, 0).transpose(), H[1]))
477 }
478 
479 /* ************************************************************************* */
480 TEST(Expression, WeightedSum) {
481  const Key key1(42), key2(67);
482  const Point3_ weighted_sum_ = 17 * Point3_(key1) + 23 * Point3_(key2);
483 
484  map<Key, int> actual_dims, expected_dims {{key1, 3}, {key2, 3}};
485  weighted_sum_.dims(actual_dims);
486  EXPECT(actual_dims == expected_dims)
487 
488  Values values;
489  const Point3 point1(1, 0, 0), point2(0, 1, 0);
492 
493  // Check value
494  const Point3 expected = 17 * point1 + 23 * point2;
495  EXPECT(assert_equal(expected, weighted_sum_.value(values)))
496 
497  // Check value + Jacobians
498  std::vector<Matrix> H(2);
499  EXPECT(assert_equal(expected, weighted_sum_.value(values, H)))
500  EXPECT(assert_equal(17 * I_3x3, H[0]))
501  EXPECT(assert_equal(23 * I_3x3, H[1]))
502 }
503 
504 /* ************************************************************************* */
505 TEST(Expression, Subtract) {
506  const Vector3 p = Vector3::Random(), q = Vector3::Random();
507  Values values;
508  values.insert(0, p);
509  values.insert(1, q);
510  const Vector3_ expression = Vector3_(0) - Vector3_(1);
511  set<Key> expected_keys = {0, 1};
512  EXPECT(expression.keys() == expected_keys)
513 
514  // Check value + Jacobians
515  std::vector<Matrix> H(2);
516  EXPECT(assert_equal<Vector3>(p - q, expression.value(values, H)))
517  EXPECT(assert_equal(I_3x3, H[0]))
518  EXPECT(assert_equal(-I_3x3, H[1]))
519 }
520 
521 /* ************************************************************************* */
522 TEST(Expression, LinearExpression) {
523  const Key key(67);
524  const std::function<Vector3(Point3)> f = [](const Point3& p) { return (Vector3)p; };
525  const Matrix3 kIdentity = I_3x3;
527 
528  Values values;
529  values.insert<Point3>(key, Point3(1, 0, 2));
530 
531  // Check value
532  const Vector3 expected(1, 0, 2);
534 
535  // Check value + Jacobians
536  std::vector<Matrix> H(1);
538  EXPECT(assert_equal(I_3x3, H[0]))
539 }
540 
541 /* ************************************************************************* */
542 int main() {
543  TestResult tr;
544  return TestRegistry::runAllTests(tr);
545 }
546 /* ************************************************************************* */
key1
const Symbol key1('v', 1)
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
H
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 set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
Point3_
Expression< Point3 > Point3_
Definition: testExpression.cpp:31
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
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
main
int main()
Definition: testExpression.cpp:542
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Leaf
static sharedNode Leaf(Key key, const SymbolicFactorGraph &factors)
Definition: testSymbolicEliminationTree.cpp:78
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
binary::x
Pose3_ x(1)
Definition: gnuplot_common_settings.hh:12
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
unary::pointExpression
Point3_ pointExpression(1)
TestHarness.h
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
unary::expected
const set< Key > expected
Definition: testExpression.cpp:89
binary::p_cam
Point3_ p_cam(x, &Pose3::transformTo, p)
tree
Definition: testExpression.cpp:212
gtsam::internal::VectorSpace
VectorSpace provides both Testable and VectorSpaceTraits.
Definition: VectorSpace.h:207
tree::projection
Expression< Point2 > projection(f, p_cam)
simple::R3
static Rot3 R3
Definition: testInitializePose3.cpp:54
gtsam::internal::upAligned
T upAligned(T value, unsigned requiredAlignment=TraceAlignment)
Definition: ExpressionNode.h:51
f2
double f2(const Vector2 &x)
Definition: testNumericalDerivative.cpp:58
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
Point3.h
3D Point
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
composeThree
Rot3 composeThree(const Rot3 &R1, const Rot3 &R2, const Rot3 &R3, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2, OptionalJacobian< 3, 3 > H3)
Definition: testExpression.cpp:307
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
point2
static const Point3 point2(-0.08, 0.08, 0.0)
uncalibrate
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)
Definition: testExpression.cpp:37
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
gtsam::Expression
Definition: Expression.h:47
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::Expression::keys
std::set< Key > keys() const
Return keys that play in this expression.
Definition: Expression-inl.h:128
TEST
TEST(Expression, Constant)
Definition: testExpression.cpp:46
expressions.h
Common expressions, both linear and non-linear.
key2
const Symbol key2('v', 2)
gtsam::transformTo
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
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
unary
Definition: testExpression.cpp:78
tree::K
Expression< Cal3_S2 > K(3)
binary::doubleF
double doubleF(const Pose3 &pose, const Point3 &point, OptionalJacobian< 1, 6 > H1, OptionalJacobian< 1, 3 > H2)
Definition: testExpression.cpp:170
PinholeCamera.h
Base class for all pinhole cameras.
Class::print
void print(const string &s) const
Definition: testExpression.cpp:128
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Class::norm
double norm(OptionalJacobian< 1, 3 > H={}) const
Definition: testExpression.cpp:122
kIdentity
static const NavState kIdentity
Definition: testNavState.cpp:39
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
gtsam::Expression::dims
void dims(std::map< Key, int > &map) const
Return dimensions for each argument, as a map.
Definition: Expression-inl.h:133
Rot3_
Expression< Rot3 > Rot3_
Definition: testExpression.cpp:33
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::norm3
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
Definition: Point3.cpp:41
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: SFMdata.h:40
Class::Identity
static Class Identity()
Definition: testExpression.cpp:121
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
someR
static const Rot3 someR
Definition: testExpression.cpp:42
f3
double f3(double x1, double x2)
Definition: testNumericalDerivative.cpp:78
gtsam::Values
Definition: Values.h:65
Pose3_
Expression< Pose3 > Pose3_
Definition: testExpression.cpp:32
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
Class::equals
bool equals(const Class &q, double tol) const
Definition: testExpression.cpp:125
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Vector3_
Expression< Vector3 > Vector3_
Definition: nonlinear/expressions.h:31
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::internal::upAlign
T & upAlign(T &value, unsigned requiredAlignment=TraceAlignment)
Definition: ExpressionNode.h:38
point1
const Point3 point1(3.0, 4.0, 2.0)
unary::f1
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
Definition: testExpression.cpp:79
tree::uv_hat
Expression< Point2 > uv_hat(uncalibrate< Cal3_S2 >, K, projection)
Project
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpressionFactor.cpp:40
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Class::vector
const Vector3 & vector() const
Definition: testExpression.cpp:120
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::linearExpression
Expression< T > linearExpression(const std::function< T(A)> &f, const Expression< A > &expression, const Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > &dTdA)
Definition: Expression.h:247
binary
Definition: testExpression.cpp:168
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:17