testLie.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 
20 
21 #include <gtsam/geometry/Pose2.h>
22 #include <gtsam/geometry/Point2.h>
23 #include <gtsam/base/testLie.h>
24 
26 
27 using namespace std;
28 using namespace gtsam;
29 
30 static const double tol = 1e-9;
31 
32 //******************************************************************************
34 
35 // Define any direct product group to be a model of the multiplicative Group concept
36 namespace gtsam {
37 template<> struct traits<Product> : internal::LieGroupTraits<Product> {
38  static void Print(const Product& m, const string& s = "") {
39  cout << s << "(" << m.first << "," << m.second.translation() << "/"
40  << m.second.theta() << ")" << endl;
41  }
42  static bool Equals(const Product& m1, const Product& m2, double tol = 1e-8) {
43  return traits<Point2>::Equals(m1.first, m2.first, tol) && m1.second.equals(m2.second, tol);
44  }
45 };
46 }
47 
48 //******************************************************************************
51  BOOST_CONCEPT_ASSERT((IsManifold<Product>));
53  Product pair1;
54  Vector5 d;
55  d << 1, 2, 0.1, 0.2, 0.3;
56  Product expected(Point2(1, 2), Pose2::Expmap(Vector3(0.1, 0.2, 0.3)));
57  Product pair2 = pair1.expmap(d);
58  EXPECT(assert_equal(expected, pair2, 1e-9));
59  EXPECT(assert_equal(d, pair1.logmap(pair2), 1e-9));
60 }
61 
62 /* ************************************************************************* */
63 Product compose_proxy(const Product& A, const Product& B) {
64  return A.compose(B);
65 }
66 TEST( testProduct, compose ) {
67  Product state1(Point2(1, 2), Pose2(3, 4, 5)), state2 = state1;
68 
69  Matrix actH1, actH2;
70  state1.compose(state2, actH1, actH2);
71  Matrix numericH1 = numericalDerivative21(compose_proxy, state1, state2);
72  Matrix numericH2 = numericalDerivative22(compose_proxy, state1, state2);
73  EXPECT(assert_equal(numericH1, actH1, tol));
74  EXPECT(assert_equal(numericH2, actH2, tol));
75 }
76 
77 /* ************************************************************************* */
78 Product between_proxy(const Product& A, const Product& B) {
79  return A.between(B);
80 }
81 TEST( testProduct, between ) {
82  Product state1(Point2(1, 2), Pose2(3, 4, 5)), state2 = state1;
83 
84  Matrix actH1, actH2;
85  state1.between(state2, actH1, actH2);
86  Matrix numericH1 = numericalDerivative21(between_proxy, state1, state2);
87  Matrix numericH2 = numericalDerivative22(between_proxy, state1, state2);
88  EXPECT(assert_equal(numericH1, actH1, tol));
89  EXPECT(assert_equal(numericH2, actH2, tol));
90 }
91 
92 /* ************************************************************************* */
94  return A.inverse();
95 }
96 TEST( testProduct, inverse ) {
97  Product state1(Point2(1, 2), Pose2(3, 4, 5));
98 
99  Matrix actH1;
100  state1.inverse(actH1);
101  Matrix numericH1 = numericalDerivative11(inverse_proxy, state1);
102  EXPECT(assert_equal(numericH1, actH1, tol));
103 }
104 
105 /* ************************************************************************* */
106 Product expmap_proxy(const Vector5& vec) {
107  return Product::Expmap(vec);
108 }
109 TEST( testProduct, Expmap ) {
110  Vector5 vec;
111  vec << 1, 2, 0.1, 0.2, 0.3;
112 
113  Matrix actH;
114  Product::Expmap(vec, actH);
115  Matrix numericH = numericalDerivative11(expmap_proxy, vec);
116  EXPECT(assert_equal(numericH, actH, tol));
117 }
118 
119 /* ************************************************************************* */
120 Vector5 logmap_proxy(const Product& p) {
121  return Product::Logmap(p);
122 }
123 TEST( testProduct, Logmap ) {
124  Product state(Point2(1, 2), Pose2(3, 4, 5));
125 
126  Matrix actH;
127  Product::Logmap(state, actH);
128  Matrix numericH = numericalDerivative11(logmap_proxy, state);
129  EXPECT(assert_equal(numericH, actH, tol));
130 }
131 
132 //******************************************************************************
133 int main() {
134  TestResult tr;
135  return TestRegistry::runAllTests(tr);
136 }
137 //******************************************************************************
138 
Matrix3f m
ProductLieGroup inverse() const
TEST(Lie, ProductLieGroup)
Definition: testLie.cpp:49
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
Matrix expected
Definition: testMatrix.cpp:974
MatrixType m2(n_dims)
Vector2 Point2
Definition: Point2.h:27
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
TangentVector logmap(const ProductLieGroup &g) const
static void Print(const Product &m, const string &s="")
Definition: testLie.cpp:38
static const NavState state1(x1, v1)
Group product of two Lie Groups.
static const double tol
Definition: testLie.cpp:30
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
ProductLieGroup expmap(const TangentVector &v) const
Matrix3d m1
Definition: IOFormat.cpp:2
static const NavState state2(x2, v2)
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Product inverse_proxy(const Product &A)
Definition: testLie.cpp:93
Product expmap_proxy(const Vector5 &vec)
Definition: testLie.cpp:106
traits
Definition: chartTesting.h:28
Product compose_proxy(const Product &A, const Product &B)
Definition: testLie.cpp:63
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
ProductLieGroup compose(const ProductLieGroup &g) const
ProductLieGroup< Point2, Pose2 > Product
Definition: testLie.cpp:33
static bool Equals(const Product &m1, const Product &m2, double tol=1e-8)
Definition: testLie.cpp:42
Product between_proxy(const Product &A, const Product &B)
Definition: testLie.cpp:78
float * p
ProductLieGroup between(const ProductLieGroup &g) const
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
2D Pose
2D Point
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
int main()
Definition: testLie.cpp:133
Vector5 logmap_proxy(const Product &p)
Definition: testLie.cpp:120


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