timeSFMBAL.h
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>
22 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/inference/Symbol.h>
26 #include <gtsam/base/timing.h>
27 
28 #include <string>
29 #include <vector>
30 
31 using namespace std;
32 using namespace gtsam;
36 
37 static bool gUseSchur = true;
38 static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2);
39 
40 // parse options and read BAL file
41 SfmData preamble(int argc, char* argv[]) {
42  // primitive argument parsing:
43  if (argc > 2) {
44  if (strcmp(argv[1], "--colamd"))
45  gUseSchur = false;
46  else
47  throw runtime_error("Usage: timeSFMBALxxx [--colamd] [BALfile]");
48  }
49 
50  // Load BAL file
51  SfmData db;
52  string filename;
53  if (argc > 1)
54  filename = argv[argc - 1];
55  else
56  filename = findExampleDataFile("dubrovnik-16-22106-pre");
57  bool success = readBAL(filename, db);
58  if (!success) throw runtime_error("Could not access file!");
59  return db;
60 }
61 
62 // Create ordering and optimize
64  const Values& initial, bool separateCalibration = false) {
65  using symbol_shorthand::P;
66 
67  // Set parameters to be similar to ceres
69  LevenbergMarquardtParams::SetCeresDefaults(&params);
70 // params.setLinearSolverType("SEQUENTIAL_CHOLESKY");
71 // params.setVerbosityLM("SUMMARY");
72 
73  if (gUseSchur) {
74  // Create Schur-complement ordering
76  for (size_t j = 0; j < db.number_tracks(); j++) ordering.push_back(P(j));
77  for (size_t i = 0; i < db.number_cameras(); i++) {
78  ordering.push_back(C(i));
79  if (separateCalibration) ordering.push_back(K(i));
80  }
81  params.setOrdering(ordering);
82  }
83 
84  // Optimize
85  {
87  LevenbergMarquardtOptimizer lm(graph, initial, params);
88  Values result = lm.optimize();
89  }
90 
92  tictoc_print_();
93 
94  return 0;
95 }
static SharedNoiseModel gNoiseModel
Definition: timeSFMBAL.h:38
virtual const Values & optimize()
#define gttic_(label)
Definition: timing.h:230
Define the structure for SfM data.
Definition: dataset.h:326
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static enum @843 ordering
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Definition: Half.h:150
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:333
Values result
void setOrdering(const Ordering &ordering)
static bool gUseSchur
Definition: timeSFMBAL.h:37
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
void tictoc_print_()
Definition: timing.h:253
static SmartStereoProjectionParams params
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
SfmData preamble(int argc, char *argv[])
Definition: timeSFMBAL.h:41
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
utility functions for loading datasets
std::ptrdiff_t j
Timing utilities.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
Definition: dataset.cpp:1073
size_t number_cameras() const
Definition: dataset.h:329


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