PlanarSLAMExample.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 // As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
29 // the robot positions and Point2 variables (x, y) to represent the landmark coordinates.
30 #include <gtsam/geometry/Pose2.h>
31 #include <gtsam/geometry/Point2.h>
32 
33 // Each variable in the system (poses and landmarks) must be identified with a unique key.
34 // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
35 // Here we will use Symbols
36 #include <gtsam/inference/Symbol.h>
37 
38 // In GTSAM, measurement functions are represented as 'factors'. Several common factors
39 // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
40 // Here we will use a RangeBearing factor for the range-bearing measurements to identified
41 // landmarks, and Between factors for the relative motion described by odometry measurements.
42 // Also, we will initialize the robot at the origin using a Prior factor.
45 
46 // When the factors are created, we will add them to a Factor Graph. As the factors we are using
47 // are nonlinear factors, we will need a Nonlinear Factor Graph.
49 
50 // Finally, once all of the factors have been added to our factor graph, we will want to
51 // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
52 // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
53 // common Levenberg-Marquardt solver
55 
56 // Once the optimized values have been calculated, we can also calculate the marginal covariance
57 // of desired variables
59 
60 // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
61 // nonlinear functions around an initial linearization point, then solve the linear system
62 // to update the linearization point. This happens repeatedly until the solver converges
63 // to a consistent set of variable values. This requires us to specify an initial guess
64 // for each variable, held in a Values container.
65 #include <gtsam/nonlinear/Values.h>
66 
67 
68 using namespace std;
69 using namespace gtsam;
70 
71 int main(int argc, char** argv) {
72  // Create a factor graph
74 
75  // Create the keys we need for this simple example
76  static Symbol x1('x', 1), x2('x', 2), x3('x', 3);
77  static Symbol l1('l', 1), l2('l', 2);
78 
79  // Add a prior on pose x1 at the origin. A prior factor consists of a mean and
80  // a noise model (covariance matrix)
81  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
82  auto priorNoise = noiseModel::Diagonal::Sigmas(
83  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
84  graph.addPrior(x1, prior, priorNoise); // add directly to graph
85 
86  // Add two odometry factors
87  Pose2 odometry(2.0, 0.0, 0.0);
88  // create a measurement for both factors (the same in this case)
89  auto odometryNoise = noiseModel::Diagonal::Sigmas(
90  Vector3(0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
93 
94  // Add Range-Bearing measurements to two different landmarks
95  // create a noise model for the landmark measurements
96  auto measurementNoise = noiseModel::Diagonal::Sigmas(
97  Vector2(0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range
98  // create the measurement values - indices are (pose id, landmark id)
99  Rot2 bearing11 = Rot2::fromDegrees(45), bearing21 = Rot2::fromDegrees(90),
100  bearing32 = Rot2::fromDegrees(90);
101  double range11 = std::sqrt(4.0 + 4.0), range21 = 2.0, range32 = 2.0;
102 
103  // Add Bearing-Range factors
104  graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x1, l1, bearing11, range11, measurementNoise);
105  graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x2, l1, bearing21, range21, measurementNoise);
106  graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x3, l2, bearing32, range32, measurementNoise);
107 
108  // Print
109  graph.print("Factor Graph:\n");
110 
111  // Create (deliberately inaccurate) initial estimate
112  Values initialEstimate;
113  initialEstimate.insert(x1, Pose2(0.5, 0.0, 0.2));
114  initialEstimate.insert(x2, Pose2(2.3, 0.1, -0.2));
115  initialEstimate.insert(x3, Pose2(4.1, 0.1, 0.1));
116  initialEstimate.insert(l1, Point2(1.8, 2.1));
117  initialEstimate.insert(l2, Point2(4.1, 1.8));
118 
119  // Print
120  initialEstimate.print("Initial Estimate:\n");
121 
122  // Optimize using Levenberg-Marquardt optimization. The optimizer
123  // accepts an optional set of configuration parameters, controlling
124  // things like convergence criteria, the type of linear system solver
125  // to use, and the amount of information displayed during optimization.
126  // Here we will use the default set of parameters. See the
127  // documentation for the full set of parameters.
128  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
129  Values result = optimizer.optimize();
130  result.print("Final Result:\n");
131 
132  // Calculate and print marginal covariances for all variables
133  Marginals marginals(graph, result);
134  print(marginals.marginalCovariance(x1), "x1 covariance");
135  print(marginals.marginalCovariance(x2), "x2 covariance");
136  print(marginals.marginalCovariance(x3), "x3 covariance");
137  print(marginals.marginalCovariance(l1), "l1 covariance");
138  print(marginals.marginalCovariance(l2), "l2 covariance");
139 
140  return 0;
141 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
noiseModel::Diagonal::shared_ptr odometryNoise
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.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
gtsam::Key l2
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Values result
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
gtsam::Key l1
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
Eigen::Vector2d Vector2
Definition: Vector.h:42
Pose3 x1
Definition: testPose3.cpp:588
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:129
A class for computing marginals in a NonlinearFactorGraph.
noiseModel::Diagonal::shared_ptr priorNoise
Pose2 odometry(2.0, 0.0, 0.0)
2D Pose
2D Point
Marginals marginals(graph, result)
int main(int argc, char **argv)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:27