| 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 SFMExampleExpressions.cpp |
| 14 | * @brief A structure-from-motion example done with Expressions |
| 15 | * @author Frank Dellaert |
| 16 | * @author Duy-Nguyen Ta |
| 17 | * @date October 1, 2014 |
| 18 | */ |
| 19 | |
| 20 | /** |
| 21 | * This is the Expression version of SFMExample |
| 22 | * See detailed description of headers there, this focuses on explaining the AD part |
| 23 | */ |
| 24 | |
| 25 | // The two new headers that allow using our Automatic Differentiation Expression framework |
| 26 | #include <gtsam/slam/expressions.h> |
| 27 | #include <gtsam/nonlinear/ExpressionFactorGraph.h> |
| 28 | |
| 29 | // Header order is close to far |
| 30 | #include "SFMdata.h" |
| 31 | #include <gtsam/geometry/Point2.h> |
| 32 | #include <gtsam/nonlinear/DoglegOptimizer.h> |
| 33 | #include <gtsam/nonlinear/Values.h> |
| 34 | #include <gtsam/inference/Symbol.h> |
| 35 | |
| 36 | #include <vector> |
| 37 | |
| 38 | using namespace std; |
| 39 | using namespace gtsam; |
| 40 | using namespace noiseModel; |
| 41 | |
| 42 | /* ************************************************************************* */ |
| 43 | int main(int argc, char* argv[]) { |
| 44 | |
| 45 | Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0); |
| 46 | Isotropic::shared_ptr measurementNoise = Isotropic::Sigma(dim: 2, sigma: 1.0); // one pixel in u and v |
| 47 | |
| 48 | // Create the set of ground-truth landmarks and poses |
| 49 | vector<Point3> points = createPoints(); |
| 50 | vector<Pose3> poses = createPoses(); |
| 51 | |
| 52 | // Create a factor graph |
| 53 | ExpressionFactorGraph graph; |
| 54 | |
| 55 | // Specify uncertainty on first pose prior |
| 56 | Vector6 sigmas; sigmas << Vector3(0.3,0.3,0.3), Vector3(0.1,0.1,0.1); |
| 57 | Diagonal::shared_ptr poseNoise = Diagonal::Sigmas(sigmas); |
| 58 | |
| 59 | // Here we don't use a PriorFactor but directly the ExpressionFactor class |
| 60 | // x0 is an Expression, and we create a factor wanting it to be equal to poses[0] |
| 61 | Pose3_ x0('x',0); |
| 62 | graph.addExpressionFactor(h: x0, z: poses[0], R: poseNoise); |
| 63 | |
| 64 | // We create a constant Expression for the calibration here |
| 65 | Cal3_S2_ cK(K); |
| 66 | |
| 67 | // Simulated measurements from each camera pose, adding them to the factor graph |
| 68 | for (size_t i = 0; i < poses.size(); ++i) { |
| 69 | Pose3_ x('x', i); |
| 70 | PinholeCamera<Cal3_S2> camera(poses[i], K); |
| 71 | for (size_t j = 0; j < points.size(); ++j) { |
| 72 | Point2 measurement = camera.project(pw: points[j]); |
| 73 | // Below an expression for the prediction of the measurement: |
| 74 | Point3_ p('l', j); |
| 75 | Point2_ prediction = uncalibrate(K: cK, xy_hat: project(p_cam: transformTo(x, p))); |
| 76 | // Again, here we use an ExpressionFactor |
| 77 | graph.addExpressionFactor(h: prediction, z: measurement, R: measurementNoise); |
| 78 | } |
| 79 | } |
| 80 | |
| 81 | // Add prior on first point to constrain scale, again with ExpressionFactor |
| 82 | Isotropic::shared_ptr pointNoise = Isotropic::Sigma(dim: 3, sigma: 0.1); |
| 83 | graph.addExpressionFactor(h: Point3_('l', 0), z: points[0], R: pointNoise); |
| 84 | |
| 85 | // Create perturbed initial |
| 86 | Values initial; |
| 87 | Pose3 delta(Rot3::Rodrigues(wx: -0.1, wy: 0.2, wz: 0.25), Point3(0.05, -0.10, 0.20)); |
| 88 | for (size_t i = 0; i < poses.size(); ++i) |
| 89 | initial.insert(j: Symbol('x', i), val: poses[i].compose(g: delta)); |
| 90 | for (size_t j = 0; j < points.size(); ++j) |
| 91 | initial.insert<Point3>(j: Symbol('l', j), val: points[j] + Point3(-0.25, 0.20, 0.15)); |
| 92 | cout << "initial error = " << graph.error(values: initial) << endl; |
| 93 | |
| 94 | /* Optimize the graph and print results */ |
| 95 | Values result = DoglegOptimizer(graph, initial).optimize(); |
| 96 | cout << "final error = " << graph.error(values: result) << endl; |
| 97 | |
| 98 | return 0; |
| 99 | } |
| 100 | /* ************************************************************************* */ |
| 101 | |
| 102 | |