Pose3Localization.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 
20 #include <gtsam/slam/dataset.h>
24 #include <fstream>
25 
26 using namespace std;
27 using namespace gtsam;
28 
29 int main(const int argc, const char* argv[]) {
30  // Read graph from file
31  string g2oFile;
32  if (argc < 2)
33  g2oFile = findExampleDataFile("pose3Localizationexample.txt");
34  else
35  g2oFile = argv[1];
36 
38  Values::shared_ptr initial;
39  bool is3D = true;
40  boost::tie(graph, initial) = readG2o(g2oFile, is3D);
41 
42  // Add prior on the first key
43  auto priorModel = noiseModel::Diagonal::Variances(
44  (Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
45  Key firstKey = 0;
46  for (const auto key_value : *initial) {
47  std::cout << "Adding prior to g2o file " << std::endl;
48  firstKey = key_value.key;
49  graph->addPrior(firstKey, Pose3(), priorModel);
50  break;
51  }
52 
53  std::cout << "Optimizing the factor graph" << std::endl;
55  params.setVerbosity("TERMINATION"); // show info about stopping conditions
56  GaussNewtonOptimizer optimizer(*graph, *initial, params);
57  Values result = optimizer.optimize();
58  std::cout << "Optimization complete" << std::endl;
59 
60  std::cout << "initial error=" << graph->error(*initial) << std::endl;
61  std::cout << "final error=" << graph->error(result) << std::endl;
62 
63  if (argc < 3) {
64  result.print("result");
65  } else {
66  const string outputFile = argv[2];
67  std::cout << "Writing results to file: " << outputFile << std::endl;
69  Values::shared_ptr initial2;
70  boost::tie(graphNoKernel, initial2) = readG2o(g2oFile);
71  writeG2o(*graphNoKernel, result, outputFile);
72  std::cout << "done! " << std::endl;
73  }
74 
75  // Calculate and print marginal covariances for all variables
76  Marginals marginals(*graph, result);
77  for (const auto key_value : result) {
78  auto p = dynamic_cast<const GenericValue<Pose3>*>(&key_value.value);
79  if (!p) continue;
80  std::cout << marginals.marginalCovariance(key_value.key) << endl;
81  }
82  return 0;
83 }
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure. ...
Definition: dataset.cpp:630
virtual const Values & optimize()
Values initial
Definition: Half.h:150
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
boost::shared_ptr< This > shared_ptr
Values result
void setVerbosity(const std::string &src)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
string outputFile
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:129
float * p
A class for computing marginals in a NonlinearFactorGraph.
int main(const int argc, const char *argv[])
GraphAndValues readG2o(const string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
Definition: dataset.cpp:615
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Marginals marginals(graph, result)


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