| 1 | /* ---------------------------------------------------------------------------- |
| 2 | |
| 3 | * GTSAM Copyright 2010, Georgia Tech Research Corporation, |
| 4 | * Atlanta, Georgia 30332-0415 |
| 5 | * All Rights Reserved |
| 6 | * Authors: Frank Dellaert, et al. (see THANKS for the full author list) |
| 7 | |
| 8 | * See LICENSE for the license information |
| 9 | |
| 10 | * -------------------------------------------------------------------------- */ |
| 11 | |
| 12 | /** |
| 13 | * @file CameraResectioning.cpp |
| 14 | * @brief An example of gtsam for solving the camera resectioning problem |
| 15 | * @author Duy-Nguyen Ta |
| 16 | * @date Aug 23, 2011 |
| 17 | */ |
| 18 | |
| 19 | #include <gtsam/inference/Symbol.h> |
| 20 | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> |
| 21 | #include <gtsam/geometry/PinholeCamera.h> |
| 22 | #include <gtsam/geometry/Cal3_S2.h> |
| 23 | |
| 24 | using namespace gtsam; |
| 25 | using namespace gtsam::noiseModel; |
| 26 | using symbol_shorthand::X; |
| 27 | |
| 28 | /** |
| 29 | * Unary factor on the unknown pose, resulting from meauring the projection of |
| 30 | * a known 3D point in the image |
| 31 | */ |
| 32 | class ResectioningFactor: public NoiseModelFactorN<Pose3> { |
| 33 | typedef NoiseModelFactorN<Pose3> Base; |
| 34 | |
| 35 | Cal3_S2::shared_ptr K_; ///< camera's intrinsic parameters |
| 36 | Point3 P_; ///< 3D point on the calibration rig |
| 37 | Point2 p_; ///< 2D measurement of the 3D point |
| 38 | |
| 39 | public: |
| 40 | |
| 41 | /// Construct factor given known point P and its projection p |
| 42 | ResectioningFactor(const SharedNoiseModel& model, const Key& key, |
| 43 | const Cal3_S2::shared_ptr& calib, const Point2& p, const Point3& P) : |
| 44 | Base(model, key), K_(calib), P_(P), p_(p) { |
| 45 | } |
| 46 | |
| 47 | /// evaluate the error |
| 48 | Vector evaluateError(const Pose3& pose, OptionalMatrixType H) const override { |
| 49 | PinholeCamera<Cal3_S2> camera(pose, *K_); |
| 50 | return camera.project(pw: P_, Dpose: H, OptionalNone, OptionalNone) - p_; |
| 51 | } |
| 52 | }; |
| 53 | |
| 54 | /******************************************************************************* |
| 55 | * Camera: f = 1, Image: 100x100, center: 50, 50.0 |
| 56 | * Pose (ground truth): (Xw, -Yw, -Zw, [0,0,2.0]') |
| 57 | * Known landmarks: |
| 58 | * 3D Points: (10,10,0) (-10,10,0) (-10,-10,0) (10,-10,0) |
| 59 | * Perfect measurements: |
| 60 | * 2D Point: (55,45) (45,45) (45,55) (55,55) |
| 61 | *******************************************************************************/ |
| 62 | int main(int argc, char* argv[]) { |
| 63 | /* read camera intrinsic parameters */ |
| 64 | Cal3_S2::shared_ptr calib(new Cal3_S2(1, 1, 0, 50, 50)); |
| 65 | |
| 66 | /* 1. create graph */ |
| 67 | NonlinearFactorGraph graph; |
| 68 | |
| 69 | /* 2. add factors to the graph */ |
| 70 | // add measurement factors |
| 71 | SharedDiagonal measurementNoise = Diagonal::Sigmas(sigmas: Vector2(0.5, 0.5)); |
| 72 | std::shared_ptr<ResectioningFactor> factor; |
| 73 | graph.emplace_shared<ResectioningFactor>(args&: measurementNoise, args: X(j: 1), args&: calib, |
| 74 | args: Point2(55, 45), args: Point3(10, 10, 0)); |
| 75 | graph.emplace_shared<ResectioningFactor>(args&: measurementNoise, args: X(j: 1), args&: calib, |
| 76 | args: Point2(45, 45), args: Point3(-10, 10, 0)); |
| 77 | graph.emplace_shared<ResectioningFactor>(args&: measurementNoise, args: X(j: 1), args&: calib, |
| 78 | args: Point2(45, 55), args: Point3(-10, -10, 0)); |
| 79 | graph.emplace_shared<ResectioningFactor>(args&: measurementNoise, args: X(j: 1), args&: calib, |
| 80 | args: Point2(55, 55), args: Point3(10, -10, 0)); |
| 81 | |
| 82 | /* 3. Create an initial estimate for the camera pose */ |
| 83 | Values initial; |
| 84 | initial.insert(j: X(j: 1), |
| 85 | val: Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 2))); |
| 86 | |
| 87 | /* 4. Optimize the graph using Levenberg-Marquardt*/ |
| 88 | Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); |
| 89 | result.print(str: "Final result:\n" ); |
| 90 | |
| 91 | return 0; |
| 92 | } |
| 93 | |