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  using boost::none;
34 
35  // We set up expected values with quaternions
36  typedef Quaternion Q;
37  typedef traits<Q> TQ;
38  typedef TQ::ChartJacobian OJ;
39 
40  // We check Rot3 expressions
41  typedef Rot3 R;
42  typedef traits<R> TR;
43 
44  // Define test values
45  Q q1(Eigen::AngleAxisd(1, Vector3(0, 0, 1)));
46  Q q2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)));
47  R R1(q1), R2(q2);
48 
49  // Check Compose
50  Q q3 = TQ::Compose(q1, q2, none, none);
51  R R3 = TR::Compose(R1, R2, none, none);
52  EXPECT(assert_equal(R(q3), R3));
53 
54  // Check Retract
55  Vector3 v(1e-5, 0, 0);
56  Q q4 = TQ::Retract(q3, v);
57  R R4 = TR::Retract(R3, v);
58  EXPECT(assert_equal(R(q4), R4));
59 
60  // Check Between
61  Q q5 = TQ::Between(q3, q4);
62  R R5 = R3.between(R4);
63  EXPECT(assert_equal(R(q5), R5));
64 
65  // Check toQuaternion
66  EXPECT(assert_equal(q5, R5.toQuaternion()));
67 
68  // Check Logmap
69  Vector3 vQ = TQ::Logmap(q5);
70  Vector3 vR = R::Logmap(R5);
71  EXPECT(assert_equal(vQ, vR));
72 
73  // Check Local
74  vQ = TQ::Local(q3, q4);
75  vR = TR::Local(R3, R4);
76  EXPECT(assert_equal(vQ, vR));
77 
78  // Check Retract/Local of Compose
79  Vector3 vQ1 = TQ::Local(q3, TQ::Compose(q1, TQ::Retract(q2, v)));
80  Vector3 vR1 = TR::Local(R3, TR::Compose(R1, TR::Retract(R2, v)));
81  EXPECT(assert_equal(vQ1, vR1));
82  Vector3 vQ2 = TQ::Local(q3, TQ::Compose(q1, TQ::Retract(q2, -v)));
83  Vector3 vR2 = TR::Local(R3, TR::Compose(R1, TR::Retract(R2, -v)));
84  EXPECT(assert_equal(vQ2, vR2));
85  EXPECT(assert_equal<Vector3>((vQ1 - vQ2) / 0.2, (vR1 - vR2) / 0.2));
86 
87  // Check Compose Derivatives
88  Matrix HQ, HR;
89  HQ = numericalDerivative42<Q, Q, Q, OJ, OJ>(TQ::Compose, q1, q2, none, none);
90  HR = numericalDerivative42<R, R, R, OJ, OJ>(TR::Compose, R1, R2, none, none);
91  EXPECT(assert_equal(HQ, HR));
92 
93 }
94 
95 #endif
96 
97 /* ************************************************************************* */
98 int main() {
99  TestResult tr;
100  return TestRegistry::runAllTests(tr);
101 }
102 /* ************************************************************************* */
103 
Point2 q2
Definition: testPose2.cpp:753
Quaternion Q
Point2 q1
Definition: testPose2.cpp:753
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
Definition: Half.h:150
Some functions to compute numerical derivatives.
int main()
Definition: testRot3Q.cpp:98
#define EXPECT(condition)
Definition: Test.h:151
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Point2 q3
Definition: testPose2.cpp:753
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
traits
Definition: chartTesting.h:28
static Rot3 R3
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
The quaternion class used to represent 3D orientations and rotations.
#define HR
Definition: mincover.c:26
#define TEST(testGroup, testName)
Definition: Test.h:63
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
3D rotation represented as a rotation matrix or quaternion


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