testInertialNavFactor_GlobalVelocity.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 <iostream>
22 #include <gtsam/geometry/Pose3.h>
23 #include <gtsam/nonlinear/Values.h>
24 #include <gtsam/inference/Key.h>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 Rot3 world_R_ECEF(0.31686, 0.51505, 0.79645, 0.85173, -0.52399, 0, 0.41733,
32  0.67835, -0.60471);
33 
34 static const Vector3 world_g(0.0, 0.0, 9.81);
35 static const Vector3 world_rho(0.0, -1.5724e-05, 0.0); // NED system
36 static const Vector3 ECEF_omega_earth(0.0, 0.0, 7.292115e-5);
39 
40 /* ************************************************************************* */
42  const imuBias::ConstantBias& b1, const Pose3& p2, const Vector3& v2,
44  return Pose3::Expmap(factor.evaluateError(p1, v1, b1, p2, v2).head(6));
45 }
46 
48  const imuBias::ConstantBias& b1, const Pose3& p2, const Vector3& v2,
50  return factor.evaluateError(p1, v1, b1, p2, v2).tail(3);
51 }
52 
53 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, Constructor) {
54  Key Pose1(11);
55  Key Pose2(12);
56  Key Vel1(21);
57  Key Vel2(22);
58  Key Bias1(31);
59 
60  Vector3 measurement_acc(0.1, 0.2, 0.4);
61  Vector3 measurement_gyro(-0.2, 0.5, 0.03);
62 
63  double measurement_dt(0.1);
64 
65  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
66 
68  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
69  measurement_dt, world_g, world_rho, world_omega_earth, model);
70 }
71 
72 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, Equals) {
73  Key Pose1(11);
74  Key Pose2(12);
75  Key Vel1(21);
76  Key Vel2(22);
77  Key Bias1(31);
78 
79  Vector3 measurement_acc(0.1, 0.2, 0.4);
80  Vector3 measurement_gyro(-0.2, 0.5, 0.03);
81 
82  double measurement_dt(0.1);
83 
84  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
85 
87  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
88  measurement_dt, world_g, world_rho, world_omega_earth, model);
90  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
91  measurement_dt, world_g, world_rho, world_omega_earth, model);
92  CHECK(assert_equal(f, g, 1e-5));
93 }
94 
95 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, Predict) {
96  Key PoseKey1(11);
97  Key PoseKey2(12);
98  Key VelKey1(21);
99  Key VelKey2(22);
100  Key BiasKey1(31);
101 
102  double measurement_dt(0.1);
103 
104  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
105 
106  // First test: zero angular motion, some acceleration
107  Vector measurement_acc(Vector3(0.1, 0.2, 0.3 - 9.81));
108  Vector measurement_gyro(Vector3(0.0, 0.0, 0.0));
109 
111  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
112  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
113  model);
114 
115  Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
116  Vector3 Vel1(Vector3(0.50, -0.50, 0.40));
117  imuBias::ConstantBias Bias1;
118  Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04));
119  Vector3 expectedVel2(Vector3(0.51, -0.48, 0.43));
120  Pose3 actualPose2;
121  Vector3 actualVel2;
122  f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
123 
124  CHECK(assert_equal(expectedPose2, actualPose2, 1e-5));
125  CHECK(assert_equal((Vector)expectedVel2, actualVel2, 1e-5));
126 }
127 
128 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorPosVel) {
129  Key PoseKey1(11);
130  Key PoseKey2(12);
131  Key VelKey1(21);
132  Key VelKey2(22);
133  Key BiasKey1(31);
134 
135  double measurement_dt(0.1);
136 
137  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
138 
139  // First test: zero angular motion, some acceleration
140  Vector measurement_acc(Vector3(0.1, 0.2, 0.3 - 9.81));
141  Vector measurement_gyro(Vector3(0.0, 0.0, 0.0));
142 
144  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
145  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
146  model);
147 
148  Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
149  Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04));
150  Vector3 Vel1(Vector3(0.50, -0.50, 0.40));
151  Vector3 Vel2(Vector3(0.51, -0.48, 0.43));
152  imuBias::ConstantBias Bias1;
153 
154  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
155  Vector ExpectedErr(Z_9x1);
156 
157  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
158 }
159 
160 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorRot) {
161  Key PoseKey1(11);
162  Key PoseKey2(12);
163  Key VelKey1(21);
164  Key VelKey2(22);
165  Key BiasKey1(31);
166 
167  double measurement_dt(0.1);
168 
169  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
170 
171  // Second test: zero angular motion, some acceleration
172  Vector measurement_acc(Vector3(0.0, 0.0, 0.0 - 9.81));
173  Vector measurement_gyro(Vector3(0.1, 0.2, 0.3));
174 
176  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
177  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
178  model);
179 
180  Pose3 Pose1(Rot3(), Point3(2.0, 1.0, 3.0));
181  Pose3 Pose2(Rot3::Expmap(measurement_gyro * measurement_dt),
182  Point3(2.0, 1.0, 3.0));
183  Vector3 Vel1(Vector3(0.0, 0.0, 0.0));
184  Vector3 Vel2(Vector3(0.0, 0.0, 0.0));
185  imuBias::ConstantBias Bias1;
186 
187  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
188  Vector ExpectedErr(Z_9x1);
189 
190  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
191 }
192 
193 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorRotPosVel) {
194  Key PoseKey1(11);
195  Key PoseKey2(12);
196  Key VelKey1(21);
197  Key VelKey2(22);
198  Key BiasKey1(31);
199 
200  double measurement_dt(0.1);
201 
202  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
203 
204  // Second test: zero angular motion, some acceleration - generated in matlab
205  Vector measurement_acc(
206  Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
207  Vector measurement_gyro(Vector3(0.1, 0.2, 0.3));
208 
210  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
211  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
212  model);
213 
214  Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
215  -0.427669306, -0.652537293, 0.709880342, 0.265075427);
216  Point3 t1(2.0, 1.0, 3.0);
217  Pose3 Pose1(R1, t1);
218  Vector3 Vel1(Vector3(0.5, -0.5, 0.4));
219  Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
220  -0.422594037, -0.636011287, 0.731761397, 0.244979388);
221  Point3 t2 = t1 + Point3(Vel1 * measurement_dt);
222  Pose3 Pose2(R2, t2);
223  Vector dv = measurement_dt * (R1.matrix() * measurement_acc + world_g);
224  Vector3 Vel2 = Vel1 + dv;
225  imuBias::ConstantBias Bias1;
226 
227  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
228  Vector ExpectedErr(Z_9x1);
229 
230  // TODO: Expected values need to be updated for global velocity version
231  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
232 }
233 
235 //Vector3 predictionRq(const Vector3 angles, const Vector3 q) {
236 // return (Rot3().RzRyRx(angles) * q);
237 //}
238 //
239 //TEST (InertialNavFactor_GlobalVelocity, Rotation_Deriv ) {
240 // Vector3 angles(Vector3(3.001, -1.0004, 2.0005));
241 // Rot3 R1(Rot3().RzRyRx(angles));
242 // Vector3 q(Vector3(5.8, -2.2, 4.105));
243 // Rot3 qx(0.0, -q[2], q[1],
244 // q[2], 0.0, -q[0],
245 // -q[1], q[0],0.0);
246 // Matrix J_hyp( -(R1*qx).matrix() );
247 //
248 // Matrix J_expected;
249 //
250 // Vector3 v(predictionRq(angles, q));
251 //
252 // J_expected = numericalDerivative11<Vector3, Vector3>(boost::bind(&predictionRq, _1, q), angles);
253 //
254 // cout<<"J_hyp"<<J_hyp<<endl;
255 // cout<<"J_expected"<<J_expected<<endl;
256 //
257 // CHECK( assert_equal(J_expected, J_hyp, 1e-6));
258 //}
260 
261 /* ************************************************************************* */TEST (InertialNavFactor_GlobalVelocity, Jacobian ) {
262 
263  Key PoseKey1(11);
264  Key PoseKey2(12);
265  Key VelKey1(21);
266  Key VelKey2(22);
267  Key BiasKey1(31);
268 
269  double measurement_dt(0.01);
270 
271  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
272 
273  Vector measurement_acc(
274  Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
275  Vector measurement_gyro((Vector(3) << 3.14, 3.14 / 2, -3.14).finished());
276 
278  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
279  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
280  model);
281 
282  Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
283  -0.427669306, -0.652537293, 0.709880342, 0.265075427);
284  Point3 t1(2.0, 1.0, 3.0);
285  Pose3 Pose1(R1, t1);
286  Vector3 Vel1(Vector3(0.5, -0.5, 0.4));
287  Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
288  -0.422594037, -0.636011287, 0.731761397, 0.244979388);
289  Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
290  Pose3 Pose2(R2, t2);
291  Vector3 Vel2(
292  Vector3(0.510000000000000, -0.480000000000000, 0.430000000000000));
293  imuBias::ConstantBias Bias1;
294 
295  Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
296 
297  Vector ActualErr(
298  factor.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
299  H2_actual, H3_actual, H4_actual, H5_actual));
300 
301  // Checking for Pose part in the jacobians
302  // ******
303  Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
304  Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
305  Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
306  Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
307  Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
308 
309  // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
310  Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
311  H5_expectedPose;
312  H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
313  boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor),
314  Pose1);
315  H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
316  boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor),
317  Vel1);
318  H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
319  boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor),
320  Bias1);
321  H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
322  boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor),
323  Pose2);
324  H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
325  boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor),
326  Vel2);
327 
328  // Verify they are equal for this choice of state
329  CHECK( assert_equal(H1_expectedPose, H1_actualPose, 1e-5));
330  CHECK( assert_equal(H2_expectedPose, H2_actualPose, 1e-5));
331  CHECK( assert_equal(H3_expectedPose, H3_actualPose, 2e-3));
332  CHECK( assert_equal(H4_expectedPose, H4_actualPose, 1e-5));
333  CHECK( assert_equal(H5_expectedPose, H5_actualPose, 1e-5));
334 
335  // Checking for Vel part in the jacobians
336  // ******
337  Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
338  Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
339  Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
340  Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
341  Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
342 
343  // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
344  Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
345  H5_expectedVel;
346  H1_expectedVel = numericalDerivative11<Vector, Pose3>(
347  boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor),
348  Pose1);
349  H2_expectedVel = numericalDerivative11<Vector, Vector3>(
350  boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor),
351  Vel1);
352  H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
353  boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor),
354  Bias1);
355  H4_expectedVel = numericalDerivative11<Vector, Pose3>(
356  boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor),
357  Pose2);
358  H5_expectedVel = numericalDerivative11<Vector, Vector3>(
359  boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor),
360  Vel2);
361 
362  // Verify they are equal for this choice of state
363  CHECK( assert_equal(H1_expectedVel, H1_actualVel, 1e-5));
364  CHECK( assert_equal(H2_expectedVel, H2_actualVel, 1e-5));
365  CHECK( assert_equal(H3_expectedVel, H3_actualVel, 1e-5));
366  CHECK( assert_equal(H4_expectedVel, H4_actualVel, 1e-5));
367  CHECK( assert_equal(H5_expectedVel, H5_actualVel, 1e-5));
368 }
369 
370 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ConstructorWithTransform) {
371  Key Pose1(11);
372  Key Pose2(12);
373  Key Vel1(21);
374  Key Vel2(22);
375  Key Bias1(31);
376 
377  Vector measurement_acc(Vector3(0.1, 0.2, 0.4));
378  Vector measurement_gyro(Vector3(-0.2, 0.5, 0.03));
379 
380  double measurement_dt(0.1);
381 
382  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
383 
384  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(0.0, 0.0, 0.0)); // IMU is in ENU orientation
385 
387  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
388  measurement_dt, world_g, world_rho, world_omega_earth, model,
389  body_P_sensor);
390 }
391 
392 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, EqualsWithTransform) {
393  Key Pose1(11);
394  Key Pose2(12);
395  Key Vel1(21);
396  Key Vel2(22);
397  Key Bias1(31);
398 
399  Vector measurement_acc(Vector3(0.1, 0.2, 0.4));
400  Vector measurement_gyro(Vector3(-0.2, 0.5, 0.03));
401 
402  double measurement_dt(0.1);
403 
404  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
405 
406  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(0.0, 0.0, 0.0)); // IMU is in ENU orientation
407 
409  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
410  measurement_dt, world_g, world_rho, world_omega_earth, model,
411  body_P_sensor);
413  Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
414  measurement_dt, world_g, world_rho, world_omega_earth, model,
415  body_P_sensor);
416  CHECK(assert_equal(f, g, 1e-5));
417 }
418 
419 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, PredictWithTransform) {
420  Key PoseKey1(11);
421  Key PoseKey2(12);
422  Key VelKey1(21);
423  Key VelKey2(22);
424  Key BiasKey1(31);
425 
426  double measurement_dt(0.1);
427 
428  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
429 
430  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(1.0, -2.0, 3.0)); // IMU is in ENU orientation
431 
432  // First test: zero angular motion, some acceleration
433  Vector measurement_gyro(Vector3(0.0, 0.0, 0.0)); // Measured in ENU orientation
434  Matrix omega__cross = skewSymmetric(measurement_gyro);
435  Vector measurement_acc = Vector3(0.2, 0.1, -0.3 + 9.81)
436  + omega__cross * omega__cross
437  * body_P_sensor.rotation().inverse().matrix()
438  * body_P_sensor.translation(); // Measured in ENU orientation
439 
441  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
442  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
443  model, body_P_sensor);
444 
445  Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
446  Vector3 Vel1(Vector3(0.50, -0.50, 0.40));
447  imuBias::ConstantBias Bias1;
448  Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04));
449  Vector3 expectedVel2(Vector3(0.51, -0.48, 0.43));
450  Pose3 actualPose2;
451  Vector3 actualVel2;
452  f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
453 
454  CHECK(assert_equal(expectedPose2, actualPose2, 1e-5));
455  CHECK(assert_equal((Vector)expectedVel2, actualVel2, 1e-5));
456 }
457 
458 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorPosVelWithTransform) {
459  Key PoseKey1(11);
460  Key PoseKey2(12);
461  Key VelKey1(21);
462  Key VelKey2(22);
463  Key BiasKey1(31);
464 
465  double measurement_dt(0.1);
466 
467  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
468 
469  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(1.0, -2.0, 3.0)); // IMU is in ENU orientation
470 
471  // First test: zero angular motion, some acceleration
472  Vector measurement_gyro(Vector3(0.0, 0.0, 0.0)); // Measured in ENU orientation
473  Matrix omega__cross = skewSymmetric(measurement_gyro);
474  Vector measurement_acc = Vector3(0.2, 0.1, -0.3 + 9.81)
475  + omega__cross * omega__cross
476  * body_P_sensor.rotation().inverse().matrix()
477  * body_P_sensor.translation(); // Measured in ENU orientation
478 
480  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
481  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
482  model, body_P_sensor);
483 
484  Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
485  Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04));
486  Vector3 Vel1(Vector3(0.50, -0.50, 0.40));
487  Vector3 Vel2(Vector3(0.51, -0.48, 0.43));
488  imuBias::ConstantBias Bias1;
489 
490  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
491  Vector ExpectedErr(Z_9x1);
492 
493  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
494 }
495 
496 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorRotWithTransform) {
497  Key PoseKey1(11);
498  Key PoseKey2(12);
499  Key VelKey1(21);
500  Key VelKey2(22);
501  Key BiasKey1(31);
502 
503  double measurement_dt(0.1);
504 
505  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
506 
507  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(1.0, -2.0, 3.0)); // IMU is in ENU orientation
508 
509  // Second test: zero angular motion, some acceleration
510  Vector measurement_gyro(Vector3(0.2, 0.1, -0.3)); // Measured in ENU orientation
511  Matrix omega__cross = skewSymmetric(measurement_gyro);
512  Vector measurement_acc = Vector3(0.0, 0.0, 0.0 + 9.81)
513  + omega__cross * omega__cross
514  * body_P_sensor.rotation().inverse().matrix()
515  * body_P_sensor.translation(); // Measured in ENU orientation
516 
518  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
519  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
520  model, body_P_sensor);
521 
522  Pose3 Pose1(Rot3(), Point3(2.0, 1.0, 3.0));
523  Pose3 Pose2(
524  Rot3::Expmap(
525  body_P_sensor.rotation().matrix() * measurement_gyro
526  * measurement_dt), Point3(2.0, 1.0, 3.0));
527  Vector3 Vel1(Vector3(0.0, 0.0, 0.0));
528  Vector3 Vel2(Vector3(0.0, 0.0, 0.0));
529  imuBias::ConstantBias Bias1;
530 
531  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
532  Vector ExpectedErr(Z_9x1);
533 
534  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
535 }
536 
537 /* ************************************************************************* */TEST( InertialNavFactor_GlobalVelocity, ErrorRotPosVelWithTransform) {
538  Key PoseKey1(11);
539  Key PoseKey2(12);
540  Key VelKey1(21);
541  Key VelKey2(22);
542  Key BiasKey1(31);
543 
544  double measurement_dt(0.1);
545 
546  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
547 
548  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(1.0, -2.0, 3.0)); // IMU is in ENU orientation
549 
550  // Second test: zero angular motion, some acceleration - generated in matlab
551  Vector measurement_gyro(Vector3(0.2, 0.1, -0.3)); // Measured in ENU orientation
552  Matrix omega__cross = skewSymmetric(measurement_gyro);
553  Vector measurement_acc =
554  Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
555  + omega__cross * omega__cross
556  * body_P_sensor.rotation().inverse().matrix()
557  * body_P_sensor.translation(); // Measured in ENU orientation
558 
560  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
561  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
562  model, body_P_sensor);
563 
564  Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
565  -0.427669306, -0.652537293, 0.709880342, 0.265075427);
566  Point3 t1(2.0, 1.0, 3.0);
567  Pose3 Pose1(R1, t1);
568  Vector3 Vel1(Vector3(0.5, -0.5, 0.4));
569  Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
570  -0.422594037, -0.636011287, 0.731761397, 0.244979388);
571  Point3 t2 = t1+ Point3(Vel1 * measurement_dt);
572  Pose3 Pose2(R2, t2);
573  Vector dv =
574  measurement_dt
575  * (R1.matrix() * body_P_sensor.rotation().matrix()
576  * Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
577  + world_g);
578  Vector3 Vel2 = Vel1 + dv;
579  imuBias::ConstantBias Bias1;
580 
581  Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
582  Vector ExpectedErr(Z_9x1);
583 
584  // TODO: Expected values need to be updated for global velocity version
585  CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
586 }
587 
588 /* ************************************************************************* */TEST (InertialNavFactor_GlobalVelocity, JacobianWithTransform ) {
589 
590  Key PoseKey1(11);
591  Key PoseKey2(12);
592  Key VelKey1(21);
593  Key VelKey2(22);
594  Key BiasKey1(31);
595 
596  double measurement_dt(0.01);
597 
598  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
599 
600  Pose3 body_P_sensor(Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1), Point3(1.0, -2.0, 3.0)); // IMU is in ENU orientation
601 
602  Vector measurement_gyro((Vector(3) << 3.14 / 2, 3.14, +3.14).finished()); // Measured in ENU orientation
603  Matrix omega__cross = skewSymmetric(measurement_gyro);
604  Vector measurement_acc =
605  Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
606  + omega__cross * omega__cross
607  * body_P_sensor.rotation().inverse().matrix()
608  * body_P_sensor.translation(); // Measured in ENU orientation
609 
611  PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
612  measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth,
613  model, body_P_sensor);
614 
615  Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
616  -0.427669306, -0.652537293, 0.709880342, 0.265075427);
617  Point3 t1(2.0, 1.0, 3.0);
618  Pose3 Pose1(R1, t1);
619  Vector3 Vel1(0.5, -0.5, 0.4);
620  Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
621  -0.422594037, -0.636011287, 0.731761397, 0.244979388);
622  Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
623  Pose3 Pose2(R2, t2);
624  Vector3 Vel2(0.510000000000000, -0.480000000000000, 0.430000000000000);
625  imuBias::ConstantBias Bias1;
626 
627  Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
628 
629  Vector ActualErr(
630  factor.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
631  H2_actual, H3_actual, H4_actual, H5_actual));
632 
633  // Checking for Pose part in the jacobians
634  // ******
635  Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
636  Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
637  Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
638  Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
639  Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
640 
641  // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
642  Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
643  H5_expectedPose;
644  H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
645  boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor),
646  Pose1);
647  H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
648  boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor),
649  Vel1);
650  H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
651  boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor),
652  Bias1);
653  H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
654  boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor),
655  Pose2);
656  H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
657  boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor),
658  Vel2);
659 
660  // Verify they are equal for this choice of state
661  CHECK( assert_equal(H1_expectedPose, H1_actualPose, 1e-5));
662  CHECK( assert_equal(H2_expectedPose, H2_actualPose, 1e-5));
663  CHECK( assert_equal(H3_expectedPose, H3_actualPose, 2e-3));
664  CHECK( assert_equal(H4_expectedPose, H4_actualPose, 1e-5));
665  CHECK( assert_equal(H5_expectedPose, H5_actualPose, 1e-5));
666 
667  // Checking for Vel part in the jacobians
668  // ******
669  Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
670  Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
671  Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
672  Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
673  Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
674 
675  // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
676  Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
677  H5_expectedVel;
678  H1_expectedVel = numericalDerivative11<Vector, Pose3>(
679  boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor),
680  Pose1);
681  H2_expectedVel = numericalDerivative11<Vector, Vector3>(
682  boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor),
683  Vel1);
684  H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
685  boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor),
686  Bias1);
687  H4_expectedVel = numericalDerivative11<Vector, Pose3>(
688  boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor),
689  Pose2);
690  H5_expectedVel = numericalDerivative11<Vector, Vector3>(
691  boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor),
692  Vel2);
693 
694  // Verify they are equal for this choice of state
695  CHECK( assert_equal(H1_expectedVel, H1_actualVel, 1e-5));
696  CHECK( assert_equal(H2_expectedVel, H2_actualVel, 1e-5));
697  CHECK( assert_equal(H3_expectedVel, H3_actualVel, 1e-5));
698  CHECK( assert_equal(H4_expectedVel, H4_actualVel, 1e-5));
699  CHECK( assert_equal(H5_expectedVel, H5_actualVel, 1e-5));
700 }
701 
702 /* ************************************************************************* */
703 int main() {
704  TestResult tr;
705  return TestRegistry::runAllTests(tr);
706 }
707 /* ************************************************************************* */
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:109
Vector predictionErrorVel(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
TEST(InertialNavFactor_GlobalVelocity, Constructor)
Vector v2
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
A non-templated config holding any types of Manifold-group elements.
Vector3f p1
Inertial navigation factor (velocity in the global frame)
noiseModel::Diagonal::shared_ptr model
Pose3 predictionErrorPose(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
Some functions to compute numerical derivatives.
Matrix3 matrix() const
Definition: Rot3M.cpp:219
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
void g(const string &key, int i)
Definition: testBTree.cpp:43
static const Vector3 world_omega_earth
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
static const Vector3 world_rho(0.0,-1.5724e-05, 0.0)
Eigen::VectorXd Vector
Definition: Vector.h:38
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 world_g(0.0, 0.0, 9.81)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
traits
Definition: chartTesting.h:28
Vector2 b1(2,-1)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
static const Vector3 ECEF_omega_earth(0.0, 0.0, 7.292115e-5)
Rot3 world_R_ECEF(0.31686, 0.51505, 0.79645, 0.85173,-0.52399, 0, 0.41733, 0.67835,-0.60471)
static Point3 p2
Vector3 Point3
Definition: Point3.h:35
void predict(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2) const
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none) const override
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:23