37 using namespace gtsam;
46 bool success =
readBAL(filename, db);
47 if (!success)
throw runtime_error(
"Could not access file!");
62 double actualError = graph.
error(actual);
virtual const Values & optimize()
Define the structure for SfM data.
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
std::vector< SfmTrack > tracks
Sparse set of points.
GeneralSFMFactor< PinholeCamera< Cal3Bundler >, Point3 > sfmFactor
string findExampleDataFile(const string &name)
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
size_t number_tracks() const
The number of reconstructed 3D points.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
double error(const Values &values) const
a general SFM factor with an unknown calibration
Base class and parameters for nonlinear optimization algorithms.
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...