35 using namespace gtsam;
47 if (strcmp(argv[1],
"--colamd"))
50 throw runtime_error(
"Usage: timeSFMBALxxx [--colamd] [BALfile]");
57 filename = argv[argc - 1];
60 return SfmData::FromBalFile(filename);
70 LevenbergMarquardtParams::SetCeresDefaults(¶ms);
79 ordering.push_back(
C(
i));
80 if (separateCalibration) ordering.push_back(
K(
i));
static SharedNoiseModel gNoiseModel
virtual const Values & optimize()
SfmData stores a bunch of SfmTracks.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
static enum @1107 ordering
static const SmartProjectionParams params
void setOrdering(const Ordering &ordering)
Data structure for dealing with Structure from Motion data.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
size_t numberCameras() const
The number of cameras.
Matrix< Scalar, Dynamic, Dynamic > C
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
SfmData preamble(int argc, char *argv[])
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
void tictoc_finishedIteration_()
size_t numberTracks() const
The number of reconstructed 3D points.
utility functions for loading datasets
noiseModel::Base::shared_ptr SharedNoiseModel