Pose2SLAMExample_graphviz.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>
23 #include <fstream>
24 
25 using namespace std;
26 using namespace gtsam;
27 
28 int main(int argc, char** argv) {
29  // 1. Create a factor graph container and add factors to it
31 
32  // 2a. Add a prior on the first pose, setting it to the origin
33  auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
34  graph.addPrior(1, Pose2(0, 0, 0), priorNoise);
35 
36  // For simplicity, we will use the same noise model for odometry and loop
37  // closures
38  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
39 
40  // 2b. Add odometry factors
41  graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2, 0, 0), model);
42  graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2, 0, M_PI_2), model);
43  graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2, 0, M_PI_2), model);
44  graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2, 0, M_PI_2), model);
45 
46  // 2c. Add the loop closure constraint
47  graph.emplace_shared<BetweenFactor<Pose2> >(5, 2, Pose2(2, 0, M_PI_2), model);
48 
49  // 3. Create the data structure to hold the initial estimate to the solution
50  // For illustrative purposes, these have been deliberately set to incorrect values
52  initial.insert(1, Pose2(0.5, 0.0, 0.2));
53  initial.insert(2, Pose2(2.3, 0.1, -0.2));
54  initial.insert(3, Pose2(4.1, 0.1, M_PI_2));
55  initial.insert(4, Pose2(4.0, 2.0, M_PI));
56  initial.insert(5, Pose2(2.1, 2.1, -M_PI_2));
57 
58  // Single Step Optimization using Levenberg-Marquardt
60 
61  // save factor graph as graphviz dot file
62  // Render to PDF using "fdp Pose2SLAMExample.dot -Tpdf > graph.pdf"
63  ofstream os("Pose2SLAMExample.dot");
64  graph.saveGraph(os, result);
65 
66  // Also print out to console
67  graph.saveGraph(cout, result);
68 
69  return 0;
70 }
virtual const Values & optimize()
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
#define M_PI
Definition: main.h:78
Values initial
int main(int argc, char **argv)
Definition: Half.h:150
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.
traits
Definition: chartTesting.h:28
void saveGraph(std::ostream &stm, const Values &values=Values(), const GraphvizFormatting &graphvizFormatting=GraphvizFormatting(), const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Write the graph in GraphViz format for visualization.
ofstream os("timeSchurFactors.csv")
noiseModel::Diagonal::shared_ptr priorNoise
2D Pose


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