Updated documentation on SimpleRotation example

release/4.3a0
Stephen Williams 2012-07-22 05:43:44 +00:00
parent e3a6282ff8
commit ff522a73c0
1 changed files with 35 additions and 19 deletions

View File

@ -17,20 +17,41 @@
* @author Alex Cunningham * @author Alex Cunningham
*/ */
#include <cmath> /**
#include <iostream> * This example will perform a relatively trivial optimization on
#include <gtsam/slam/PriorFactor.h> * a single variable with a single factor.
*/
// In this example, a 2D rotation will be used as the variable of interest
#include <gtsam/geometry/Rot2.h> #include <gtsam/geometry/Rot2.h>
#include <gtsam/linear/NoiseModel.h>
// Each variable in the system (poses) must be identified with a unique key.
// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
// Here we will use symbols
#include <gtsam/nonlinear/Symbol.h> #include <gtsam/nonlinear/Symbol.h>
// In GTSAM, measurement functions are represented as 'factors'. Several common factors
// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
// We will apply a simple prior on the rotation
#include <gtsam/slam/PriorFactor.h>
// When the factors are created, we will add them to a Factor Graph. As the factors we are using
// are nonlinear factors, we will need a Nonlinear Factor Graph.
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
// nonlinear functions around an initial linearization point, then solve the linear system
// to update the linearization point. This happens repeatedly until the solver converges
// to a consistent set of variable values. This requires us to specify an initial guess
// for each variable, held in a Values container.
#include <gtsam/nonlinear/Values.h>
// Finally, once all of the factors have been added to our factor graph, we will want to
// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
// standard Levenberg-Marquardt solver
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
/*
* TODO: make factors independent of RotValues
* TODO: make toplevel documentation
* TODO: Clean up nonlinear optimization API
*/
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
@ -40,12 +61,7 @@ const double degree = M_PI / 180;
int main() { int main() {
/** /**
* This example will perform a relatively trivial optimization on * Step 1: Create a factor to express a unary constraint
* a single variable with a single factor.
*/
/**
* Step 1: create a factor on to express a unary constraint
* The "prior" in this case is the measurement from a sensor, * The "prior" in this case is the measurement from a sensor,
* with a model of the noise on the measurement. * with a model of the noise on the measurement.
* *
@ -60,12 +76,12 @@ int main() {
*/ */
Rot2 prior = Rot2::fromAngle(30 * degree); Rot2 prior = Rot2::fromAngle(30 * degree);
prior.print("goal angle"); prior.print("goal angle");
SharedDiagonal model = noiseModel::Isotropic::Sigma(1, 1 * degree); noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(1, 1 * degree);
Symbol key('x',1); Symbol key('x',1);
PriorFactor<Rot2> factor(key, prior, model); PriorFactor<Rot2> factor(key, prior, model);
/** /**
* Step 2: create a graph container and add the factor to it * Step 2: Create a graph container and add the factor to it
* Before optimizing, all factors need to be added to a Graph container, * Before optimizing, all factors need to be added to a Graph container,
* which provides the necessary top-level functionality for defining a * which provides the necessary top-level functionality for defining a
* system of constraints. * system of constraints.
@ -78,7 +94,7 @@ int main() {
graph.print("full graph"); graph.print("full graph");
/** /**
* Step 3: create an initial estimate * Step 3: Create an initial estimate
* An initial estimate of the solution for the system is necessary to * An initial estimate of the solution for the system is necessary to
* start optimization. This system state is the "RotValues" structure, * start optimization. This system state is the "RotValues" structure,
* which is similar in structure to a STL map, in that it maps * which is similar in structure to a STL map, in that it maps
@ -98,7 +114,7 @@ int main() {
initial.print("initial estimate"); initial.print("initial estimate");
/** /**
* Step 4: optimize * Step 4: Optimize
* After formulating the problem with a graph of constraints * After formulating the problem with a graph of constraints
* and an initial estimate, executing optimization is as simple * and an initial estimate, executing optimization is as simple
* as calling a general optimization function with the graph and * as calling a general optimization function with the graph and