ConcurrentCalibration.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  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 ConcurrentCalibration.cpp
  10. * @brief First step towards estimating monocular calibration in concurrent
  11. * filter/smoother framework. To start with, just batch LM.
  12. * @date June 11, 2014
  13. * @author Chris Beall
  14. */
  15. #include <gtsam/geometry/Pose3.h>
  16. #include <gtsam/nonlinear/Values.h>
  17. #include <gtsam/nonlinear/NonlinearEquality.h>
  18. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  19. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  20. #include <gtsam/inference/Symbol.h>
  21. #include <gtsam/slam/ProjectionFactor.h>
  22. #include <gtsam/slam/GeneralSFMFactor.h>
  23. #include <gtsam/slam/dataset.h>
  24. #include <string>
  25. #include <fstream>
  26. #include <iostream>
  27. #include <boost/lexical_cast.hpp>
  28. using namespace std;
  29. using namespace gtsam;
  30. int main(int argc, char** argv){
  31. Values initial_estimate;
  32. NonlinearFactorGraph graph;
  33. const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1);
  34. string calibration_loc = findExampleDataFile("VO_calibration00s.txt");
  35. string pose_loc = findExampleDataFile("VO_camera_poses00s.txt");
  36. string factor_loc = findExampleDataFile("VO_stereo_factors00s.txt");
  37. //read camera calibration info from file
  38. // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
  39. double fx, fy, s, u0, v0, b;
  40. ifstream calibration_file(calibration_loc.c_str());
  41. cout << "Reading calibration info" << endl;
  42. calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
  43. //create stereo camera calibration object
  44. const Cal3_S2::shared_ptr K(new Cal3_S2(fx,fy,s,u0,v0));
  45. const Cal3_S2::shared_ptr noisy_K(new Cal3_S2(fx*1.2,fy*1.2,s,u0-10,v0+10));
  46. initial_estimate.insert(Symbol('K', 0), *noisy_K);
  47. noiseModel::Diagonal::shared_ptr calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 1e-5, 100, 100).finished());
  48. graph.addPrior(Symbol('K', 0), *noisy_K, calNoise);
  49. ifstream pose_file(pose_loc.c_str());
  50. cout << "Reading camera poses" << endl;
  51. int pose_id;
  52. MatrixRowMajor m(4,4);
  53. //read camera pose parameters and use to make initial estimates of camera poses
  54. while (pose_file >> pose_id) {
  55. for (int i = 0; i < 16; i++) {
  56. pose_file >> m.data()[i];
  57. }
  58. initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
  59. }
  60. noiseModel::Isotropic::shared_ptr poseNoise = noiseModel::Isotropic::Sigma(6, 0.01);
  61. graph.addPrior(Symbol('x', pose_id), Pose3(m), poseNoise);
  62. // camera and landmark keys
  63. size_t x, l;
  64. // pixel coordinates uL, uR, v (same for left/right images due to rectification)
  65. // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
  66. double uL, uR, v, X, Y, Z;
  67. ifstream factor_file(factor_loc.c_str());
  68. cout << "Reading stereo factors" << endl;
  69. //read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation
  70. while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
  71. // graph.emplace_shared<GenericStereoFactor<Pose3, Point3> >(StereoPoint2(uL, uR, v), model, Symbol('x', x), Symbol('l', l), K);
  72. graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(Point2(uL,v), model, Symbol('x', x), Symbol('l', l), Symbol('K', 0));
  73. //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it
  74. if (!initial_estimate.exists(Symbol('l', l))) {
  75. Pose3 camPose = initial_estimate.at<Pose3>(Symbol('x', x));
  76. //transformFrom() transforms the input Point3 from the camera pose space, camPose, to the global space
  77. Point3 worldPoint = camPose.transformFrom(Point3(X, Y, Z));
  78. initial_estimate.insert(Symbol('l', l), worldPoint);
  79. }
  80. }
  81. Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1));
  82. //constrain the first pose such that it cannot change from its original value during optimization
  83. // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
  84. // QR is much slower than Cholesky, but numerically more stable
  85. graph.emplace_shared<NonlinearEquality<Pose3> >(Symbol('x',1),first_pose);
  86. cout << "Optimizing" << endl;
  87. LevenbergMarquardtParams params;
  88. params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
  89. params.verbosity = NonlinearOptimizerParams::ERROR;
  90. //create Levenberg-Marquardt optimizer to optimize the factor graph
  91. LevenbergMarquardtOptimizer optimizer(graph, initial_estimate,params);
  92. // Values result = optimizer.optimize();
  93. string K_values_file = "K_values.txt";
  94. ofstream stream_K(K_values_file.c_str());
  95. double currentError;
  96. stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl;
  97. // Iterative loop
  98. do {
  99. // Do next iteration
  100. currentError = optimizer.error();
  101. optimizer.iterate();
  102. stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl;
  103. if(params.verbosity >= NonlinearOptimizerParams::ERROR) cout << "newError: " << optimizer.error() << endl;
  104. } while(optimizer.iterations() < params.maxIterations &&
  105. !checkConvergence(params.relativeErrorTol, params.absoluteErrorTol,
  106. params.errorTol, currentError, optimizer.error(), params.verbosity));
  107. Values result = optimizer.values();
  108. cout << "Final result sample:" << endl;
  109. Values pose_values = result.filter<Pose3>();
  110. pose_values.print("Final camera poses:\n");
  111. Values(result.filter<Cal3_S2>()).print("Final K\n");
  112. noisy_K->print("Initial noisy K\n");
  113. K->print("Initial correct K\n");
  114. return 0;
  115. }