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 LocalizationExample.cpp
14 * @brief Simple robot localization example, with three "GPS-like" measurements
15 * @author Frank Dellaert
16 */
17
18/**
19 * A simple 2D pose slam example with "GPS" measurements
20 * - The robot moves forward 2 meter each iteration
21 * - The robot initially faces along the X axis (horizontal, to the right in 2D)
22 * - We have full odometry between pose
23 * - We have "GPS-like" measurements implemented with a custom factor
24 */
25
26// We will use Pose2 variables (x, y, theta) to represent the robot positions
27#include <gtsam/geometry/Pose2.h>
28
29// We will use simple integer Keys to refer to the robot poses.
30#include <gtsam/inference/Key.h>
31
32// As in OdometryExample.cpp, we use a BetweenFactor to model odometry measurements.
33#include <gtsam/slam/BetweenFactor.h>
34
35// We add all facors to a Nonlinear Factor Graph, as our factors are nonlinear.
36#include <gtsam/nonlinear/NonlinearFactorGraph.h>
37
38// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
39// nonlinear functions around an initial linearization point, then solve the linear system
40// to update the linearization point. This happens repeatedly until the solver converges
41// to a consistent set of variable values. This requires us to specify an initial guess
42// for each variable, held in a Values container.
43#include <gtsam/nonlinear/Values.h>
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// standard Levenberg-Marquardt solver
49#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
50
51// Once the optimized values have been calculated, we can also calculate the marginal covariance
52// of desired variables
53#include <gtsam/nonlinear/Marginals.h>
54
55using namespace std;
56using namespace gtsam;
57
58// Before we begin the example, we must create a custom unary factor to implement a
59// "GPS-like" functionality. Because standard GPS measurements provide information
60// only on the position, and not on the orientation, we cannot use a simple prior to
61// properly model this measurement.
62//
63// The factor will be a unary factor, affect only a single system variable. It will
64// also use a standard Gaussian noise model. Hence, we will derive our new factor from
65// the NoiseModelFactorN.
66#include <gtsam/nonlinear/NonlinearFactor.h>
67
68class UnaryFactor: public NoiseModelFactorN<Pose2> {
69 // The factor will hold a measurement consisting of an (X,Y) location
70 // We could this with a Point2 but here we just use two doubles
71 double mx_, my_;
72
73 public:
74
75 // Provide access to Matrix& version of evaluateError:
76 using NoiseModelFactor1<Pose2>::evaluateError;
77
78 /// shorthand for a smart pointer to a factor
79 typedef std::shared_ptr<UnaryFactor> shared_ptr;
80
81 // The constructor requires the variable key, the (X, Y) measurement value, and the noise model
82 UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
83 NoiseModelFactorN<Pose2>(model, j), mx_(x), my_(y) {}
84
85 ~UnaryFactor() override {}
86
87 // Using the NoiseModelFactorN base class there are two functions that must be overridden.
88 // The first is the 'evaluateError' function. This function implements the desired measurement
89 // function, returning a vector of errors when evaluated at the provided variable value. It
90 // must also calculate the Jacobians for this measurement function, if requested.
91 Vector evaluateError(const Pose2& q, OptionalMatrixType H) const override {
92 // The measurement function for a GPS-like measurement h(q) which predicts the measurement (m) is h(q) = q, q = [qx qy qtheta]
93 // The error is then simply calculated as E(q) = h(q) - m:
94 // error_x = q.x - mx
95 // error_y = q.y - my
96 // Node's orientation reflects in the Jacobian, in tangent space this is equal to the right-hand rule rotation matrix
97 // H = [ cos(q.theta) -sin(q.theta) 0 ]
98 // [ sin(q.theta) cos(q.theta) 0 ]
99 const Rot2& R = q.rotation();
100 if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, R.s(), R.c(), 0.0).finished();
101 return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
102 }
103
104 // The second is a 'clone' function that allows the factor to be copied. Under most
105 // circumstances, the following code that employs the default copy constructor should
106 // work fine.
107 gtsam::NonlinearFactor::shared_ptr clone() const override {
108 return std::static_pointer_cast<gtsam::NonlinearFactor>(
109 r: gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); }
110
111 // Additionally, we encourage you the use of unit testing your custom factors,
112 // (as all GTSAM factors are), in which you would need an equals and print, to satisfy the
113 // GTSAM_CONCEPT_TESTABLE_INST(T) defined in Testable.h, but these are not needed below.
114}; // UnaryFactor
115
116
117int main(int argc, char** argv) {
118 // 1. Create a factor graph container and add factors to it
119 NonlinearFactorGraph graph;
120
121 // 2a. Add odometry factors
122 // For simplicity, we will use the same noise model for each odometry factor
123 auto odometryNoise = noiseModel::Diagonal::Sigmas(sigmas: Vector3(0.2, 0.2, 0.1));
124 // Create odometry (Between) factors between consecutive poses
125 graph.emplace_shared<BetweenFactor<Pose2> >(args: 1, args: 2, args: Pose2(2.0, 0.0, 0.0), args&: odometryNoise);
126 graph.emplace_shared<BetweenFactor<Pose2> >(args: 2, args: 3, args: Pose2(2.0, 0.0, 0.0), args&: odometryNoise);
127
128 // 2b. Add "GPS-like" measurements
129 // We will use our custom UnaryFactor for this.
130 auto unaryNoise =
131 noiseModel::Diagonal::Sigmas(sigmas: Vector2(0.1, 0.1)); // 10cm std on x,y
132 graph.emplace_shared<UnaryFactor>(args: 1, args: 0.0, args: 0.0, args&: unaryNoise);
133 graph.emplace_shared<UnaryFactor>(args: 2, args: 2.0, args: 0.0, args&: unaryNoise);
134 graph.emplace_shared<UnaryFactor>(args: 3, args: 4.0, args: 0.0, args&: unaryNoise);
135 graph.print(str: "\nFactor Graph:\n"); // print
136
137 // 3. Create the data structure to hold the initialEstimate estimate to the solution
138 // For illustrative purposes, these have been deliberately set to incorrect values
139 Values initialEstimate;
140 initialEstimate.insert(j: 1, val: Pose2(0.5, 0.0, 0.2));
141 initialEstimate.insert(j: 2, val: Pose2(2.3, 0.1, -0.2));
142 initialEstimate.insert(j: 3, val: Pose2(4.1, 0.1, 0.1));
143 initialEstimate.print(str: "\nInitial Estimate:\n"); // print
144
145 // 4. Optimize using Levenberg-Marquardt optimization. The optimizer
146 // accepts an optional set of configuration parameters, controlling
147 // things like convergence criteria, the type of linear system solver
148 // to use, and the amount of information displayed during optimization.
149 // Here we will use the default set of parameters. See the
150 // documentation for the full set of parameters.
151 LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
152 Values result = optimizer.optimize();
153 result.print(str: "Final Result:\n");
154
155 // 5. Calculate and print marginal covariances for all variables
156 Marginals marginals(graph, result);
157 cout << "x1 covariance:\n" << marginals.marginalCovariance(variable: 1) << endl;
158 cout << "x2 covariance:\n" << marginals.marginalCovariance(variable: 2) << endl;
159 cout << "x3 covariance:\n" << marginals.marginalCovariance(variable: 3) << endl;
160
161 return 0;
162}
163