CameraResectioning.cpp 3.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  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 CameraResectioning.cpp
  10. * @brief An example of gtsam for solving the camera resectioning problem
  11. * @author Duy-Nguyen Ta
  12. * @date Aug 23, 2011
  13. */
  14. #include <gtsam/inference/Symbol.h>
  15. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  16. #include <gtsam/geometry/PinholeCamera.h>
  17. #include <gtsam/geometry/Cal3_S2.h>
  18. #include <boost/make_shared.hpp>
  19. using namespace gtsam;
  20. using namespace gtsam::noiseModel;
  21. using symbol_shorthand::X;
  22. /**
  23. * Unary factor on the unknown pose, resulting from meauring the projection of
  24. * a known 3D point in the image
  25. */
  26. class ResectioningFactor: public NoiseModelFactor1<Pose3> {
  27. typedef NoiseModelFactor1<Pose3> Base;
  28. Cal3_S2::shared_ptr K_; ///< camera's intrinsic parameters
  29. Point3 P_; ///< 3D point on the calibration rig
  30. Point2 p_; ///< 2D measurement of the 3D point
  31. public:
  32. /// Construct factor given known point P and its projection p
  33. ResectioningFactor(const SharedNoiseModel& model, const Key& key,
  34. const Cal3_S2::shared_ptr& calib, const Point2& p, const Point3& P) :
  35. Base(model, key), K_(calib), P_(P), p_(p) {
  36. }
  37. /// evaluate the error
  38. Vector evaluateError(const Pose3& pose, boost::optional<Matrix&> H =
  39. boost::none) const override {
  40. PinholeCamera<Cal3_S2> camera(pose, *K_);
  41. return camera.project(P_, H, boost::none, boost::none) - p_;
  42. }
  43. };
  44. /*******************************************************************************
  45. * Camera: f = 1, Image: 100x100, center: 50, 50.0
  46. * Pose (ground truth): (Xw, -Yw, -Zw, [0,0,2.0]')
  47. * Known landmarks:
  48. * 3D Points: (10,10,0) (-10,10,0) (-10,-10,0) (10,-10,0)
  49. * Perfect measurements:
  50. * 2D Point: (55,45) (45,45) (45,55) (55,55)
  51. *******************************************************************************/
  52. int main(int argc, char* argv[]) {
  53. /* read camera intrinsic parameters */
  54. Cal3_S2::shared_ptr calib(new Cal3_S2(1, 1, 0, 50, 50));
  55. /* 1. create graph */
  56. NonlinearFactorGraph graph;
  57. /* 2. add factors to the graph */
  58. // add measurement factors
  59. SharedDiagonal measurementNoise = Diagonal::Sigmas(Vector2(0.5, 0.5));
  60. boost::shared_ptr<ResectioningFactor> factor;
  61. graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
  62. Point2(55, 45), Point3(10, 10, 0));
  63. graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
  64. Point2(45, 45), Point3(-10, 10, 0));
  65. graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
  66. Point2(45, 55), Point3(-10, -10, 0));
  67. graph.emplace_shared<ResectioningFactor>(measurementNoise, X(1), calib,
  68. Point2(55, 55), Point3(10, -10, 0));
  69. /* 3. Create an initial estimate for the camera pose */
  70. Values initial;
  71. initial.insert(X(1),
  72. Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 2)));
  73. /* 4. Optimize the graph using Levenberg-Marquardt*/
  74. Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
  75. result.print("Final result:\n");
  76. return 0;
  77. }