testRot3Q.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/geometry/Rot3.h>
20 
21 #include <gtsam/base/Testable.h>
23 
25 
26 using namespace std;
27 using namespace gtsam;
28 
29 #ifdef GTSAM_USE_QUATERNIONS
30 
31 //******************************************************************************
32 TEST(Rot3Q , Compare) {
33 
34  // We set up expected values with quaternions
35  typedef Quaternion Q;
36  typedef traits<Q> TQ;
37  typedef TQ::ChartJacobian OJ;
38 
39  // We check Rot3 expressions
40  typedef Rot3 R;
41  typedef traits<R> TR;
42 
43  // Define test values
44  Q q1(Eigen::AngleAxisd(1, Vector3(0, 0, 1)));
45  Q q2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)));
46  R R1(q1), R2(q2);
47 
48  // Check Compose
49  Q q3 = TQ::Compose(q1, q2, {}, {});
50  R R3 = TR::Compose(R1, R2, {}, {});
51  EXPECT(assert_equal(R(q3), R3));
52 
53  // Check Retract
54  Vector3 v(1e-5, 0, 0);
55  Q q4 = TQ::Retract(q3, v);
56  R R4 = TR::Retract(R3, v);
57  EXPECT(assert_equal(R(q4), R4));
58 
59  // Check Between
60  Q q5 = TQ::Between(q3, q4);
61  R R5 = R3.between(R4);
62  EXPECT(assert_equal(R(q5), R5));
63 
64  // Check toQuaternion
65  EXPECT(assert_equal(q5, R5.toQuaternion()));
66 
67  // Check Logmap
68  Vector3 vQ = TQ::Logmap(q5);
69  Vector3 vR = R::Logmap(R5);
70  EXPECT(assert_equal(vQ, vR));
71 
72  // Check Local
73  vQ = TQ::Local(q3, q4);
74  vR = TR::Local(R3, R4);
75  EXPECT(assert_equal(vQ, vR));
76 
77  // Check Retract/Local of Compose
78  Vector3 vQ1 = TQ::Local(q3, TQ::Compose(q1, TQ::Retract(q2, v)));
79  Vector3 vR1 = TR::Local(R3, TR::Compose(R1, TR::Retract(R2, v)));
80  EXPECT(assert_equal(vQ1, vR1));
81  Vector3 vQ2 = TQ::Local(q3, TQ::Compose(q1, TQ::Retract(q2, -v)));
82  Vector3 vR2 = TR::Local(R3, TR::Compose(R1, TR::Retract(R2, -v)));
83  EXPECT(assert_equal(vQ2, vR2));
84  EXPECT(assert_equal<Vector3>((vQ1 - vQ2) / 0.2, (vR1 - vR2) / 0.2));
85 
86  // Check Compose Derivatives
87  Matrix HQ, HR;
88  HQ = numericalDerivative42<Q, Q, Q, OJ, OJ>(TQ::Compose, q1, q2, {}, {});
89  HR = numericalDerivative42<R, R, R, OJ, OJ>(TR::Compose, R1, R2, {}, {});
90  EXPECT(assert_equal(HQ, HR));
91 
92 }
93 
94 #endif
95 
96 /* ************************************************************************* */
97 int main() {
98  TestResult tr;
99  return TestRegistry::runAllTests(tr);
100 }
101 /* ************************************************************************* */
102 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
Eigen::AngleAxis
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Definition: ForwardDeclarations.h:290
simple::R3
static Rot3 R3
Definition: testInitializePose3.cpp:54
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
Q
Quaternion Q
Definition: testQuaternion.cpp:27
TEST
#define TEST(testGroup, testName)
Definition: Test.h:63
Rot3.h
3D rotation represented as a rotation matrix or quaternion
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
TR
#define TR
Definition: gtsam/3rdparty/Eigen/blas/common.h:33
main
int main()
Definition: testRot3Q.cpp:97
TestResult
Definition: TestResult.h:26
Between
BetweenFactor< Rot3 > Between
Definition: testRot3Optimization.cpp:31
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: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
std
Definition: BFloat16.h:88
Quaternion.h
Lie Group wrapper for Eigen Quaternions.
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
R
Rot2 R(Rot2::fromAngle(0.1))
HR
#define HR
Definition: mincover.c:26


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:24