SFMExample_SmartFactorPCG.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126
  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 SFMExample_SmartFactorPCG.cpp
  10. * @brief Version of SFMExample_SmartFactor that uses Preconditioned Conjugate Gradient
  11. * @author Frank Dellaert
  12. */
  13. // For an explanation of these headers, see SFMExample_SmartFactor.cpp
  14. #include "SFMdata.h"
  15. #include <gtsam/slam/SmartProjectionPoseFactor.h>
  16. // These extra headers allow us a LM outer loop with PCG linear solver (inner loop)
  17. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  18. #include <gtsam/linear/Preconditioner.h>
  19. #include <gtsam/linear/PCGSolver.h>
  20. using namespace std;
  21. using namespace gtsam;
  22. // Make the typename short so it looks much cleaner
  23. typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor;
  24. // create a typedef to the camera type
  25. typedef PinholePose<Cal3_S2> Camera;
  26. /* ************************************************************************* */
  27. int main(int argc, char* argv[]) {
  28. // Define the camera calibration parameters
  29. Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
  30. // Define the camera observation noise model
  31. auto measurementNoise =
  32. noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  33. // Create the set of ground-truth landmarks and poses
  34. vector<Point3> points = createPoints();
  35. vector<Pose3> poses = createPoses();
  36. // Create a factor graph
  37. NonlinearFactorGraph graph;
  38. // Simulated measurements from each camera pose, adding them to the factor graph
  39. for (size_t j = 0; j < points.size(); ++j) {
  40. // every landmark represent a single landmark, we use shared pointer to init
  41. // the factor, and then insert measurements.
  42. SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
  43. for (size_t i = 0; i < poses.size(); ++i) {
  44. // generate the 2D measurement
  45. Camera camera(poses[i], K);
  46. Point2 measurement = camera.project(points[j]);
  47. // call add() function to add measurement into a single factor
  48. smartfactor->add(measurement, i);
  49. }
  50. // insert the smart factor in the graph
  51. graph.push_back(smartfactor);
  52. }
  53. // Add a prior on pose x0. This indirectly specifies where the origin is.
  54. // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
  55. auto noise = noiseModel::Diagonal::Sigmas(
  56. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
  57. graph.addPrior(0, poses[0], noise);
  58. // Fix the scale ambiguity by adding a prior
  59. graph.addPrior(1, poses[0], noise);
  60. // Create the initial estimate to the solution
  61. Values initialEstimate;
  62. Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
  63. for (size_t i = 0; i < poses.size(); ++i)
  64. initialEstimate.insert(i, poses[i].compose(delta));
  65. // We will use LM in the outer optimization loop, but by specifying
  66. // "Iterative" below We indicate that an iterative linear solver should be
  67. // used. In addition, the *type* of the iterativeParams decides on the type of
  68. // iterative solver, in this case the SPCG (subgraph PCG)
  69. LevenbergMarquardtParams parameters;
  70. parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
  71. parameters.absoluteErrorTol = 1e-10;
  72. parameters.relativeErrorTol = 1e-10;
  73. parameters.maxIterations = 500;
  74. PCGSolverParameters::shared_ptr pcg =
  75. boost::make_shared<PCGSolverParameters>();
  76. pcg->preconditioner_ =
  77. boost::make_shared<BlockJacobiPreconditionerParameters>();
  78. // Following is crucial:
  79. pcg->setEpsilon_abs(1e-10);
  80. pcg->setEpsilon_rel(1e-10);
  81. parameters.iterativeParams = pcg;
  82. LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
  83. Values result = optimizer.optimize();
  84. // Display result as in SFMExample_SmartFactor.run
  85. result.print("Final results:\n");
  86. Values landmark_result;
  87. for (size_t j = 0; j < points.size(); ++j) {
  88. auto smart = boost::dynamic_pointer_cast<SmartFactor>(graph[j]);
  89. if (smart) {
  90. boost::optional<Point3> point = smart->point(result);
  91. if (point) // ignore if boost::optional return nullptr
  92. landmark_result.insert(j, *point);
  93. }
  94. }
  95. landmark_result.print("Landmark results:\n");
  96. cout << "final error: " << graph.error(result) << endl;
  97. cout << "number of iterations: " << optimizer.iterations() << endl;
  98. return 0;
  99. }
  100. /* ************************************************************************* */