cmake/example_cmake_find_gtsam/main.cpp
Go to the documentation of this file.
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 
25 // In planar SLAM example we use Pose2 variables (x, y, theta) to represent the robot poses
26 #include <gtsam/geometry/Pose2.h>
27 
28 // We will use simple integer Keys to refer to the robot poses.
29 #include <gtsam/inference/Key.h>
30 
31 // In GTSAM, measurement functions are represented as 'factors'. Several common factors
32 // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
33 // Here we will use Between factors for the relative motion described by odometry measurements.
34 // We will also use a Between Factor to encode the loop closure constraint
35 // Also, we will initialize the robot at the origin using a Prior factor.
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.
41 
42 // Finally, once all of the factors have been added to our factor graph, we will want to
43 // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
44 // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
45 // a Gauss-Newton solver
47 
48 // Once the optimized values have been calculated, we can also calculate the marginal covariance
49 // of desired variables
51 
52 // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
53 // nonlinear functions around an initial linearization point, then solve the linear system
54 // to update the linearization point. This happens repeatedly until the solver converges
55 // to a consistent set of variable values. This requires us to specify an initial guess
56 // for each variable, held in a Values container.
57 #include <gtsam/nonlinear/Values.h>
58 
59 
60 using namespace std;
61 using namespace gtsam;
62 
63 int main(int argc, char** argv) {
64 
65  // 1. Create a factor graph container and add factors to it
67 
68  // 2a. Add a prior on the first pose, setting it to the origin
69  // A prior factor consists of a mean and a noise model (covariance matrix)
70  noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
71  graph.addPrior(1, Pose2(0, 0, 0), priorNoise);
72 
73  // For simplicity, we will use the same noise model for odometry and loop closures
74  noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
75 
76  // 2b. Add odometry factors
77  // Create odometry (Between) factors between consecutive poses
78  graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2, 0, 0 ), model);
79  graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2, 0, M_PI_2), model);
80  graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2, 0, M_PI_2), model);
81  graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2, 0, M_PI_2), model);
82 
83  // 2c. Add the loop closure constraint
84  // This factor encodes the fact that we have returned to the same pose. In real systems,
85  // these constraints may be identified in many ways, such as appearance-based techniques
86  // with camera images. We will use another Between Factor to enforce this constraint:
87  graph.emplace_shared<BetweenFactor<Pose2> >(5, 2, Pose2(2, 0, M_PI_2), model);
88  graph.print("\nFactor Graph:\n"); // print
89 
90  // 3. Create the data structure to hold the initialEstimate estimate to the solution
91  // For illustrative purposes, these have been deliberately set to incorrect values
92  Values initialEstimate;
93  initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 ));
94  initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2 ));
95  initialEstimate.insert(3, Pose2(4.1, 0.1, M_PI_2));
96  initialEstimate.insert(4, Pose2(4.0, 2.0, M_PI ));
97  initialEstimate.insert(5, Pose2(2.1, 2.1, -M_PI_2));
98  initialEstimate.print("\nInitial Estimate:\n"); // print
99 
100  // 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
101  // The optimizer accepts an optional set of configuration parameters,
102  // controlling things like convergence criteria, the type of linear
103  // system solver to use, and the amount of information displayed during
104  // optimization. We will set a few parameters as a demonstration.
106  // Stop iterating once the change in error between steps is less than this value
107  parameters.relativeErrorTol = 1e-5;
108  // Do not perform more than N iteration steps
109  parameters.maxIterations = 100;
110  // Create the optimizer ...
111  GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters);
112  // ... and optimize
113  Values result = optimizer.optimize();
114  result.print("Final Result:\n");
115 
116  // 5. Calculate and print marginal covariances for all variables
117  cout.precision(3);
118  Marginals marginals(graph, result);
119  cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl;
120  cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl;
121  cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl;
122  cout << "x4 covariance:\n" << marginals.marginalCovariance(4) << endl;
123  cout << "x5 covariance:\n" << marginals.marginalCovariance(5) << endl;
124 
125  return 0;
126 }
virtual const Values & optimize()
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
int main(int argc, char **argv)
#define M_PI
Definition: main.h:78
Definition: Half.h:150
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Values result
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
static ConjugateGradientParameters parameters
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:129
A class for computing marginals in a NonlinearFactorGraph.
noiseModel::Diagonal::shared_ptr priorNoise
2D Pose
Marginals marginals(graph, result)
size_t maxIterations
The maximum iterations to stop iterating (default 100)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:35