| 1 | /* ---------------------------------------------------------------------------- |
| 2 | |
| 3 | * GTSAM Copyright 2010, Georgia Tech Research Corporation, |
| 4 | * Atlanta, Georgia 30332-0415 |
| 5 | * All Rights Reserved |
| 6 | * Authors: Frank Dellaert, et al. (see THANKS for the full author list) |
| 7 | |
| 8 | * See LICENSE for the license information |
| 9 | |
| 10 | * -------------------------------------------------------------------------- */ |
| 11 | |
| 12 | /** |
| 13 | * @file timeSFMBALsmart.cpp |
| 14 | * @brief time SFM with BAL file, SmartProjectionFactor |
| 15 | * @author Frank Dellaert |
| 16 | * @date Feb 26, 2016 |
| 17 | */ |
| 18 | |
| 19 | #include "timeSFMBAL.h" |
| 20 | |
| 21 | #include <gtsam/slam/SmartProjectionFactor.h> |
| 22 | #include <gtsam/geometry/Cal3Bundler.h> |
| 23 | #include <gtsam/geometry/PinholeCamera.h> |
| 24 | #include <gtsam/geometry/Point3.h> |
| 25 | |
| 26 | using namespace std; |
| 27 | using namespace gtsam; |
| 28 | |
| 29 | typedef PinholeCamera<Cal3Bundler> Camera; |
| 30 | typedef SmartProjectionFactor<Camera> SfmFactor; |
| 31 | |
| 32 | int main(int argc, char* argv[]) { |
| 33 | // parse options and read BAL file |
| 34 | SfmData db = preamble(argc, argv); |
| 35 | |
| 36 | // Add smart factors to graph |
| 37 | NonlinearFactorGraph graph; |
| 38 | for (size_t j = 0; j < db.numberTracks(); j++) { |
| 39 | auto smartFactor = std::make_shared<SfmFactor>(args&: gNoiseModel); |
| 40 | for (const SfmMeasurement& m : db.tracks[j].measurements) { |
| 41 | size_t i = m.first; |
| 42 | Point2 z = m.second; |
| 43 | smartFactor->add(measured: z, key: C(j: i)); |
| 44 | } |
| 45 | graph.push_back(factor: smartFactor); |
| 46 | } |
| 47 | |
| 48 | Values initial; |
| 49 | size_t i = 0; |
| 50 | gUseSchur = false; |
| 51 | for (const SfmCamera& camera : db.cameras) |
| 52 | initial.insert(j: C(j: i++), val: camera); |
| 53 | |
| 54 | return optimize(db, graph, initial); |
| 55 | } |
| 56 | |