@@ -109,6 +109,59 @@ TEST(ManifoldPreintegration, computeError) {
109
109
EXPECT (assert_equal (numericalDerivative33 (f, x1, x2, bias), aH3, 1e-9 ));
110
110
}
111
111
112
+ /* ************************************************************************* */
113
+ TEST (ManifoldPreintegration, CompareWithPreintegratedRotation) {
114
+ // Create a PreintegratedRotation object
115
+ auto p = std::make_shared<PreintegratedRotationParams>();
116
+ PreintegratedRotation pim (p);
117
+
118
+ // Integrate a single measurement
119
+ const double omega = 0.1 ;
120
+ const Vector3 trueOmega (omega, 0 , 0 );
121
+ const Vector3 bias (1 , 2 , 3 );
122
+ const Vector3 measuredOmega = trueOmega + bias;
123
+ const double deltaT = 0.5 ;
124
+
125
+ // Check the accumulated rotation.
126
+ Rot3 expected = Rot3::Roll (omega * deltaT);
127
+ pim.integrateGyroMeasurement (measuredOmega, bias, deltaT);
128
+ EXPECT (assert_equal (expected, pim.deltaRij (), 1e-9 ));
129
+
130
+ // Now do the same for a ManifoldPreintegration object
131
+ imuBias::ConstantBias biasHat {Z_3x1, bias};
132
+ ManifoldPreintegration manifoldPim (testing::Params (), biasHat);
133
+ manifoldPim.integrateMeasurement (Z_3x1, measuredOmega, deltaT);
134
+ EXPECT (assert_equal (expected, manifoldPim.deltaRij (), 1e-9 ));
135
+
136
+ // Check their internal Jacobians are the same:
137
+ EXPECT (assert_equal (pim.delRdelBiasOmega (), manifoldPim.delRdelBiasOmega ()));
138
+
139
+ // Check PreintegratedRotation::biascorrectedDeltaRij.
140
+ Matrix3 H;
141
+ const double delta = 0.05 ;
142
+ const Vector3 biasOmegaIncr (delta, 0 , 0 );
143
+ Rot3 corrected = pim.biascorrectedDeltaRij (biasOmegaIncr, H);
144
+ EQUALITY (Vector3 (-deltaT * delta, 0 , 0 ), expected.logmap (corrected));
145
+ const Rot3 expected2 = Rot3::Roll ((omega - delta) * deltaT);
146
+ EXPECT (assert_equal (expected2, corrected, 1e-9 ));
147
+
148
+ // Check ManifoldPreintegration::biasCorrectedDelta.
149
+ imuBias::ConstantBias bias_i {Z_3x1, bias + biasOmegaIncr};
150
+ Matrix96 H2;
151
+ Vector9 biasCorrected = manifoldPim.biasCorrectedDelta (bias_i, H2);
152
+ Vector9 expected3;
153
+ expected3 << Rot3::Logmap (expected2), Z_3x1, Z_3x1;
154
+ EXPECT (assert_equal (expected3, biasCorrected, 1e-9 ));
155
+
156
+ // Check that this one is sane:
157
+ auto g = [&](const Vector3& increment) {
158
+ return manifoldPim.biasCorrectedDelta ({Z_3x1, bias + increment}, {});
159
+ };
160
+ EXPECT (assert_equal<Matrix>(numericalDerivative11<Vector9, Vector3>(g, Z_3x1),
161
+ H2.rightCols <3 >(),
162
+ 1e-4 )); // NOTE(frank): reduced tolerance
163
+ }
164
+
112
165
/* ************************************************************************* */
113
166
int main () {
114
167
TestResult tr;
0 commit comments