| 
									
										
										
										
											2015-01-22 07:06:29 +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    SFMExampleExpressions_bal.cpp | 
					
						
							|  |  |  |  * @brief   A structure-from-motion example done with Expressions | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  * @date    January 2015 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * This is the Expression version of SFMExample | 
					
						
							|  |  |  |  * See detailed description of headers there, this focuses on explaining the AD part | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // The two new headers that allow using our Automatic Differentiation Expression framework
 | 
					
						
							|  |  |  | #include <gtsam/slam/expressions.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/ExpressionFactorGraph.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Header order is close to far
 | 
					
						
							| 
									
										
										
										
											2022-02-01 01:29:13 +08:00
										 |  |  | #include <gtsam/sfm/SfmData.h>  // for loading BAL datasets !
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2022-02-17 04:08:28 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/format.hpp>
 | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace noiseModel; | 
					
						
							|  |  |  | using symbol_shorthand::C; | 
					
						
							|  |  |  | using symbol_shorthand::P; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  | // An SfmCamera is defined in datase.h as a camera with unknown Cal3Bundler calibration
 | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | // and has a total of 9 free parameters
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   // Find default file, but if an argument is given, try loading a file
 | 
					
						
							|  |  |  |   string filename = findExampleDataFile("dubrovnik-3-7-pre"); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   if (argc > 1) filename = string(argv[1]); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Load the SfM data from file
 | 
					
						
							| 
									
										
										
										
											2022-02-01 01:29:13 +08:00
										 |  |  |   SfmData mydata = SfmData::FromBalFile(filename); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   cout << boost::format("read %1% tracks on %2% cameras\n") % | 
					
						
							| 
									
										
										
										
											2022-02-01 01:46:42 +08:00
										 |  |  |               mydata.numberTracks() % mydata.numberCameras(); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create a factor graph
 | 
					
						
							|  |  |  |   ExpressionFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Here we don't use a PriorFactor but directly the ExpressionFactor class
 | 
					
						
							|  |  |  |   // First, we create an expression to the pose from the first camera
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |   Expression<SfmCamera> camera0_(C(0)); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |   // Then, to get its pose:
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |   Pose3_ pose0_(&SfmCamera::getPose, camera0_); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |   // Finally, we say it should be equal to first guess
 | 
					
						
							|  |  |  |   graph.addExpressionFactor(pose0_, mydata.cameras[0].pose(), | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |                             noiseModel::Isotropic::Sigma(6, 0.1)); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // similarly, we create a prior on the first point
 | 
					
						
							|  |  |  |   Point3_ point0_(P(0)); | 
					
						
							|  |  |  |   graph.addExpressionFactor(point0_, mydata.tracks[0].p, | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |                             noiseModel::Isotropic::Sigma(3, 0.1)); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // We share *one* noiseModel between all projection factors
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto noise = noiseModel::Isotropic::Sigma(2, 1.0);  // one pixel in u and v
 | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // Simulated measurements from each camera pose, adding them to the factor
 | 
					
						
							|  |  |  |   // graph
 | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |   size_t j = 0; | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   for (const SfmTrack& track : mydata.tracks) { | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |     // Leaf expression for j^th point
 | 
					
						
							|  |  |  |     Point3_ point_('p', j); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |     for (const SfmMeasurement& m : track.measurements) { | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |       size_t i = m.first; | 
					
						
							|  |  |  |       Point2 uv = m.second; | 
					
						
							|  |  |  |       // Leaf expression for i^th camera
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |       Expression<SfmCamera> camera_(C(i)); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |       // Below an expression for the prediction of the measurement:
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |       Point2_ predict_ = project2<SfmCamera>(camera_, point_); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  |       // Again, here we use an ExpressionFactor
 | 
					
						
							|  |  |  |       graph.addExpressionFactor(predict_, uv, noise); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     j += 1; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create initial estimate
 | 
					
						
							|  |  |  |   Values initial; | 
					
						
							|  |  |  |   size_t i = 0; | 
					
						
							|  |  |  |   j = 0; | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera); | 
					
						
							|  |  |  |   for (const SfmTrack& track : mydata.tracks) initial.insert(P(j++), track.p); | 
					
						
							| 
									
										
										
										
											2015-01-22 07:06:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* Optimize the graph and print results */ | 
					
						
							|  |  |  |   Values result; | 
					
						
							|  |  |  |   try { | 
					
						
							|  |  |  |     LevenbergMarquardtParams params; | 
					
						
							|  |  |  |     params.setVerbosity("ERROR"); | 
					
						
							|  |  |  |     LevenbergMarquardtOptimizer lm(graph, initial, params); | 
					
						
							|  |  |  |     result = lm.optimize(); | 
					
						
							|  |  |  |   } catch (exception& e) { | 
					
						
							|  |  |  |     cout << e.what(); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   cout << "final error: " << graph.error(result) << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |