testSO4.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 
18 #include <gtsam/base/Manifold.h>
19 #include <gtsam/base/Testable.h>
20 #include <gtsam/base/lieProxies.h>
22 #include <gtsam/geometry/SO4.h>
23 #include <gtsam/geometry/SO3.h>
24 
26 
27 #include <iostream>
28 #include <random>
29 
30 using namespace std;
31 using namespace gtsam;
32 
33 //******************************************************************************
34 TEST(SO4, Identity) {
35  const SO4 R;
36  EXPECT_LONGS_EQUAL(4, R.rows());
37  EXPECT_LONGS_EQUAL(6, SO4::dimension);
38  EXPECT_LONGS_EQUAL(6, SO4::Dim());
39  EXPECT_LONGS_EQUAL(6, R.dim());
41 }
42 
43 //******************************************************************************
44 TEST(SO4, Concept) {
46  GTSAM_CONCEPT_ASSERT(IsManifold<SO4>);
48 }
49 
50 //******************************************************************************
51 TEST(SO4, Random) {
52  std::mt19937 rng(42);
53  auto Q = SO4::Random(rng);
54  EXPECT_LONGS_EQUAL(4, Q.matrix().rows());
55 }
56 
57 //******************************************************************************
58 namespace {
59 SO4 id;
60 Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished();
61 SO4 Q1 = SO4::Expmap(v1);
62 Vector6 v2 = (Vector(6) << 0.00, 0.00, 0.00, 0.01, 0.02, 0.03).finished();
63 SO4 Q2 = SO4::Expmap(v2);
64 Vector6 v3 = (Vector(6) << 1, 2, 3, 4, 5, 6).finished();
65 SO4 Q3 = SO4::Expmap(v3);
66 } // namespace
67 
68 //******************************************************************************
70  // If we do exponential map in SO(3) subgroup, topleft should be equal to R1.
71  auto R1 = SO3::Expmap(v1.tail<3>()).matrix();
72  EXPECT((Q1.matrix().topLeftCorner<3, 3>().isApprox(R1)));
73 
74  // Same here
75  auto R2 = SO3::Expmap(v2.tail<3>()).matrix();
76  EXPECT((Q2.matrix().topLeftCorner<3, 3>().isApprox(R2)));
77 
78  // Check commutative subgroups
79  for (size_t i = 0; i < 6; i++) {
80  Vector6 xi = Vector6::Zero();
81  xi[i] = 2;
82  SO4 Q1 = SO4::Expmap(xi);
83  xi[i] = 3;
84  SO4 Q2 = SO4::Expmap(xi);
85  EXPECT(assert_equal(Q1 * Q2, Q2 * Q1));
86  }
87 }
88 
89 //******************************************************************************
90 // Check that Hat specialization is equal to dynamic version
91 TEST(SO4, Hat) {
92  EXPECT(assert_equal(SO4::Hat(v1), SOn::Hat(v1)));
93  EXPECT(assert_equal(SO4::Hat(v2), SOn::Hat(v2)));
94  EXPECT(assert_equal(SO4::Hat(v3), SOn::Hat(v3)));
95 }
96 
97 //******************************************************************************
98 // Check that Hat specialization is equal to dynamic version
99 TEST(SO4, Vee) {
100  auto X1 = SOn::Hat(v1), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3);
101  EXPECT(assert_equal(SO4::Vee(X1), SOn::Vee(X1)));
102  EXPECT(assert_equal(SO4::Vee(X2), SOn::Vee(X2)));
103  EXPECT(assert_equal(SO4::Vee(X3), SOn::Vee(X3)));
104 }
105 
106 //******************************************************************************
107 TEST(SO4, Retract) {
108  // Check that Cayley yields the same as Expmap for small values
109  EXPECT(assert_equal(id.retract(v1 / 100), SO4::Expmap(v1 / 100)));
110  EXPECT(assert_equal(id.retract(v2 / 100), SO4::Expmap(v2 / 100)));
111 
112  // Check that Cayley is identical to dynamic version
113  EXPECT(assert_equal(SOn(id.retract(v1 / 100)), SOn(4).retract(v1 / 100)));
114  EXPECT(assert_equal(SOn(id.retract(v2 / 100)), SOn(4).retract(v2 / 100)));
115 
116  auto v = Vector6::Zero();
117  SO4 actual = traits<SO4>::Retract(id, v);
118  EXPECT(assert_equal(id, actual));
119 }
120 
121 //******************************************************************************
122 // Check that Cayley is identical to dynamic version
123 TEST(SO4, Local) {
124  EXPECT(
125  assert_equal(id.localCoordinates(Q1), SOn(4).localCoordinates(SOn(Q1))));
126  EXPECT(
127  assert_equal(id.localCoordinates(Q2), SOn(4).localCoordinates(SOn(Q2))));
128 
129  auto v0 = Vector6::Zero();
130  Vector6 actual = traits<SO4>::Local(id, id);
131  EXPECT(assert_equal((Vector)v0, actual));
132 }
133 
134 //******************************************************************************
135 TEST(SO4, Invariants) {
136  EXPECT(check_group_invariants(id, id));
137  EXPECT(check_group_invariants(id, Q1));
138  EXPECT(check_group_invariants(Q2, id));
139  EXPECT(check_group_invariants(Q2, Q1));
140  EXPECT(check_group_invariants(Q1, Q2));
141 
142  EXPECT(check_manifold_invariants(id, id));
143  EXPECT(check_manifold_invariants(id, Q1));
144  EXPECT(check_manifold_invariants(Q2, id));
145  EXPECT(check_manifold_invariants(Q2, Q1));
146  EXPECT(check_manifold_invariants(Q1, Q2));
147 }
148 
149 //******************************************************************************
151  SO4 expected = Q1 * Q2;
152  Matrix actualH1, actualH2;
153  SO4 actual = Q1.compose(Q2, actualH1, actualH2);
154  EXPECT(assert_equal(expected, actual));
155 
156  Matrix numericalH1 =
157  numericalDerivative21(testing::compose<SO4>, Q1, Q2, 1e-2);
158  EXPECT(assert_equal(numericalH1, actualH1));
159 
160  Matrix numericalH2 =
161  numericalDerivative22(testing::compose<SO4>, Q1, Q2, 1e-2);
162  EXPECT(assert_equal(numericalH2, actualH2));
163 }
164 
165 //******************************************************************************
166 TEST(SO4, vec) {
167  using Vector16 = SO4::VectorN2;
168  const Vector16 expected = Eigen::Map<const Vector16>(Q2.matrix().data());
169  Matrix actualH;
170  const Vector16 actual = Q2.vec(actualH);
171  EXPECT(assert_equal(expected, actual));
172  std::function<Vector16(const SO4&)> f = [](const SO4& Q) { return Q.vec(); };
173  const Matrix numericalH = numericalDerivative11(f, Q2, 1e-5);
174  EXPECT(assert_equal(numericalH, actualH));
175 }
176 
177 //******************************************************************************
179  const Matrix3 expected = Q3.matrix().topLeftCorner<3, 3>();
180  Matrix actualH;
181  const Matrix3 actual = topLeft(Q3, actualH);
182  EXPECT(assert_equal(expected, actual));
183  std::function<Matrix3(const SO4&)> f = [](const SO4& Q3) {
184  return topLeft(Q3);
185  };
186  const Matrix numericalH = numericalDerivative11(f, Q3, 1e-5);
187  EXPECT(assert_equal(numericalH, actualH));
188 }
189 
190 //******************************************************************************
192  const Matrix43 expected = Q3.matrix().leftCols<3>();
193  Matrix actualH;
194  const Matrix43 actual = stiefel(Q3, actualH);
195  EXPECT(assert_equal(expected, actual));
196  std::function<Matrix43(const SO4&)> f = [](const SO4& Q3) {
197  return stiefel(Q3);
198  };
199  const Matrix numericalH = numericalDerivative11(f, Q3, 1e-5);
200  EXPECT(assert_equal(numericalH, actualH));
201 }
202 
203 //******************************************************************************
204 int main() {
205  TestResult tr;
206  return TestRegistry::runAllTests(tr);
207 }
208 //******************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::topLeft
GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian< 9, 6 > H)
Definition: SO4.cpp:206
TEST
TEST(SO4, Identity)
Definition: testSO4.cpp:34
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::stiefel
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian< 12, 6 > H)
Definition: SO4.cpp:220
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
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
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
SO4.h
4*4 matrix representation of SO(4)
gtsam::IsGroup
Definition: Group.h:42
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
Q
Quaternion Q
Definition: testQuaternion.cpp:27
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
SO3.h
3*3 matrix representation of SO(3)
main
int main()
Definition: testSO4.cpp:204
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::SOn
SO< Eigen::Dynamic > SOn
Definition: SOn.h:342
gtsam::IsLieGroup
Definition: Lie.h:260
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
Manifold.h
Base class and basic functions for Manifold types.
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
Q2
static double Q2[8]
Definition: ndtri.c:122
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: chartTesting.h:28
gtsam::traits
Definition: Group.h:36
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
v2
Vector v2
Definition: testSerializationBase.cpp:39
Q1
static double Q1[8]
Definition: ndtri.c:94
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::SO
Definition: SOn.h:54
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
v3
Vector v3
Definition: testSerializationBase.cpp:40
lieProxies.h
Provides convenient mappings of common member functions for testing.
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
R
Rot2 R(Rot2::fromAngle(0.1))
v1
Vector v1
Definition: testSerializationBase.cpp:38


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:07:00