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  GTSAM_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);
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);
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);
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);
129  EXPECT(assert_equal(numericH, actH, tol));
130 }
131 
132 /* ************************************************************************* */
133 Product interpolate_proxy(const Product& x, const Product& y, double t) {
134  return interpolate<Product>(x, y, t);
135 }
136 
137 TEST(Lie, Interpolate) {
138  Product x(Point2(1, 2), Pose2(3, 4, 5));
139  Product y(Point2(6, 7), Pose2(8, 9, 0));
140 
141  double t;
142  Matrix actH1, numericH1, actH2, numericH2;
143 
144  t = 0.0;
145  interpolate<Product>(x, y, t, actH1, actH2);
146  numericH1 = numericalDerivative31<Product, Product, Product, double>(
147  interpolate_proxy, x, y, t);
148  EXPECT(assert_equal(numericH1, actH1, tol));
149  numericH2 = numericalDerivative32<Product, Product, Product, double>(
150  interpolate_proxy, x, y, t);
151  EXPECT(assert_equal(numericH2, actH2, tol));
152 
153  t = 0.5;
154  interpolate<Product>(x, y, t, actH1, actH2);
155  numericH1 = numericalDerivative31<Product, Product, Product, double>(
156  interpolate_proxy, x, y, t);
157  EXPECT(assert_equal(numericH1, actH1, tol));
158  numericH2 = numericalDerivative32<Product, Product, Product, double>(
159  interpolate_proxy, x, y, t);
160  EXPECT(assert_equal(numericH2, actH2, tol));
161 
162  t = 1.0;
163  interpolate<Product>(x, y, t, actH1, actH2);
164  numericH1 = numericalDerivative31<Product, Product, Product, double>(
165  interpolate_proxy, x, y, t);
166  EXPECT(assert_equal(numericH1, actH1, tol));
167  numericH2 = numericalDerivative32<Product, Product, Product, double>(
168  interpolate_proxy, x, y, t);
169  EXPECT(assert_equal(numericH2, actH2, tol));
170 }
171 
172 //******************************************************************************
173 int main() {
174  TestResult tr;
175  return TestRegistry::runAllTests(tr);
176 }
177 //******************************************************************************
178 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Pose2.h
2D Pose
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
between_proxy
Product between_proxy(const Product &A, const Product &B)
Definition: testLie.cpp:78
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
logmap_proxy
Vector5 logmap_proxy(const Product &p)
Definition: testLie.cpp:120
m1
Matrix3d m1
Definition: IOFormat.cpp:2
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
testLie.h
gtsam::IsGroup
Definition: Group.h:42
ProductLieGroup.h
Group product of two Lie Groups.
Point2.h
2D Point
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
m2
MatrixType m2(n_dims)
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
TEST
TEST(Lie, ProductLieGroup)
Definition: testLie.cpp:49
expmap_proxy
Product expmap_proxy(const Vector5 &vec)
Definition: testLie.cpp:106
gtsam::IsLieGroup
Definition: Lie.h:260
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::traits< Product >::Equals
static bool Equals(const Product &m1, const Product &m2, double tol=1e-8)
Definition: testLie.cpp:42
inverse_proxy
Product inverse_proxy(const Product &A)
Definition: testLie.cpp:93
gtsam::internal::LieGroupTraits
Definition: Lie.h:174
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
common::state2
static const NavState state2(x2, v2)
gtsam::ProductLieGroup::expmap
ProductLieGroup expmap(const TangentVector &v) const
Definition: ProductLieGroup.h:167
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
compose_proxy
Product compose_proxy(const Product &A, const Product &B)
Definition: testLie.cpp:63
gtsam
traits
Definition: SFMdata.h:40
gtsam::ProductLieGroup::logmap
TangentVector logmap(const ProductLieGroup &g) const
Definition: ProductLieGroup.h:170
gtsam::ProductLieGroup
Definition: ProductLieGroup.h:29
interpolate_proxy
Product interpolate_proxy(const Product &x, const Product &y, double t)
Definition: testLie.cpp:133
gtsam::traits
Definition: Group.h:36
gtsam::traits< Product >::Print
static void Print(const Product &m, const string &s="")
Definition: testLie.cpp:38
gtsam::testing::compose
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
std
Definition: BFloat16.h:88
Product
ProductLieGroup< Point2, Pose2 > Product
Definition: testLie.cpp:33
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
main
int main()
Definition: testLie.cpp:173
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
common::state1
static const NavState state1(x1, v1)
align_3::t
Point2 t(10, 10)
tol
static const double tol
Definition: testLie.cpp:30
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
gtsam::Pose2
Definition: Pose2.h:39
make_changelog.state
state
Definition: make_changelog.py:29


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:48