| 
									
										
										
										
											2011-10-23 03:57:36 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |  * @file    CameraResectioning.cpp | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  |  * @brief   An example of gtsam for solving the camera resectioning problem | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |  * @author  Duy-Nguyen Ta | 
					
						
							|  |  |  |  * @date    Aug 23, 2011 | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2011-10-23 03:57:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2012-03-25 03:53:17 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-04 03:50:04 +08:00
										 |  |  | #include <gtsam/geometry/SimpleCamera.h>
 | 
					
						
							|  |  |  | #include <boost/make_shared.hpp>
 | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | using namespace gtsam::noiseModel; | 
					
						
							| 
									
										
										
										
											2012-06-04 03:50:04 +08:00
										 |  |  | using symbol_shorthand::X; | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-06-04 03:50:04 +08:00
										 |  |  |  * Unary factor on the unknown pose, resulting from meauring the projection of | 
					
						
							|  |  |  |  * a known 3D point in the image | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 |  |  | class ResectioningFactor: public NoiseModelFactor1<Pose3> { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   typedef NoiseModelFactor1<Pose3> Base; | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-05-09 03:21:00 +08:00
										 |  |  |   Cal3_S2::shared_ptr K_; ///< camera's intrinsic parameters
 | 
					
						
							|  |  |  |   Point3 P_;              ///< 3D point on the calibration rig
 | 
					
						
							|  |  |  |   Point2 p_;              ///< 2D measurement of the 3D point
 | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							| 
									
										
										
										
											2012-01-30 06:10:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /// Construct factor given known point P and its projection p
 | 
					
						
							|  |  |  |   ResectioningFactor(const SharedNoiseModel& model, const Key& key, | 
					
						
							| 
									
										
										
										
											2013-05-09 03:21:00 +08:00
										 |  |  |       const Cal3_S2::shared_ptr& calib, const Point2& p, const Point3& P) : | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       Base(model, key), K_(calib), P_(P), p_(p) { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// evaluate the error
 | 
					
						
							|  |  |  |   virtual Vector evaluateError(const Pose3& pose, boost::optional<Matrix&> H = | 
					
						
							|  |  |  |       boost::none) const { | 
					
						
							|  |  |  |     SimpleCamera camera(pose, *K_); | 
					
						
							| 
									
										
										
										
											2014-10-07 07:16:10 +08:00
										 |  |  |     Point2 reprojectionError(camera.project(P_, H, boost::none, boost::none) - p_); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     return reprojectionError.vector(); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-04 03:50:04 +08:00
										 |  |  | /*******************************************************************************
 | 
					
						
							|  |  |  |  * Camera: f = 1, Image: 100x100, center: 50, 50.0 | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  |  * Pose (ground truth): (Xw, -Yw, -Zw, [0,0,2.0]') | 
					
						
							|  |  |  |  * Known landmarks: | 
					
						
							|  |  |  |  *    3D Points: (10,10,0) (-10,10,0) (-10,-10,0) (10,-10,0) | 
					
						
							|  |  |  |  * Perfect measurements: | 
					
						
							|  |  |  |  *    2D Point:  (55,45)   (45,45)    (45,55)     (55,55) | 
					
						
							| 
									
										
										
										
											2012-06-04 03:50:04 +08:00
										 |  |  |  *******************************************************************************/ | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | int main(int argc, char* argv[]) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /* read camera intrinsic parameters */ | 
					
						
							| 
									
										
										
										
											2013-05-09 03:21:00 +08:00
										 |  |  |   Cal3_S2::shared_ptr calib(new Cal3_S2(1, 1, 0, 50, 50)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* 1. create graph */ | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* 2. add factors to the graph */ | 
					
						
							|  |  |  |   // add measurement factors
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   SharedDiagonal measurementNoise = Diagonal::Sigmas(Vector2(0.5, 0.5)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   boost::shared_ptr<ResectioningFactor> factor; | 
					
						
							|  |  |  |   graph.push_back( | 
					
						
							|  |  |  |       boost::make_shared<ResectioningFactor>(measurementNoise, X(1), calib, | 
					
						
							|  |  |  |           Point2(55, 45), Point3(10, 10, 0))); | 
					
						
							|  |  |  |   graph.push_back( | 
					
						
							|  |  |  |       boost::make_shared<ResectioningFactor>(measurementNoise, X(1), calib, | 
					
						
							|  |  |  |           Point2(45, 45), Point3(-10, 10, 0))); | 
					
						
							|  |  |  |   graph.push_back( | 
					
						
							|  |  |  |       boost::make_shared<ResectioningFactor>(measurementNoise, X(1), calib, | 
					
						
							|  |  |  |           Point2(45, 55), Point3(-10, -10, 0))); | 
					
						
							|  |  |  |   graph.push_back( | 
					
						
							|  |  |  |       boost::make_shared<ResectioningFactor>(measurementNoise, X(1), calib, | 
					
						
							|  |  |  |           Point2(55, 55), Point3(10, -10, 0))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* 3. Create an initial estimate for the camera pose */ | 
					
						
							|  |  |  |   Values initial; | 
					
						
							|  |  |  |   initial.insert(X(1), | 
					
						
							|  |  |  |       Pose3(Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1), Point3(0, 0, 2))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* 4. Optimize the graph using Levenberg-Marquardt*/ | 
					
						
							|  |  |  |   Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); | 
					
						
							|  |  |  |   result.print("Final result:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 |  |  | } |