| 
									
										
										
										
											2015-06-08 11:25:35 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * 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 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-02-01 01:29:13 +08:00
										 |  |  | #include <gtsam/sfm/SfmData.h>
 | 
					
						
							| 
									
										
										
										
											2015-06-08 11:25:35 +08:00
										 |  |  | #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 <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"); | 
					
						
							| 
									
										
										
										
											2022-02-01 01:29:13 +08:00
										 |  |  |   SfmData db = SfmData::FromBalFile(filename); | 
					
						
							| 
									
										
										
										
											2015-06-08 11:25:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   SharedNoiseModel unit2 = noiseModel::Unit::Create(2); | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-02-01 01:46:42 +08:00
										 |  |  |   for (size_t j = 0; j < db.numberTracks(); j++) { | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |     for (const SfmMeasurement& m: db.tracks[j].measurements) | 
					
						
							| 
									
										
										
										
											2016-10-01 23:17:41 +08:00
										 |  |  |       graph.emplace_shared<sfmFactor>(m.second, unit2, m.first, P(j)); | 
					
						
							| 
									
										
										
										
											2015-06-08 11:25:35 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values initial = initialCamerasAndPointsEstimate(db); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   LevenbergMarquardtOptimizer lm(graph, initial); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values actual = lm.optimize(); | 
					
						
							|  |  |  |   double actualError = graph.error(actual); | 
					
						
							| 
									
										
										
										
											2015-07-06 03:18:34 +08:00
										 |  |  |   EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); | 
					
						
							| 
									
										
										
										
											2015-06-08 11:25:35 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  |   TestResult tr; | 
					
						
							|  |  |  |   return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |