diff --git a/timing/timeSFMBAL.cpp b/timing/timeSFMBAL.cpp index 49bf23024..98fa3d249 100644 --- a/timing/timeSFMBAL.cpp +++ b/timing/timeSFMBAL.cpp @@ -16,20 +16,20 @@ * @date June 6, 2015 */ -#include -#include +#include +#include #include #include #include -#include -#include -#include #include #include -#include #include -#include -#include +#include +#include +#include +#include + +#include #include #include #include @@ -39,18 +39,19 @@ using namespace gtsam; //#define TERNARY -int main(int argc, char *argv[]) { +int main(int argc, char* argv[]) { typedef GeneralSFMFactor, Point3> sfmFactor; using symbol_shorthand::P; + // Load BAL file (default is tiny) string defaultFilename = findExampleDataFile("dubrovnik-3-7-pre"); SfM_data db; - bool success = readBAL(argc>1 ? argv[1] : defaultFilename, db); + bool success = readBAL(argc > 1 ? argv[1] : defaultFilename, db); if (!success) throw runtime_error("Could not access file!"); + // Build graph SharedNoiseModel unit2 = noiseModel::Unit::Create(2); NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { BOOST_FOREACH (const SfM_Measurement& m, db.tracks[j].measurements) graph.push_back(sfmFactor(m.second, unit2, m.first, P(j))); @@ -58,9 +59,18 @@ int main(int argc, char *argv[]) { Values initial = initialCamerasAndPointsEstimate(db); - LevenbergMarquardtOptimizer lm(graph, initial); + // Create Schur-complement ordering + vector pointKeys; + for (size_t j = 0; j < db.number_tracks(); j++) pointKeys.push_back(P(j)); + Ordering schurOrdering = Ordering::colamdConstrainedFirst(graph, pointKeys, true); + // Optimize + LevenbergMarquardtParams params; + params.setOrdering(schurOrdering); + LevenbergMarquardtOptimizer lm(graph, initial, params); Values actual = lm.optimize(); + + tictoc_finishedIteration_(); tictoc_print_(); return 0;