32 using namespace gtsam;
44 if (strcmp(argv[1],
"--colamd"))
47 throw runtime_error(
"Usage: timeSFMBALxxx [--colamd] [BALfile]");
54 filename = argv[argc - 1];
57 bool success =
readBAL(filename, db);
58 if (!success)
throw runtime_error(
"Could not access file!");
69 LevenbergMarquardtParams::SetCeresDefaults(¶ms);
78 ordering.push_back(
C(
i));
79 if (separateCalibration) ordering.push_back(
K(
i));
static SharedNoiseModel gNoiseModel
virtual const Values & optimize()
Define the structure for SfM data.
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)
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
size_t number_tracks() const
The number of reconstructed 3D points.
void setOrdering(const Ordering &ordering)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
static SmartStereoProjectionParams params
Matrix< Scalar, Dynamic, Dynamic > C
SfmData preamble(int argc, char *argv[])
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
void tictoc_finishedIteration_()
utility functions for loading datasets
noiseModel::Base::shared_ptr SharedNoiseModel
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...
size_t number_cameras() const