chartTesting.h
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 
12 /*
13  * @file chartTesting.h
14  * @brief
15  * @date November, 2014
16  * @author Paul Furgale
17  */
18 
19 #pragma once
20 
21 #include <gtsam/base/Matrix.h>
22 #include <gtsam/base/Manifold.h>
23 #include <gtsam/base/Testable.h>
24 #include <CppUnitLite/TestResult.h>
25 #include <CppUnitLite/Test.h>
26 #include <CppUnitLite/Failure.h>
27 
28 namespace gtsam {
29 // Do a full concept check and test the invertibility of local() vs. retract().
30 template<typename T>
32  const std::string& name_,
33  const T& value) {
34 
36 
37  typedef typename gtsam::DefaultChart<T> Chart;
38  typedef typename Chart::vector Vector;
39 
40  // First, check the basic chart concept. This checks that the interface is satisfied.
41  // The rest of the function is even more detailed, checking the correctness of the chart.
42  GTSAM_CONCEPT_ASSERT(ChartConcept<Chart>);
43 
44  T other = value;
45 
46  // Check that the dimension of the local value matches the chart dimension.
47  Vector dx = Chart::local(value, other);
48  EXPECT_LONGS_EQUAL(Chart::getDimension(value), dx.size());
49  // And that the "local" of a value vs. itself is zero.
50  EXPECT(assert_equal(Matrix(dx), Matrix(Eigen::VectorXd::Zero(dx.size()))));
51 
52  // Test the invertibility of retract/local
53  dx.setRandom();
54  T updated = Chart::retract(value, dx);
55  Vector invdx = Chart::local(value, updated);
56  EXPECT(assert_equal(Matrix(dx), Matrix(invdx), 1e-9));
57 
58  // And test that negative steps work as well.
59  dx = -dx;
60  updated = Chart::retract(value, dx);
61  invdx = Chart::local(value, updated);
62  EXPECT(assert_equal(Matrix(dx), Matrix(invdx), 1e-9));
63 }
64 } // namespace gtsam
65 
68 #define CHECK_CHART_CONCEPT(value) \
69  { gtsam::testDefaultChart(result_, name_, value); }
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
Concept check for values that can be used in unit tests.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:177
Eigen::VectorXd Vector
Definition: Vector.h:38
Base class and basic functions for Manifold types.
#define EXPECT(condition)
Definition: Test.h:150
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
A small structure to hold a non zero as a triplet (i,j,value).
Definition: SparseUtil.h:162
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
void testDefaultChart(TestResult &result_, const std::string &name_, const T &value)
Definition: chartTesting.h:31


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:01