testGeneralSFMFactorB.cpp
Go to the documentation of this file.
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 
18 #include <gtsam/slam/dataset.h>
20 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/inference/Symbol.h>
27 
28 #include <CppUnitLite/Failure.h>
29 #include <CppUnitLite/Test.h>
31 #include <CppUnitLite/TestResult.h>
32 #include <stddef.h>
33 #include <stdexcept>
34 #include <string>
35 
36 using namespace std;
37 using namespace gtsam;
38 
41 
42 /* ************************************************************************* */
44  string filename = findExampleDataFile("dubrovnik-3-7-pre");
45  SfmData db;
46  bool success = readBAL(filename, db);
47  if (!success) throw runtime_error("Could not access file!");
48 
49  SharedNoiseModel unit2 = noiseModel::Unit::Create(2);
51 
52  for (size_t j = 0; j < db.number_tracks(); j++) {
53  for (const SfmMeasurement& m: db.tracks[j].measurements)
54  graph.emplace_shared<sfmFactor>(m.second, unit2, m.first, P(j));
55  }
56 
58 
59  LevenbergMarquardtOptimizer lm(graph, initial);
60 
61  Values actual = lm.optimize();
62  double actualError = graph.error(actual);
63  EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5);
64 }
65 
66 /* ************************************************************************* */
67 int main() {
68  TestResult tr;
69  return TestRegistry::runAllTests(tr);
70 }
71 /* ************************************************************************* */
Matrix3f m
virtual const Values & optimize()
Define the structure for SfM data.
Definition: dataset.h:326
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Definition: Half.h:150
int main()
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: dataset.h:328
GeneralSFMFactor< PinholeCamera< Cal3Bundler >, Point3 > sfmFactor
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
Definition: dataset.h:214
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:333
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
TEST(PinholeCamera, BAL)
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))
traits
Definition: chartTesting.h:28
3D Point
Vector3 Point3
Definition: Point3.h:35
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: dataset.cpp:1284
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
std::ptrdiff_t j
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
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...
Definition: dataset.cpp:1073


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:03