27 using namespace gtsam;
29 #ifdef GTSAM_USE_QUATERNIONS 32 TEST(Rot3Q , Compare) {
38 typedef TQ::ChartJacobian OJ;
50 Q
q3 = TQ::Compose(
q1,
q2, none, none);
51 R
R3 = TR::Compose(
R1,
R2, none, none);
56 Q q4 = TQ::Retract(q3,
v);
57 R R4 = TR::Retract(R3,
v);
62 R R5 = R3.between(R4);
74 vQ = TQ::Local(q3, q4);
75 vR = TR::Local(R3, R4);
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)));
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)));
85 EXPECT(assert_equal<Vector3>((vQ1 - vQ2) / 0.2, (vR1 - vR2) / 0.2));
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);
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Rot2 R(Rot2::fromAngle(0.1))
Some functions to compute numerical derivatives.
#define EXPECT(condition)
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
The quaternion class used to represent 3D orientations and rotations.
#define TEST(testGroup, testName)
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