SelfCalibrationExample.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  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 SelfCalibrationExample.cpp
  10. * @brief Based on VisualSLAMExample, but with unknown (yet fixed) calibration.
  11. * @author Frank Dellaert
  12. */
  13. /*
  14. * See the detailed documentation in Visual SLAM.
  15. * The only documentation below with deal with the self-calibration.
  16. */
  17. // For loading the data
  18. #include "SFMdata.h"
  19. // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
  20. #include <gtsam/geometry/Point2.h>
  21. // Inference and optimization
  22. #include <gtsam/inference/Symbol.h>
  23. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  24. #include <gtsam/nonlinear/DoglegOptimizer.h>
  25. #include <gtsam/nonlinear/Values.h>
  26. // SFM-specific factors
  27. #include <gtsam/slam/GeneralSFMFactor.h> // does calibration !
  28. // Standard headers
  29. #include <vector>
  30. using namespace std;
  31. using namespace gtsam;
  32. int main(int argc, char* argv[]) {
  33. // Create the set of ground-truth
  34. vector<Point3> points = createPoints();
  35. vector<Pose3> poses = createPoses();
  36. // Create the factor graph
  37. NonlinearFactorGraph graph;
  38. // Add a prior on pose x1.
  39. auto poseNoise = noiseModel::Diagonal::Sigmas(
  40. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
  41. .finished()); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
  42. graph.addPrior(Symbol('x', 0), poses[0], poseNoise);
  43. // Simulated measurements from each camera pose, adding them to the factor
  44. // graph
  45. Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
  46. auto measurementNoise =
  47. noiseModel::Isotropic::Sigma(2, 1.0);
  48. for (size_t i = 0; i < poses.size(); ++i) {
  49. for (size_t j = 0; j < points.size(); ++j) {
  50. PinholeCamera<Cal3_S2> camera(poses[i], K);
  51. Point2 measurement = camera.project(points[j]);
  52. // The only real difference with the Visual SLAM example is that here we
  53. // use a different factor type, that also calculates the Jacobian with
  54. // respect to calibration
  55. graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(
  56. measurement, measurementNoise, Symbol('x', i), Symbol('l', j),
  57. Symbol('K', 0));
  58. }
  59. }
  60. // Add a prior on the position of the first landmark.
  61. auto pointNoise =
  62. noiseModel::Isotropic::Sigma(3, 0.1);
  63. graph.addPrior(Symbol('l', 0), points[0],
  64. pointNoise); // add directly to graph
  65. // Add a prior on the calibration.
  66. auto calNoise = noiseModel::Diagonal::Sigmas(
  67. (Vector(5) << 500, 500, 0.1, 100, 100).finished());
  68. graph.addPrior(Symbol('K', 0), K, calNoise);
  69. // Create the initial estimate to the solution
  70. // now including an estimate on the camera calibration parameters
  71. Values initialEstimate;
  72. initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0));
  73. for (size_t i = 0; i < poses.size(); ++i)
  74. initialEstimate.insert(
  75. Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25),
  76. Point3(0.05, -0.10, 0.20))));
  77. for (size_t j = 0; j < points.size(); ++j)
  78. initialEstimate.insert<Point3>(Symbol('l', j),
  79. points[j] + Point3(-0.25, 0.20, 0.15));
  80. /* Optimize the graph and print results */
  81. Values result = DoglegOptimizer(graph, initialEstimate).optimize();
  82. result.print("Final results:\n");
  83. return 0;
  84. }