Pose2SLAMExample_graph.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 
19 // For an explanation of headers below, please see Pose2SLAMExample.cpp
21 #include <gtsam/geometry/Pose2.h>
24 
25 // This new header allows us to read examples easily from .graph files
26 #include <gtsam/slam/dataset.h>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 int main (int argc, char** argv) {
32 
33  // Read File, create graph and initial estimate
34  // we are in build/examples, data is in examples/Data
36  Values::shared_ptr initial;
37  SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
38  string graph_file = findExampleDataFile("w100.graph");
39  boost::tie(graph, initial) = load2D(graph_file, model);
40  initial->print("Initial estimate:\n");
41 
42  // Add a Gaussian prior on first poses
43  Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
44  SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.01, 0.01, 0.01));
45  graph -> addPrior(0, priorMean, priorNoise);
46 
47  // Single Step Optimization using Levenberg-Marquardt
48  Values result = LevenbergMarquardtOptimizer(*graph, *initial).optimize();
49  result.print("\nFinal result:\n");
50 
51  // Plot the covariance of the last pose
52  Marginals marginals(*graph, result);
53  cout.precision(2);
54  cout << "\nP3:\n" << marginals.marginalCovariance(99) << endl;
55 
56  return 0;
57 }
virtual const Values & optimize()
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
Definition: dataset.cpp:500
#define M_PI
Definition: main.h:78
Values initial
Definition: Half.h:150
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
int main(int argc, char **argv)
boost::shared_ptr< This > shared_ptr
Values result
Pose2 priorMean(0.0, 0.0, 0.0)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
graph addPrior(1, priorMean, priorNoise)
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:129
A class for computing marginals in a NonlinearFactorGraph.
noiseModel::Diagonal::shared_ptr priorNoise
2D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
Marginals marginals(graph, result)


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