timeLago.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 #include <gtsam/slam/dataset.h>
20 #include <gtsam/slam/lago.h>
21 #include <gtsam/geometry/Pose2.h>
23 #include <gtsam/linear/Sampler.h>
24 #include <gtsam/base/timing.h>
25 
26 #include <iostream>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 int main(int argc, char *argv[]) {
32 
33  size_t trials = 1;
34 
35  // read graph
36  Values::shared_ptr solution;
38  string inputFile = findExampleDataFile("w10000");
39  SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
40  boost::tie(g, solution) = load2D(inputFile, model);
41 
42  // add noise to create initial estimate
44  Sampler sampler(42u);
45  Values::ConstFiltered<Pose2> poses = solution->filter<Pose2>();
46  SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
47  for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: poses)
48  initial.insert(it.key, it.value.retract(sampler.sampleNewModel(noise)));
49 
50  // Add prior on the pose having index (key) = 0
52  noiseModel::Diagonal::Sigmas(Vector3(1e-6, 1e-6, 1e-8));
53  g->addPrior(0, Pose2(), priorModel);
54 
55  // LAGO
56  for (size_t i = 0; i < trials; i++) {
57  {
58  gttic_(lago);
59 
60  gttic_(init);
61  Values lagoInitial = lago::initialize(*g);
62  gttoc_(init);
63 
64  gttic_(refine);
65  GaussNewtonOptimizer optimizer(*g, lagoInitial);
66  Values result = optimizer.optimize();
67  gttoc_(refine);
68  }
69 
70  {
72  GaussNewtonOptimizer optimizer(*g, initial);
73  Values result = optimizer.optimize();
74  }
75 
77  }
78 
79  tictoc_print_();
80 
81  return 0;
82 }
virtual const Values & optimize()
#define gttic_(label)
Definition: timing.h:230
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
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
void g(const string &key, int i)
Definition: testBTree.cpp:43
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers:
string inputFile
boost::shared_ptr< This > shared_ptr
Values result
void tictoc_print_()
Definition: timing.h:253
Array< double, 1, 3 > e(1./3., 0.5, 2.)
sampling from a NoiseModel
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63
void tictoc_finishedIteration_()
Definition: timing.h:249
2D Pose
#define gttoc_(label)
Definition: timing.h:235
int main(int argc, char *argv[])
Definition: timeLago.cpp:31
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:338
utility functions for loading datasets
Timing utilities.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:34