testQuaternion.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 
20 #include <gtsam/base/testLie.h>
21 
23 
24 using namespace std;
25 using namespace gtsam;
26 
27 typedef Quaternion Q; // Typedef
29 
30 //******************************************************************************
31 TEST(Quaternion , Concept) {
33  GTSAM_CONCEPT_ASSERT(IsManifold<Quaternion >);
35 }
36 
37 //******************************************************************************
38 TEST(Quaternion , Constructor) {
39  Q q(Eigen::AngleAxisd(1, Vector3(0, 0, 1)));
40 }
41 
42 //******************************************************************************
43 TEST(Quaternion , Logmap) {
44  Q q1(5e-06, 0, 0, 1), q2(-5e-06, 0, 0, -1);
47  EXPECT(assert_equal(v1, v2));
48 }
49 
50 //******************************************************************************
51 TEST(Quaternion , Local) {
52  Vector3 z_axis(0, 0, 1);
53  Q q1(Eigen::AngleAxisd(0, z_axis));
54  Q q2(Eigen::AngleAxisd(0.1, z_axis));
55  QuaternionJacobian H1, H2;
56  Vector3 expected(0, 0, 0.1);
57  Vector3 actual = traits<Q>::Local(q1, q2, H1, H2);
58  EXPECT(assert_equal((Vector )expected, actual));
59 }
60 
61 //******************************************************************************
62 TEST(Quaternion , Retract) {
63  Vector3 z_axis(0, 0, 1);
64  Q q(Eigen::AngleAxisd(0, z_axis));
65  Q expected(Eigen::AngleAxisd(0.1, z_axis));
66  Vector3 v(0, 0, 0.1);
67  QuaternionJacobian Hq, Hv;
68  Q actual = traits<Q>::Retract(q, v, Hq, Hv);
69  EXPECT(actual.isApprox(expected));
70 }
71 
72 //******************************************************************************
73 TEST(Quaternion , Compose) {
74  Vector3 z_axis(0, 0, 1);
75  Q q1(Eigen::AngleAxisd(0.2, z_axis));
76  Q q2(Eigen::AngleAxisd(0.1, z_axis));
77 
78  Q expected = q1 * q2;
79  Q actual = traits<Q>::Compose(q1, q2);
80  EXPECT(traits<Q>::Equals(expected, actual));
81 }
82 
83 //******************************************************************************
85  Vector3 z_axis(0, 0, 1);
86  Q q1(Eigen::AngleAxisd(0.2, z_axis));
87  Q q2(Eigen::AngleAxisd(0.1, z_axis));
88 
89  Q expected = q1.inverse() * q2;
90  Q actual = traits<Q>::Between(q1, q2);
91  EXPECT(traits<Q>::Equals(expected, actual));
92 }
93 
94 //******************************************************************************
96  Vector3 z_axis(0, 0, 1);
97  Q q1(Eigen::AngleAxisd(0.1, z_axis));
98  Q expected(Eigen::AngleAxisd(-0.1, z_axis));
99 
100  Q actual = traits<Q>::Inverse(q1);
101  EXPECT(traits<Q>::Equals(expected, actual));
102 }
103 
104 //******************************************************************************
105 namespace {
106 Vector3 Q_z_axis(0, 0, 1);
107 Q id(Eigen::AngleAxisd(0, Q_z_axis));
108 Q R1(Eigen::AngleAxisd(1, Q_z_axis));
109 Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)));
110 } // namespace
111 
112 //******************************************************************************
113 TEST(Quaternion, Invariants) {
114  EXPECT(check_group_invariants(id, id));
115  EXPECT(check_group_invariants(id, R1));
116  EXPECT(check_group_invariants(R2, id));
117  EXPECT(check_group_invariants(R2, R1));
118 
119  EXPECT(check_manifold_invariants(id, id));
120  EXPECT(check_manifold_invariants(id, R1));
121  EXPECT(check_manifold_invariants(R2, id));
122  EXPECT(check_manifold_invariants(R2, R1));
123 }
124 
125 //******************************************************************************
126 TEST(Quaternion, LieGroupDerivatives) {
131 }
132 
133 //******************************************************************************
134 TEST(Quaternion, ChartDerivatives) {
135  CHECK_CHART_DERIVATIVES(id, id);
139 }
140 
141 //******************************************************************************
142 int main() {
143  TestResult tr;
144  return TestRegistry::runAllTests(tr);
145 }
146 //******************************************************************************
147 
Quaternion Q
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
Vector v2
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
Matrix expected
Definition: testMatrix.cpp:971
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Definition: BFloat16.h:88
Some functions to compute numerical derivatives.
static const Similarity3 id
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
Eigen::VectorXd Vector
Definition: Vector.h:38
EIGEN_DEVICE_FUNC bool isApprox(const QuaternionBase< OtherDerived > &other, const RealScalar &prec=NumTraits< Scalar >::dummy_precision()) const
#define EXPECT(condition)
Definition: Test.h:150
Array< int, Dynamic, 1 > v
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits< Q >::ChartJacobian QuaternionJacobian
EIGEN_DEVICE_FUNC const Scalar & q
traits
Definition: chartTesting.h:28
TEST(Quaternion, Concept)
The quaternion class used to represent 3D orientations and rotations.
int main()
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:13