testValues.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 
19 #include <gtsam/nonlinear/Values.h>
20 #include <gtsam/inference/Symbol.h>
22 #include <gtsam/geometry/Pose2.h>
23 #include <gtsam/geometry/Pose3.h>
24 #include <gtsam/base/Testable.h>
26 
28 #include <stdexcept>
29 #include <limits>
30 #include <type_traits>
31 
32 using namespace std::placeholders;
33 using namespace gtsam;
34 using namespace std;
35 static double inf = std::numeric_limits<double>::infinity();
36 
37 // Convenience for named keys
40 
41 const Symbol key1('v', 1), key2('v', 2), key3('v', 3), key4('v', 4);
42 
43 
45 public:
46  static int ConstructorCount;
47  static int DestructorCount;
48  TestValueData(const TestValueData& other) { ++ ConstructorCount; }
49  TestValueData() { ++ ConstructorCount; }
50  ~TestValueData() { ++ DestructorCount; }
51 };
54 class TestValue {
56 public:
57  enum {dimension = 0};
58  void print(const std::string& str = "") const {}
59  bool equals(const TestValue& other, double tol = 1e-9) const { return true; }
60  size_t dim() const { return 0; }
64  return TestValue();
65  }
69  return Vector();
70  }
71 };
72 
73 namespace gtsam {
74 template <> struct traits<TestValue> : public internal::Manifold<TestValue> {};
75 }
76 
77 /* ************************************************************************* */
78 TEST( Values, equals1 )
79 {
81  Vector3 v(5.0, 6.0, 7.0);
82 
83  expected.insert(key1, v);
84  Values actual;
85  actual.insert(key1, v);
86  CHECK(assert_equal(expected, actual));
87 }
88 
89 /* ************************************************************************* */
90 TEST( Values, equals2 )
91 {
92  Values cfg1, cfg2;
93  Vector3 v1(5.0, 6.0, 7.0);
94  Vector3 v2(5.0, 6.0, 8.0);
95 
96  cfg1.insert(key1, v1);
97  cfg2.insert(key1, v2);
98  CHECK(!cfg1.equals(cfg2));
99  CHECK(!cfg2.equals(cfg1));
100 }
101 
102 /* ************************************************************************* */
103 TEST( Values, equals_nan )
104 {
105  Values cfg1, cfg2;
106  Vector3 v1(5.0, 6.0, 7.0);
107  Vector3 v2(inf, inf, inf);
108 
109  cfg1.insert(key1, v1);
110  cfg2.insert(key1, v2);
111  CHECK(!cfg1.equals(cfg2));
112  CHECK(!cfg2.equals(cfg1));
113 }
114 
115 /* ************************************************************************* */
116 TEST( Values, insert_good )
117 {
118  Values cfg1, cfg2, expected;
119  Vector3 v1(5.0, 6.0, 7.0);
120  Vector3 v2(8.0, 9.0, 1.0);
121  Vector3 v3(2.0, 4.0, 3.0);
122  Vector3 v4(8.0, 3.0, 7.0);
123 
124  cfg1.insert(key1, v1);
125  cfg1.insert(key2, v2);
126  cfg2.insert(key3, v4);
127 
128  cfg1.insert(cfg2);
129 
130  expected.insert(key1, v1);
131  expected.insert(key2, v2);
132  expected.insert(key3, v4);
133 
134  CHECK(assert_equal(expected, cfg1));
135 }
136 
137 /* ************************************************************************* */
138 TEST( Values, insert_bad )
139 {
140  Values cfg1, cfg2;
141  Vector3 v1(5.0, 6.0, 7.0);
142  Vector3 v2(8.0, 9.0, 1.0);
143  Vector3 v3(2.0, 4.0, 3.0);
144  Vector3 v4(8.0, 3.0, 7.0);
145 
146  cfg1.insert(key1, v1);
147  cfg1.insert(key2, v2);
148  cfg2.insert(key2, v3);
149  cfg2.insert(key3, v4);
150 
152 }
153 
154 /* ************************************************************************* */
155 TEST( Values, update_element )
156 {
157  Values cfg;
158  Vector3 v1(5.0, 6.0, 7.0);
159  Vector3 v2(8.0, 9.0, 1.0);
160 
161  cfg.insert(key1, v1);
162  CHECK(cfg.size() == 1);
163  CHECK(assert_equal((Vector)v1, cfg.at<Vector3>(key1)));
164 
165  cfg.update(key1, v2);
166  CHECK(cfg.size() == 1);
167  CHECK(assert_equal((Vector)v2, cfg.at<Vector3>(key1)));
168 }
169 
170 TEST(Values, InsertOrAssign) {
171  Values values;
172  Key X(0);
173  double x = 1;
174 
175  CHECK(values.size() == 0);
176  // This should perform an insert.
177  values.insert_or_assign(X, x);
178  EXPECT(assert_equal(values.at<double>(X), x));
179 
180  // This should perform an update.
181  double y = 2;
182  values.insert_or_assign(X, y);
183  EXPECT(assert_equal(values.at<double>(X), y));
184 }
185 
186 /* ************************************************************************* */
187 TEST(Values, basic_functions)
188 {
189  Values values;
190  Matrix23 M1 = Matrix23::Zero(), M2 = Matrix23::Zero();
191  values.insert(2, Vector3(0, 0, 0));
192  values.insert(4, Vector3(0, 0, 0));
193  values.insert(6, M1);
194  values.insert(8, M2);
195 
196 
197  EXPECT(!values.exists(1));
198  EXPECT(values.exists(2));
199  EXPECT(values.exists(4));
200  EXPECT(values.exists(6));
201  EXPECT(values.exists(8));
202 
203  size_t count = 0;
204  for (const auto& [key, value] : values) {
205  count += 1;
206  if (key == 2 || key == 4) EXPECT_LONGS_EQUAL(3, value.dim());
207  if (key == 6 || key == 8) EXPECT_LONGS_EQUAL(6, value.dim());
208  }
209  EXPECT_LONGS_EQUAL(4, count);
210 
211  // find
212  EXPECT_LONGS_EQUAL(4, values.find(4)->key);
213 
214  // lower_bound
215  EXPECT_LONGS_EQUAL(4, values.lower_bound(4)->key);
216  EXPECT_LONGS_EQUAL(4, values.lower_bound(3)->key);
217 
218  // upper_bound
219  EXPECT_LONGS_EQUAL(6, values.upper_bound(4)->key);
220  EXPECT_LONGS_EQUAL(4, values.upper_bound(3)->key);
221 }
222 
223 /* ************************************************************************* */
224 TEST(Values, retract_full)
225 {
226  Values config0;
227  config0.insert(key1, Vector3(1.0, 2.0, 3.0));
228  config0.insert(key2, Vector3(5.0, 6.0, 7.0));
229 
230  const VectorValues delta{{key1, Vector3(1.0, 1.1, 1.2)},
231  {key2, Vector3(1.3, 1.4, 1.5)}};
232 
234  expected.insert(key1, Vector3(2.0, 3.1, 4.2));
235  expected.insert(key2, Vector3(6.3, 7.4, 8.5));
236 
237  CHECK(assert_equal(expected, config0.retract(delta)));
238  CHECK(assert_equal(expected, Values(config0, delta)));
239 }
240 
241 /* ************************************************************************* */
242 TEST(Values, retract_partial)
243 {
244  Values config0;
245  config0.insert(key1, Vector3(1.0, 2.0, 3.0));
246  config0.insert(key2, Vector3(5.0, 6.0, 7.0));
247 
248  const VectorValues delta{{key2, Vector3(1.3, 1.4, 1.5)}};
249 
251  expected.insert(key1, Vector3(1.0, 2.0, 3.0));
252  expected.insert(key2, Vector3(6.3, 7.4, 8.5));
253 
254  CHECK(assert_equal(expected, config0.retract(delta)));
255  CHECK(assert_equal(expected, Values(config0, delta)));
256 }
257 
258 /* ************************************************************************* */
259 TEST(Values, retract_masked)
260 {
261  Values config0;
262  config0.insert(key1, Vector3(1.0, 2.0, 3.0));
263  config0.insert(key2, Vector3(5.0, 6.0, 7.0));
264 
265  const VectorValues delta{{key1, Vector3(1.0, 1.1, 1.2)},
266  {key2, Vector3(1.3, 1.4, 1.5)}};
267 
269  expected.insert(key1, Vector3(1.0, 2.0, 3.0));
270  expected.insert(key2, Vector3(6.3, 7.4, 8.5));
271 
272  config0.retractMasked(delta, {key2});
273  CHECK(assert_equal(expected, config0));
274 }
275 
276 /* ************************************************************************* */
278 {
279  Values config0;
280  config0.insert(key1, Vector3(1.0, 2.0, 3.0));
281  config0.insert(key2, Vector3(5.0, 6.0, 7.0));
282 
283  CHECK(equal(config0, config0));
284  CHECK(config0.equals(config0));
285 
286  Values poseconfig;
287  poseconfig.insert(key1, Pose2(1, 2, 3));
288  poseconfig.insert(key2, Pose2(0.3, 0.4, 0.5));
289 
290  CHECK(equal(poseconfig, poseconfig));
291  CHECK(poseconfig.equals(poseconfig));
292 }
293 
294 /* ************************************************************************* */
295 TEST(Values, localCoordinates)
296 {
297  Values valuesA;
298  valuesA.insert(key1, Vector3(1.0, 2.0, 3.0));
299  valuesA.insert(key2, Vector3(5.0, 6.0, 7.0));
300 
301  VectorValues expDelta{{key1, Vector3(0.1, 0.2, 0.3)},
302  {key2, Vector3(0.4, 0.5, 0.6)}};
303 
304  Values valuesB = valuesA.retract(expDelta);
305 
306  EXPECT(assert_equal(expDelta, valuesA.localCoordinates(valuesB)));
307 }
308 
309 /* ************************************************************************* */
310 TEST(Values, extract_keys)
311 {
312  Values config;
313 
314  config.insert(key1, Pose2());
315  config.insert(key2, Pose2());
316  config.insert(key3, Pose2());
317  config.insert(key4, Pose2());
318 
320  KeyVector actual = config.keys();
321 
322  CHECK(actual.size() == expected.size());
323  KeyVector::const_iterator itAct = actual.begin(), itExp = expected.begin();
324  for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) {
325  EXPECT(*itExp == *itAct);
326  }
327 }
328 
329 /* ************************************************************************* */
330 TEST(Values, exists_)
331 {
332  Values config0;
333  config0.insert(key1, 1.0);
334  config0.insert(key2, 2.0);
335 
336  const double* v = config0.exists<double>(key1);
337  DOUBLES_EQUAL(1.0,*v,1e-9);
338 }
339 
340 /* ************************************************************************* */
342 {
343  Values config0;
344  config0.insert(key1, 1.0);
345  config0.insert(key2, 2.0);
346 
347  Values superset;
348  superset.insert(key1, -1.0);
349  superset.insert(key2, -2.0);
350  config0.update(superset);
351 
353  expected.insert(key1, -1.0);
354  expected.insert(key2, -2.0);
355  CHECK(assert_equal(expected, config0));
356 }
357 
358 /* ************************************************************************* */
359 TEST(Values, filter) {
360  Pose2 pose0(1.0, 2.0, 0.3);
361  Pose3 pose1(Pose2(0.1, 0.2, 0.3));
362  Pose2 pose2(4.0, 5.0, 0.6);
363  Pose3 pose3(Pose2(0.3, 0.7, 0.9));
364 
365  Values values;
366  values.insert(0, pose0);
367  values.insert(1, pose1);
368  values.insert(2, pose2);
369  values.insert(3, pose3);
370 
371  // Test counting by type.
372  EXPECT_LONGS_EQUAL(2, (long)values.count<Pose3>());
373  EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>());
374 
375  // Filter by type using extract.
376  auto extracted_pose3s = values.extract<Pose3>();
377  EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());
378 }
379 
380 /* ************************************************************************* */
381 TEST(Values, Symbol_filter) {
382  Pose2 pose0(1.0, 2.0, 0.3);
383  Pose3 pose1(Pose2(0.1, 0.2, 0.3));
384  Pose2 pose2(4.0, 5.0, 0.6);
385  Pose3 pose3(Pose2(0.3, 0.7, 0.9));
386 
387  Values values;
388  values.insert(X(0), pose0);
389  values.insert(Symbol('y', 1), pose1);
390  values.insert(X(2), pose2);
391  values.insert(Symbol('y', 3), pose3);
392 
393  // Test extract with filter on symbol:
394  auto extracted_pose3s = values.extract<Pose3>(Symbol::ChrTest('y'));
395  EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());
396 }
397 
398 /* ************************************************************************* */
399 // Check that Value destructors are called when Values container is deleted
400 TEST(Values, Destructors) {
401  {
402  Values values;
403  {
404  TestValue value1;
405  TestValue value2;
408  values.insert(0, value1);
409  values.insert(1, value2);
410  }
411  // additional 2 con/destructor counts for the temporary
412  // GenericValue<TestValue> in insert()
413  // but I'm sure some advanced programmer can figure out
414  // a way to avoid the temporary, or optimize it out
417  }
420 }
421 
422 /* ************************************************************************* */
423 TEST(Values, copy_constructor) {
424  {
425  Values values;
428  {
429  TestValue value1;
430  TestValue value2;
433  values.insert(0, value1);
434  values.insert(1, value2);
435  }
438 
439  // Copy constructor
440  {
441  Values copied(values); // makes 2 extra copies
442  EXPECT_LONGS_EQUAL(8, (long)TestValueData::ConstructorCount);
443  EXPECT_LONGS_EQUAL(4, (long)TestValueData::DestructorCount);
444  }
445  EXPECT_LONGS_EQUAL(8, (long)TestValueData::ConstructorCount);
446  EXPECT_LONGS_EQUAL(6, (long)TestValueData::DestructorCount); // copied destructed !
447  }
449  EXPECT_LONGS_EQUAL(8, (long)TestValueData::DestructorCount); // values destructed !
450 }
451 
452 /* ************************************************************************* */
453 // small class with a constructor to create an rvalue
454 struct TestValues : Values {
455  using Values::Values; // inherits move constructor
456 
457  TestValues(const TestValue& value1, const TestValue& value2) {
458  insert(0, value1);
459  insert(1, value2);
460  }
461 };
464 
465 // test move semantics
466 TEST(Values, move_constructor) {
467  {
470  TestValue value1;
471  TestValue value2;
474  TestValues values(TestValues(value1, value2)); // Move happens here ! (could be optimization?)
475  EXPECT_LONGS_EQUAL(2, values.size());
476  EXPECT_LONGS_EQUAL(6, (long)TestValueData::ConstructorCount); // yay ! We don't copy
477  EXPECT_LONGS_EQUAL(2, (long)TestValueData::DestructorCount); // extra insert copies
478  }
481 }
482 
483 // test use of std::move
484 TEST(Values, std_move) {
485  {
488  {
489  TestValue value1;
490  TestValue value2;
491  TestValues values(value1, value2);
494  EXPECT_LONGS_EQUAL(2, values.size());
495  TestValues moved(std::move(values)); // Move happens here !
496  EXPECT_LONGS_EQUAL(0, values.size()); // Should be 0 !
497  EXPECT_LONGS_EQUAL(2, moved.size());
498  EXPECT_LONGS_EQUAL(6, (long)TestValueData::ConstructorCount); // Should be 6 :-)
499  EXPECT_LONGS_EQUAL(2, (long)TestValueData::DestructorCount); // extra insert copies
500  }
503  }
504 }
505 
506 /* ************************************************************************* */
507 TEST(Values, VectorDynamicInsertFixedRead) {
508  Values values;
509  Vector v(3); v << 5.0, 6.0, 7.0;
510  values.insert(key1, v);
511  Vector3 expected(5.0, 6.0, 7.0);
512  Vector3 actual = values.at<Vector3>(key1);
513  CHECK(assert_equal(expected, actual));
514  CHECK_EXCEPTION(values.at<Vector7>(key1), exception);
515 }
516 
517 /* ************************************************************************* */
518 TEST(Values, VectorDynamicInsertDynamicRead) {
519  Values values;
520  Vector v(3); v << 5.0, 6.0, 7.0;
521  values.insert(key1, v);
522  Vector expected(3); expected << 5.0, 6.0, 7.0;
523  Vector actual = values.at<Vector>(key1);
524  LONGS_EQUAL(3, actual.rows());
525  LONGS_EQUAL(1, actual.cols());
526  CHECK(assert_equal(expected, actual));
527 }
528 
529 /* ************************************************************************* */
530 TEST(Values, VectorFixedInsertFixedRead) {
531  Values values;
532  Vector3 v; v << 5.0, 6.0, 7.0;
533  values.insert(key1, v);
534  Vector3 expected; expected << 5.0, 6.0, 7.0;
535  Vector3 actual = values.at<Vector3>(key1);
536  CHECK(assert_equal(expected, actual));
537  CHECK_EXCEPTION(values.at<Vector7>(key1), exception);
538 }
539 
540 /* ************************************************************************* */
541 // NOTE(frank): test is broken, because the scheme it tested was *very* slow.
542 // TODO(frank): find long-term solution. that works w matlab/python.
543 //TEST(Values, VectorFixedInsertDynamicRead) {
544 // Values values;
545 // Vector3 v; v << 5.0, 6.0, 7.0;
546 // values.insert(key1, v);
547 // Vector expected(3); expected << 5.0, 6.0, 7.0;
548 // Vector actual = values.at<Vector>(key1);
549 // LONGS_EQUAL(3, actual.rows());
550 // LONGS_EQUAL(1, actual.cols());
551 // CHECK(assert_equal(expected, actual));
552 //}
553 
554 /* ************************************************************************* */
555 TEST(Values, MatrixDynamicInsertFixedRead) {
556  Values values;
557  Matrix v(1,3); v << 5.0, 6.0, 7.0;
558  values.insert(key1, v);
559  Vector3 expected(5.0, 6.0, 7.0);
560  CHECK(assert_equal((Vector)expected, values.at<Matrix13>(key1)));
561  CHECK_EXCEPTION(values.at<Matrix23>(key1), exception);
562 }
563 
564 TEST(Values, Demangle) {
565  Values values;
566  Matrix13 v; v << 5.0, 6.0, 7.0;
567  values.insert(key1, v);
568  string expected = "Values with 1 values:\nValue v1: (Eigen::Matrix<double, 1, 3, 1, 1, 3>)\n[\n 5, 6, 7\n]\n\n";
569 
570  EXPECT(assert_print_equal(expected, values));
571 }
572 
573 /* ************************************************************************* */
574 TEST(Values, brace_initializer) {
575  const Pose2 poseA(1.0, 2.0, 0.3), poseC(.0, .0, .0);
576  const Pose3 poseB(Pose2(0.1, 0.2, 0.3));
577 
578  {
579  Values values;
580  EXPECT_LONGS_EQUAL(0, values.size());
581  values = { {key1, genericValue(1.0)} };
582  EXPECT_LONGS_EQUAL(1, values.size());
583  CHECK(values.at<double>(key1) == 1.0);
584  }
585  {
586  Values values = { {key1, genericValue(poseA)}, {key2, genericValue(poseB)} };
587  EXPECT_LONGS_EQUAL(2, values.size());
588  EXPECT(assert_equal(values.at<Pose2>(key1), poseA));
589  EXPECT(assert_equal(values.at<Pose3>(key2), poseB));
590  }
591  // Test exception: duplicated key:
592  {
593  Values values;
594  CHECK_EXCEPTION((values = {
595  {key1, genericValue(poseA)},
596  {key2, genericValue(poseB)},
597  {key1, genericValue(poseC)}
598  }), std::exception);
599  }
600 }
601 
602 
603 /* ************************************************************************* */
604 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
605 /* ************************************************************************* */
const gtsam::Symbol key('X', 0)
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:108
void print(const std::string &str="") const
Definition: testValues.cpp:58
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
A insert(1, 2)=0
const Symbol key3('v', 3)
Scalar * y
Vector v2
Concept check for values that can be used in unit tests.
def update(text)
Definition: relicense.py:46
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
A non-templated config holding any types of Manifold-group elements.
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
const ValueType at(Key j) const
Definition: Values-inl.h:204
Matrix expected
Definition: testMatrix.cpp:971
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
std::map< Key, ValueType > extract(const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const
Definition: Values-inl.h:105
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
size_t dim() const
Definition: testValues.cpp:60
int main()
Definition: testValues.cpp:604
leaf::MyValues values
KeyVector keys() const
Definition: Values.cpp:218
void update(Key j, const Value &val)
Definition: Values.cpp:169
TestValues(const TestValue &value1, const TestValue &value2)
Definition: testValues.cpp:457
MatrixXf M1
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
TestValueData data_
Definition: testValues.cpp:55
VectorValues localCoordinates(const Values &cp) const
Definition: Values.cpp:129
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
bool equals(const TestValue &other, double tol=1e-9) const
Definition: testValues.cpp:59
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
Factor Graph Values.
Vector v3
Eigen::VectorXd Vector
Definition: Vector.h:38
const Symbol key1('v', 1)
M1<< 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12;Map< MatrixXf > M2(M1.data(), 6, 2)
Definition: pytypes.h:1403
#define EXPECT(condition)
Definition: Test.h:150
static Pose3 pose3(rt3, pt3)
const Symbol key4('v', 4)
Array< int, Dynamic, 1 > v
static int DestructorCount
Definition: testValues.cpp:47
void retractMasked(const VectorValues &delta, const KeySet &mask)
Definition: Values.cpp:103
Array< double, 1, 3 > e(1./3., 0.5, 2.)
size_t size() const
Definition: Values.h:178
bool equals(const Values &other, double tol=1e-9) const
Definition: Values.cpp:77
TEST(Values, equals1)
Definition: testValues.cpp:78
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
static Pose3 pose0
traits
Definition: chartTesting.h:28
GenericValue< T > genericValue(const T &v)
Definition: GenericValue.h:211
size_t count() const
Definition: Values-inl.h:94
TestValueData(const TestValueData &other)
Definition: testValues.cpp:48
std::vector< float > Values
void insert_or_assign(Key j, const Value &val)
If key j exists, update value, else perform an insert.
Definition: Values.cpp:192
Vector localCoordinates(const TestValue &, OptionalJacobian< dimension, dimension > H1={}, OptionalJacobian< dimension, dimension > H2={}) const
Definition: testValues.cpp:66
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
TestValue retract(const Vector &, OptionalJacobian< dimension, dimension > H1={}, OptionalJacobian< dimension, dimension > H2={}) const
Definition: testValues.cpp:61
static Pose3 pose2
void insert(Key j, const Value &val)
Definition: Values.cpp:155
static double inf
Definition: testValues.cpp:35
const G double tol
Definition: Group.h:86
static int ConstructorCount
Definition: testValues.cpp:46
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
2D Pose
#define X
Definition: icosphere.cpp:20
bool exists(Key j) const
Definition: Values.cpp:93
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
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 x
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
const Symbol key2('v', 2)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:56