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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file		CameraResectioning.cpp
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief   An example of gtsam for solving the camera resectioning problem
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author	Duy-Nguyen Ta
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-23 03:57:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * @date	  Aug 23, 2011
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-23 03:57:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 12:58:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/Symbol.h>
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Pose3.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Cal3_S2.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/SimpleCamera.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactor.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactorGraph.h>
							 | 
						
					
						
							
								
									
										
										
										
											2011-12-21 07:25:43 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearOptimization.h>
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Unary factor for the pose.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								class ResectioningFactor: public NoiseModelFactor1<Pose3> {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef NoiseModelFactor1<Pose3> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  shared_ptrK K_; // camera's intrinsic parameters
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point3 P_; // 3D point on the calibration rig
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point2 p_; // 2D measurement of the 3D point
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								public:
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  ResectioningFactor(const SharedNoiseModel& model, const Symbol& key,
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      const shared_ptrK& calib, const Point2& p, const Point3& P) :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Base(model, key), K_(calib), P_(P), p_(p) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 06:10:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  virtual ~ResectioningFactor() {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  virtual Vector evaluateError(const Pose3& X, boost::optional<Matrix&> H = boost::none) const {
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    SimpleCamera camera(*K_, X);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Point2 reprojectionError(camera.project(P_, H) - p_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return reprojectionError.vector();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/*******************************************************************************/
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Camera: f = 1.0, Image: 100x100, center: 50.0, 50.0
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * 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)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								int main(int argc, char* argv[]) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* read camera intrinsic parameters */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  shared_ptrK calib(new Cal3_S2(1.0, 1.0, 0, 50.0, 50.0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* create keys for variables */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // we have only 1 variable to solve: the camera pose
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Symbol X('x',1);
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* 1. create graph */
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 06:10:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph graph;
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* 2. add factors to the graph */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // add measurement factors
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:17:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedDiagonal measurementNoise = sharedSigmas(Vector_(2, 0.5, 0.5));
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  boost::shared_ptr<ResectioningFactor> factor;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  factor = boost::shared_ptr<ResectioningFactor>(new ResectioningFactor(
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:17:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      measurementNoise, X, calib, Point2(55.0, 45.0), Point3(10.0, 10.0, 0.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  graph.push_back(factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  factor = boost::shared_ptr<ResectioningFactor>(new ResectioningFactor(
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:17:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      measurementNoise, X, calib, Point2(45.0, 45.0), Point3(-10.0, 10.0, 0.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  graph.push_back(factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  factor = boost::shared_ptr<ResectioningFactor>(new ResectioningFactor(
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:17:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      measurementNoise, X, calib, Point2(45.0, 55.0), Point3(-10.0, -10.0, 0.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  graph.push_back(factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  factor = boost::shared_ptr<ResectioningFactor>(new ResectioningFactor(
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:17:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      measurementNoise, X, calib, Point2(55.0, 55.0), Point3(10.0, -10.0, 0.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  graph.push_back(factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* 3. Create an initial estimate for the camera pose */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values initial;
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  initial.insert(X, Pose3(Rot3(1.,0.,0.,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								                               0.,-1.,0.,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								                               0.,0.,-1.), Point3(0.,0.,2.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /* 4. Optimize the graph using Levenberg-Marquardt*/
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values result = optimize<NonlinearFactorGraph> (graph, initial);
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-24 06:10:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  result.print("Final result: ");
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return 0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 |