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