/* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) * See LICENSE for the license information * -------------------------------------------------------------------------- */ /** * @file testGeneralSFMFactorB.cpp * @author Frank Dellaert * @brief test general SFM class, with nonlinear optimization and BAL files */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace std; using namespace gtsam; typedef GeneralSFMFactor, Point3> sfmFactor; using symbol_shorthand::P; /* ************************************************************************* */ TEST(PinholeCamera, BAL) { string filename = findExampleDataFile("dubrovnik-3-7-pre"); SfmData db = SfmData::FromBalFile(filename); SharedNoiseModel unit2 = noiseModel::Unit::Create(2); NonlinearFactorGraph graph; for (size_t j = 0; j < db.numberTracks(); j++) { for (const SfmMeasurement& m: db.tracks[j].measurements) graph.emplace_shared(m.second, unit2, m.first, P(j)); } Values initial = initialCamerasAndPointsEstimate(db); LevenbergMarquardtOptimizer lm(graph, initial); Values actual = lm.optimize(); double actualError = graph.error(actual); EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */