ISAM2Example_SmartFactor.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121
  1. /**
  2. * @file ISAM2Example_SmartFactor.cpp
  3. * @brief test of iSAM with smart factors, led to bitbucket issue #367
  4. * @author Alexander (pumaking on BitBucket)
  5. */
  6. #include <gtsam/geometry/PinholeCamera.h>
  7. #include <gtsam/geometry/Cal3_S2.h>
  8. #include <gtsam/nonlinear/ISAM2.h>
  9. #include <gtsam/slam/BetweenFactor.h>
  10. #include <gtsam/slam/SmartProjectionPoseFactor.h>
  11. #include <iostream>
  12. #include <vector>
  13. using namespace std;
  14. using namespace gtsam;
  15. using symbol_shorthand::P;
  16. using symbol_shorthand::X;
  17. // Make the typename short so it looks much cleaner
  18. typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor;
  19. int main(int argc, char* argv[]) {
  20. Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
  21. auto measurementNoise =
  22. noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  23. Vector6 sigmas;
  24. sigmas << Vector3::Constant(0.1), Vector3::Constant(0.3);
  25. auto noise = noiseModel::Diagonal::Sigmas(sigmas);
  26. ISAM2Params parameters;
  27. parameters.relinearizeThreshold = 0.01;
  28. parameters.relinearizeSkip = 1;
  29. parameters.cacheLinearizedFactors = false;
  30. parameters.enableDetailedResults = true;
  31. parameters.print();
  32. ISAM2 isam(parameters);
  33. // Create a factor graph
  34. NonlinearFactorGraph graph;
  35. Values initialEstimate;
  36. Point3 point(0.0, 0.0, 1.0);
  37. // Intentionally initialize the variables off from the ground truth
  38. Pose3 delta(Rot3::Rodrigues(0.0, 0.0, 0.0), Point3(0.05, -0.10, 0.20));
  39. Pose3 pose1(Rot3(), Point3(0.0, 0.0, 0.0));
  40. Pose3 pose2(Rot3(), Point3(0.0, 0.2, 0.0));
  41. Pose3 pose3(Rot3(), Point3(0.0, 0.4, 0.0));
  42. Pose3 pose4(Rot3(), Point3(0.0, 0.5, 0.0));
  43. Pose3 pose5(Rot3(), Point3(0.0, 0.6, 0.0));
  44. vector<Pose3> poses = {pose1, pose2, pose3, pose4, pose5};
  45. // Add first pose
  46. graph.addPrior(X(0), poses[0], noise);
  47. initialEstimate.insert(X(0), poses[0].compose(delta));
  48. // Create smart factor with measurement from first pose only
  49. SmartFactor::shared_ptr smartFactor(new SmartFactor(measurementNoise, K));
  50. smartFactor->add(PinholePose<Cal3_S2>(poses[0], K).project(point), X(0));
  51. graph.push_back(smartFactor);
  52. // loop over remaining poses
  53. for (size_t i = 1; i < 5; i++) {
  54. cout << "****************************************************" << endl;
  55. cout << "i = " << i << endl;
  56. // Add prior on new pose
  57. graph.addPrior(X(i), poses[i], noise);
  58. initialEstimate.insert(X(i), poses[i].compose(delta));
  59. // "Simulate" measurement from this pose
  60. PinholePose<Cal3_S2> camera(poses[i], K);
  61. Point2 measurement = camera.project(point);
  62. cout << "Measurement " << i << "" << measurement << endl;
  63. // Add measurement to smart factor
  64. smartFactor->add(measurement, X(i));
  65. // Update iSAM2
  66. ISAM2Result result = isam.update(graph, initialEstimate);
  67. result.print();
  68. cout << "Detailed results:" << endl;
  69. for (auto keyedStatus : result.detail->variableStatus) {
  70. const auto& status = keyedStatus.second;
  71. PrintKey(keyedStatus.first);
  72. cout << " {" << endl;
  73. cout << "reeliminated: " << status.isReeliminated << endl;
  74. cout << "relinearized above thresh: " << status.isAboveRelinThreshold
  75. << endl;
  76. cout << "relinearized involved: " << status.isRelinearizeInvolved << endl;
  77. cout << "relinearized: " << status.isRelinearized << endl;
  78. cout << "observed: " << status.isObserved << endl;
  79. cout << "new: " << status.isNew << endl;
  80. cout << "in the root clique: " << status.inRootClique << endl;
  81. cout << "}" << endl;
  82. }
  83. Values currentEstimate = isam.calculateEstimate();
  84. currentEstimate.print("Current estimate: ");
  85. boost::optional<Point3> pointEstimate = smartFactor->point(currentEstimate);
  86. if (pointEstimate) {
  87. cout << *pointEstimate << endl;
  88. } else {
  89. cout << "Point degenerate." << endl;
  90. }
  91. // Reset graph and initial estimate for next iteration
  92. graph.resize(0);
  93. initialEstimate.clear();
  94. }
  95. return 0;
  96. }