Pose2SLAMwSPCG.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 
24 // In contrast to that example, however, we will use a PCG solver here
26 
27 using namespace std;
28 using namespace gtsam;
29 
30 int main(int argc, char** argv) {
31  // 1. Create a factor graph container and add factors to it
33 
34  // 2a. Add a prior on the first pose, setting it to the origin
35  Pose2 prior(0.0, 0.0, 0.0); // prior at origin
36  auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
38 
39  // 2b. Add odometry factors
40  auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
45 
46  // 2c. Add the loop closure constraint
47  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
48  graph.emplace_shared<BetweenFactor<Pose2> >(5, 1, Pose2(0.0, 0.0, 0.0),
49  model);
50  graph.print("\nFactor Graph:\n"); // print
51 
52  // 3. Create the data structure to hold the initialEstimate estimate to the
53  // solution
54  Values initialEstimate;
55  initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
56  initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1));
57  initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8));
58  initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2));
59  initialEstimate.insert(5, Pose2(0.1, -0.7, 5.8));
60  initialEstimate.print("\nInitial Estimate:\n"); // print
61 
62  // 4. Single Step Optimization using Levenberg-Marquardt
64  parameters.verbosity = NonlinearOptimizerParams::ERROR;
65  parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA;
66 
67  // LM is still the outer optimization loop, but by specifying "Iterative"
68  // below We indicate that an iterative linear solver should be used. In
69  // addition, the *type* of the iterativeParams decides on the type of
70  // iterative solver, in this case the SPCG (subgraph PCG)
71  parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
72  parameters.iterativeParams = std::make_shared<SubgraphSolverParameters>();
73 
74  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
75  Values result = optimizer.optimize();
76  result.print("Final Result:\n");
77  cout << "subgraph solver final error = " << graph.error(result) << endl;
78 
79  return 0;
80 }
Pose2.h
2D Pose
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
SubgraphSolver.h
Subgraph Solver from IROS 2010.
main
int main(int argc, char **argv)
Definition: Pose2SLAMwSPCG.cpp:30
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
gtsam::IterativeOptimizationParameters::verbosity
Verbosity verbosity() const
Definition: IterativeSolver.h:61
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
BetweenFactor.h
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
priorNoise
auto priorNoise
Definition: doc/Code/OdometryExample.cpp:6
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
M_PI_2
#define M_PI_2
Definition: mconf.h:118
gtsam::Values::print
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:66
gtsam
traits
Definition: SFMdata.h:40
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
odometryNoise
auto odometryNoise
Definition: doc/Code/OdometryExample.cpp:11
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
different_sigmas::prior
const auto prior
Definition: testHybridBayesNet.cpp:238
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
gtsam::NonlinearFactorGraph::print
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactorGraph.cpp:55


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:36