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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:25