Moved test to right place (geometry tests should not be relying on optimization code, and this was a test of the factor, not pinholecamera)
parent
2d98056497
commit
1ae0f256a1
|
@ -21,10 +21,6 @@
|
|||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/slam/dataset.h>
|
||||
#include <gtsam/slam/GeneralSFMFactor.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
|
@ -325,34 +321,6 @@ TEST( PinholeCamera, range3) {
|
|||
EXPECT(assert_equal(Hexpected2, D2, 1e-7));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
typedef GeneralSFMFactor<Camera2, Point3> sfmFactor;
|
||||
using symbol_shorthand::P;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( PinholeCamera, BAL) {
|
||||
string filename = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data db;
|
||||
bool success = readBAL(filename, db);
|
||||
if (!success) throw runtime_error("Could not access file!");
|
||||
|
||||
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)));
|
||||
}
|
||||
|
||||
Values initial = initialCamerasAndPointsEstimate(db);
|
||||
|
||||
LevenbergMarquardtOptimizer lm(graph, initial);
|
||||
|
||||
Values actual = lm.optimize();
|
||||
double actualError = graph.error(actual);
|
||||
EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-7);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -0,0 +1,72 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 <gtsam/slam/dataset.h>
|
||||
#include <gtsam/slam/GeneralSFMFactor.h>
|
||||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
|
||||
#include <CppUnitLite/Failure.h>
|
||||
#include <CppUnitLite/Test.h>
|
||||
#include <CppUnitLite/TestRegistry.h>
|
||||
#include <CppUnitLite/TestResult.h>
|
||||
#include <boost/foreach.hpp>
|
||||
#include <stddef.h>
|
||||
#include <stdexcept>
|
||||
#include <string>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
typedef GeneralSFMFactor<PinholeCamera<Cal3Bundler>, Point3> sfmFactor;
|
||||
using symbol_shorthand::P;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(PinholeCamera, BAL) {
|
||||
string filename = findExampleDataFile("dubrovnik-3-7-pre");
|
||||
SfM_data db;
|
||||
bool success = readBAL(filename, db);
|
||||
if (!success) throw runtime_error("Could not access file!");
|
||||
|
||||
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)));
|
||||
}
|
||||
|
||||
Values initial = initialCamerasAndPointsEstimate(db);
|
||||
|
||||
LevenbergMarquardtOptimizer lm(graph, initial);
|
||||
|
||||
Values actual = lm.optimize();
|
||||
double actualError = graph.error(actual);
|
||||
EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-7);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
TestResult tr;
|
||||
return TestRegistry::runAllTests(tr);
|
||||
}
|
||||
/* ************************************************************************* */
|
Loading…
Reference in New Issue