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/sfm/SfmData.h>
19 #include <gtsam/slam/dataset.h>
21 #include <gtsam/geometry/Point3.h>
25 #include <gtsam/nonlinear/Values.h>
26 #include <gtsam/inference/Symbol.h>
28 
29 #include <CppUnitLite/Failure.h>
30 #include <CppUnitLite/Test.h>
32 #include <CppUnitLite/TestResult.h>
33 #include <stddef.h>
34 #include <stdexcept>
35 #include <string>
36 
37 using namespace std;
38 using namespace gtsam;
39 
42 
43 /* ************************************************************************* */
45  string filename = findExampleDataFile("dubrovnik-3-7-pre");
46  SfmData db = SfmData::FromBalFile(filename);
47 
48  SharedNoiseModel unit2 = noiseModel::Unit::Create(2);
50 
51  for (size_t j = 0; j < db.numberTracks(); j++) {
52  for (const SfmMeasurement& m: db.tracks[j].measurements)
53  graph.emplace_shared<sfmFactor>(m.second, unit2, m.first, P(j));
54  }
55 
57 
58  LevenbergMarquardtOptimizer lm(graph, initial);
59 
60  Values actual = lm.optimize();
61  double actualError = graph.error(actual);
62  EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5);
63 }
64 
65 /* ************************************************************************* */
66 int main() {
67  TestResult tr;
68  return TestRegistry::runAllTests(tr);
69 }
70 /* ************************************************************************* */
Matrix3f m
virtual const Values & optimize()
SfmData stores a bunch of SfmTracks.
Definition: SfmData.h:39
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: SfmData.cpp:430
Definition: BFloat16.h:88
int main()
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: SfmData.h:42
GeneralSFMFactor< PinholeCamera< Cal3Bundler >, Point3 > sfmFactor
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
Definition: SfmTrack.h:32
TEST(PinholeCamera, BAL)
Data structure for dealing with Structure from Motion data.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double error(const Values &values) const
traits
Definition: chartTesting.h:28
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
3D Point
size_t numberTracks() const
The number of reconstructed 3D points.
Definition: SfmData.h:74
Vector3 Point3
Definition: Point3.h:38
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:741


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:17