| 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 SimpleRotation.cpp |
| 14 | * @brief This is a super-simple example of optimizing a single rotation according to a single prior |
| 15 | * @date Jul 1, 2010 |
| 16 | * @author Frank Dellaert |
| 17 | * @author Alex Cunningham |
| 18 | */ |
| 19 | |
| 20 | /** |
| 21 | * This example will perform a relatively trivial optimization on |
| 22 | * a single variable with a single factor. |
| 23 | */ |
| 24 | |
| 25 | // In this example, a 2D rotation will be used as the variable of interest |
| 26 | #include <gtsam/geometry/Rot2.h> |
| 27 | |
| 28 | // Each variable in the system (poses) must be identified with a unique key. |
| 29 | // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). |
| 30 | // Here we will use symbols |
| 31 | #include <gtsam/inference/Symbol.h> |
| 32 | |
| 33 | // In GTSAM, measurement functions are represented as 'factors'. Several common factors |
| 34 | // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. |
| 35 | // We will apply a simple prior on the rotation. We do so via the `addPrior` convenience |
| 36 | // method in NonlinearFactorGraph. |
| 37 | |
| 38 | // When the factors are created, we will add them to a Factor Graph. As the factors we are using |
| 39 | // are nonlinear factors, we will need a Nonlinear Factor Graph. |
| 40 | #include <gtsam/nonlinear/NonlinearFactorGraph.h> |
| 41 | |
| 42 | // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the |
| 43 | // nonlinear functions around an initial linearization point, then solve the linear system |
| 44 | // to update the linearization point. This happens repeatedly until the solver converges |
| 45 | // to a consistent set of variable values. This requires us to specify an initial guess |
| 46 | // for each variable, held in a Values container. |
| 47 | #include <gtsam/nonlinear/Values.h> |
| 48 | |
| 49 | // Finally, once all of the factors have been added to our factor graph, we will want to |
| 50 | // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. |
| 51 | // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the |
| 52 | // standard Levenberg-Marquardt solver |
| 53 | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> |
| 54 | |
| 55 | |
| 56 | using namespace std; |
| 57 | using namespace gtsam; |
| 58 | |
| 59 | const double degree = M_PI / 180; |
| 60 | |
| 61 | int main() { |
| 62 | /** |
| 63 | * Step 1: Create a factor to express a unary constraint |
| 64 | * The "prior" in this case is the measurement from a sensor, |
| 65 | * with a model of the noise on the measurement. |
| 66 | * |
| 67 | * The "Key" created here is a label used to associate parts of the |
| 68 | * state (stored in "RotValues") with particular factors. They require |
| 69 | * an index to allow for lookup, and should be unique. |
| 70 | * |
| 71 | * In general, creating a factor requires: |
| 72 | * - A key or set of keys labeling the variables that are acted upon |
| 73 | * - A measurement value |
| 74 | * - A measurement model with the correct dimensionality for the factor |
| 75 | */ |
| 76 | Rot2 prior = Rot2::fromAngle(theta: 30 * degree); |
| 77 | prior.print(s: "goal angle" ); |
| 78 | auto model = noiseModel::Isotropic::Sigma(dim: 1, sigma: 1 * degree); |
| 79 | Symbol key('x', 1); |
| 80 | |
| 81 | /** |
| 82 | * Step 2: Create a graph container and add the factor to it |
| 83 | * Before optimizing, all factors need to be added to a Graph container, |
| 84 | * which provides the necessary top-level functionality for defining a |
| 85 | * system of constraints. |
| 86 | * |
| 87 | * In this case, there is only one factor, but in a practical scenario, |
| 88 | * many more factors would be added. |
| 89 | */ |
| 90 | NonlinearFactorGraph graph; |
| 91 | graph.addPrior(key, prior, model); |
| 92 | graph.print(str: "full graph" ); |
| 93 | |
| 94 | /** |
| 95 | * Step 3: Create an initial estimate |
| 96 | * An initial estimate of the solution for the system is necessary to |
| 97 | * start optimization. This system state is the "RotValues" structure, |
| 98 | * which is similar in structure to a STL map, in that it maps |
| 99 | * keys (the label created in step 1) to specific values. |
| 100 | * |
| 101 | * The initial estimate provided to optimization will be used as |
| 102 | * a linearization point for optimization, so it is important that |
| 103 | * all of the variables in the graph have a corresponding value in |
| 104 | * this structure. |
| 105 | * |
| 106 | * The interface to all RotValues types is the same, it only depends |
| 107 | * on the type of key used to find the appropriate value map if there |
| 108 | * are multiple types of variables. |
| 109 | */ |
| 110 | Values initial; |
| 111 | initial.insert(j: key, val: Rot2::fromAngle(theta: 20 * degree)); |
| 112 | initial.print(str: "initial estimate" ); |
| 113 | |
| 114 | /** |
| 115 | * Step 4: Optimize |
| 116 | * After formulating the problem with a graph of constraints |
| 117 | * and an initial estimate, executing optimization is as simple |
| 118 | * as calling a general optimization function with the graph and |
| 119 | * initial estimate. This will yield a new RotValues structure |
| 120 | * with the final state of the optimization. |
| 121 | */ |
| 122 | Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); |
| 123 | result.print(str: "final result" ); |
| 124 | |
| 125 | return 0; |
| 126 | } |
| 127 | |