SimpleRotation.cpp 4.9 KB

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