SFMExample.cpp 5.3 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.cpp
  10. * @brief A structure-from-motion problem on a simulated dataset
  11. * @author Duy-Nguyen Ta
  12. */
  13. // For loading the data, see the comments therein for scenario (camera rotates around cube)
  14. #include "SFMdata.h"
  15. // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
  16. #include <gtsam/geometry/Point2.h>
  17. // Each variable in the system (poses and landmarks) must be identified with a unique key.
  18. // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
  19. // Here we will use Symbols
  20. #include <gtsam/inference/Symbol.h>
  21. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  22. // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
  23. // Here we will use Projection factors to model the camera's landmark observations.
  24. // Also, we will initialize the robot at some location using a Prior factor.
  25. #include <gtsam/slam/ProjectionFactor.h>
  26. // When the factors are created, we will add them to a Factor Graph. As the factors we are using
  27. // are nonlinear factors, we will need a Nonlinear Factor Graph.
  28. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  29. // Finally, once all of the factors have been added to our factor graph, we will want to
  30. // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
  31. // GTSAM includes several nonlinear optimizers to perform this step. Here we will use a
  32. // trust-region method known as Powell's Degleg
  33. #include <gtsam/nonlinear/DoglegOptimizer.h>
  34. // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
  35. // nonlinear functions around an initial linearization point, then solve the linear system
  36. // to update the linearization point. This happens repeatedly until the solver converges
  37. // to a consistent set of variable values. This requires us to specify an initial guess
  38. // for each variable, held in a Values container.
  39. #include <gtsam/nonlinear/Values.h>
  40. #include <vector>
  41. using namespace std;
  42. using namespace gtsam;
  43. /* ************************************************************************* */
  44. int main(int argc, char* argv[]) {
  45. // Define the camera calibration parameters
  46. Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
  47. // Define the camera observation noise model
  48. auto measurementNoise =
  49. noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  50. // Create the set of ground-truth landmarks
  51. vector<Point3> points = createPoints();
  52. // Create the set of ground-truth poses
  53. vector<Pose3> poses = createPoses();
  54. // Create a factor graph
  55. NonlinearFactorGraph graph;
  56. // Add a prior on pose x1. This indirectly specifies where the origin is.
  57. auto poseNoise = noiseModel::Diagonal::Sigmas(
  58. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
  59. .finished()); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
  60. graph.addPrior(Symbol('x', 0), poses[0], poseNoise); // add directly to graph
  61. // Simulated measurements from each camera pose, adding them to the factor
  62. // graph
  63. for (size_t i = 0; i < poses.size(); ++i) {
  64. PinholeCamera<Cal3_S2> camera(poses[i], *K);
  65. for (size_t j = 0; j < points.size(); ++j) {
  66. Point2 measurement = camera.project(points[j]);
  67. graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(
  68. measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
  69. }
  70. }
  71. // Because the structure-from-motion problem has a scale ambiguity, the
  72. // problem is still under-constrained Here we add a prior on the position of
  73. // the first landmark. This fixes the scale by indicating the distance between
  74. // the first camera and the first landmark. All other landmark positions are
  75. // interpreted using this scale.
  76. auto pointNoise = noiseModel::Isotropic::Sigma(3, 0.1);
  77. graph.addPrior(Symbol('l', 0), points[0],
  78. pointNoise); // add directly to graph
  79. graph.print("Factor Graph:\n");
  80. // Create the data structure to hold the initial estimate to the solution
  81. // Intentionally initialize the variables off from the ground truth
  82. Values initialEstimate;
  83. for (size_t i = 0; i < poses.size(); ++i) {
  84. auto corrupted_pose = poses[i].compose(
  85. Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)));
  86. initialEstimate.insert(
  87. Symbol('x', i), corrupted_pose);
  88. }
  89. for (size_t j = 0; j < points.size(); ++j) {
  90. Point3 corrupted_point = points[j] + Point3(-0.25, 0.20, 0.15);
  91. initialEstimate.insert<Point3>(Symbol('l', j), corrupted_point);
  92. }
  93. initialEstimate.print("Initial Estimates:\n");
  94. /* Optimize the graph and print results */
  95. Values result = DoglegOptimizer(graph, initialEstimate).optimize();
  96. result.print("Final results:\n");
  97. cout << "initial error = " << graph.error(initialEstimate) << endl;
  98. cout << "final error = " << graph.error(result) << endl;
  99. return 0;
  100. }
  101. /* ************************************************************************* */