ImuFactorsExample2.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file ImuFactorExample2
  10. * @brief Test example for using GTSAM ImuFactor and ImuCombinedFactor with ISAM2.
  11. * @author Robert Truax
  12. */
  13. #include <gtsam/geometry/PinholeCamera.h>
  14. #include <gtsam/geometry/Cal3_S2.h>
  15. #include <gtsam/inference/Symbol.h>
  16. #include <gtsam/navigation/ImuBias.h>
  17. #include <gtsam/navigation/ImuFactor.h>
  18. #include <gtsam/navigation/Scenario.h>
  19. #include <gtsam/nonlinear/ISAM2.h>
  20. #include <gtsam/slam/BetweenFactor.h>
  21. #include <vector>
  22. using namespace std;
  23. using namespace gtsam;
  24. // Shorthand for velocity and pose variables
  25. using symbol_shorthand::V;
  26. using symbol_shorthand::X;
  27. const double kGravity = 9.81;
  28. /* ************************************************************************* */
  29. int main(int argc, char* argv[]) {
  30. auto params = PreintegrationParams::MakeSharedU(kGravity);
  31. params->setAccelerometerCovariance(I_3x3 * 0.1);
  32. params->setGyroscopeCovariance(I_3x3 * 0.1);
  33. params->setIntegrationCovariance(I_3x3 * 0.1);
  34. params->setUse2ndOrderCoriolis(false);
  35. params->setOmegaCoriolis(Vector3(0, 0, 0));
  36. Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
  37. // Start with a camera on x-axis looking at origin
  38. double radius = 30;
  39. const Point3 up(0, 0, 1), target(0, 0, 0);
  40. const Point3 position(radius, 0, 0);
  41. const auto camera = PinholeCamera<Cal3_S2>::Lookat(position, target, up);
  42. const auto pose_0 = camera.pose();
  43. // Now, create a constant-twist scenario that makes the camera orbit the
  44. // origin
  45. double angular_velocity = M_PI, // rad/sec
  46. delta_t = 1.0 / 18; // makes for 10 degrees per step
  47. Vector3 angular_velocity_vector(0, -angular_velocity, 0);
  48. Vector3 linear_velocity_vector(radius * angular_velocity, 0, 0);
  49. auto scenario = ConstantTwistScenario(angular_velocity_vector,
  50. linear_velocity_vector, pose_0);
  51. // Create a factor graph
  52. NonlinearFactorGraph newgraph;
  53. // Create (incremental) ISAM2 solver
  54. ISAM2 isam;
  55. // Create the initial estimate to the solution
  56. // Intentionally initialize the variables off from the ground truth
  57. Values initialEstimate, totalEstimate, result;
  58. // Add a prior on pose x0. This indirectly specifies where the origin is.
  59. // 0.1 rad std on roll, pitch, yaw, 30cm std on x,y,z.
  60. auto noise = noiseModel::Diagonal::Sigmas(
  61. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
  62. newgraph.addPrior(X(0), pose_0, noise);
  63. // Add imu priors
  64. Key biasKey = Symbol('b', 0);
  65. auto biasnoise = noiseModel::Diagonal::Sigmas(Vector6::Constant(0.1));
  66. newgraph.addPrior(biasKey, imuBias::ConstantBias(), biasnoise);
  67. initialEstimate.insert(biasKey, imuBias::ConstantBias());
  68. auto velnoise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1));
  69. Vector n_velocity(3);
  70. n_velocity << 0, angular_velocity * radius, 0;
  71. newgraph.addPrior(V(0), n_velocity, velnoise);
  72. initialEstimate.insert(V(0), n_velocity);
  73. // IMU preintegrator
  74. PreintegratedImuMeasurements accum(params);
  75. // Simulate poses and imu measurements, adding them to the factor graph
  76. for (size_t i = 0; i < 36; ++i) {
  77. double t = i * delta_t;
  78. if (i == 0) { // First time add two poses
  79. auto pose_1 = scenario.pose(delta_t);
  80. initialEstimate.insert(X(0), pose_0.compose(delta));
  81. initialEstimate.insert(X(1), pose_1.compose(delta));
  82. } else if (i >= 2) { // Add more poses as necessary
  83. auto pose_i = scenario.pose(t);
  84. initialEstimate.insert(X(i), pose_i.compose(delta));
  85. }
  86. if (i > 0) {
  87. // Add Bias variables periodically
  88. if (i % 5 == 0) {
  89. biasKey++;
  90. Symbol b1 = biasKey - 1;
  91. Symbol b2 = biasKey;
  92. Vector6 covvec;
  93. covvec << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1;
  94. auto cov = noiseModel::Diagonal::Variances(covvec);
  95. auto f = boost::make_shared<BetweenFactor<imuBias::ConstantBias> >(
  96. b1, b2, imuBias::ConstantBias(), cov);
  97. newgraph.add(f);
  98. initialEstimate.insert(biasKey, imuBias::ConstantBias());
  99. }
  100. // Predict acceleration and gyro measurements in (actual) body frame
  101. Vector3 measuredAcc = scenario.acceleration_b(t) -
  102. scenario.rotation(t).transpose() * params->n_gravity;
  103. Vector3 measuredOmega = scenario.omega_b(t);
  104. accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t);
  105. // Add Imu Factor
  106. ImuFactor imufac(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum);
  107. newgraph.add(imufac);
  108. // insert new velocity, which is wrong
  109. initialEstimate.insert(V(i), n_velocity);
  110. accum.resetIntegration();
  111. }
  112. // Incremental solution
  113. isam.update(newgraph, initialEstimate);
  114. result = isam.calculateEstimate();
  115. newgraph = NonlinearFactorGraph();
  116. initialEstimate.clear();
  117. }
  118. GTSAM_PRINT(result);
  119. return 0;
  120. }
  121. /* ************************************************************************* */