2012-06-04 16:31:26 +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
* - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - */
/**
2013-10-18 13:31:55 +08:00
* @ file SFMExample . cpp
* @ brief A structure - from - motion problem on a simulated dataset
2012-06-04 16:31:26 +08:00
* @ author Duy - Nguyen Ta
*/
2012-07-22 12:52:01 +08:00
/**
* A structure - from - motion example with landmarks
* - The landmarks form a 10 meter cube
* - The robot rotates around the landmarks , always facing towards the cube
*/
2013-08-30 12:23:45 +08:00
// For loading the data
2013-10-18 13:31:55 +08:00
# include "SFMdata.h"
2013-08-30 12:23:45 +08:00
2012-07-22 12:52:01 +08:00
// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
# include <gtsam/geometry/Point2.h>
// Each variable in the system (poses and landmarks) must be identified with a unique key.
// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
// Here we will use Symbols
2013-08-19 23:32:16 +08:00
# include <gtsam/inference/Symbol.h>
2012-07-22 12:52:01 +08:00
// In GTSAM, measurement functions are represented as 'factors'. Several common factors
// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
// Here we will use Projection factors to model the camera's landmark observations.
// Also, we will initialize the robot at some location using a Prior factor.
# include <gtsam/slam/PriorFactor.h>
# include <gtsam/slam/ProjectionFactor.h>
// When the factors are created, we will add them to a Factor Graph. As the factors we are using
// are nonlinear factors, we will need a Nonlinear Factor Graph.
# include <gtsam/nonlinear/NonlinearFactorGraph.h>
// Finally, once all of the factors have been added to our factor graph, we will want to
// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
// GTSAM includes several nonlinear optimizers to perform this step. Here we will use a
// trust-region method known as Powell's Degleg
# include <gtsam/nonlinear/DoglegOptimizer.h>
// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
// nonlinear functions around an initial linearization point, then solve the linear system
// to update the linearization point. This happens repeatedly until the solver converges
// to a consistent set of variable values. This requires us to specify an initial guess
// for each variable, held in a Values container.
# include <gtsam/nonlinear/Values.h>
# include <vector>
2012-06-04 16:31:26 +08:00
using namespace std ;
using namespace gtsam ;
/* ************************************************************************* */
int main ( int argc , char * argv [ ] ) {
2012-07-22 12:52:01 +08:00
// Define the camera calibration parameters
Cal3_S2 : : shared_ptr K ( new Cal3_S2 ( 50.0 , 50.0 , 0.0 , 50.0 , 50.0 ) ) ;
// Define the camera observation noise model
noiseModel : : Isotropic : : shared_ptr measurementNoise = noiseModel : : Isotropic : : Sigma ( 2 , 1.0 ) ; // one pixel in u and v
2012-06-04 16:31:26 +08:00
2012-07-22 12:52:01 +08:00
// Create the set of ground-truth landmarks
2013-08-31 00:53:21 +08:00
vector < Point3 > points = createPoints ( ) ;
2012-06-04 16:31:26 +08:00
2012-07-22 12:52:01 +08:00
// Create the set of ground-truth poses
2013-08-31 00:53:21 +08:00
vector < Pose3 > poses = createPoses ( ) ;
2012-07-22 12:52:01 +08:00
// Create a factor graph
NonlinearFactorGraph graph ;
// Add a prior on pose x1. This indirectly specifies where the origin is.
2014-11-23 08:35:27 +08:00
noiseModel : : Diagonal : : shared_ptr poseNoise = noiseModel : : Diagonal : : Sigmas ( ( Vector ( 6 ) < < Vector3 : : Constant ( 0.3 ) , Vector3 : : Constant ( 0.1 ) ) . finished ( ) ) ; // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
2013-08-17 01:13:45 +08:00
graph . push_back ( PriorFactor < Pose3 > ( Symbol ( ' x ' , 0 ) , poses [ 0 ] , poseNoise ) ) ; // add directly to graph
2012-07-22 12:52:01 +08:00
// Simulated measurements from each camera pose, adding them to the factor graph
for ( size_t i = 0 ; i < poses . size ( ) ; + + i ) {
2014-10-02 17:44:16 +08:00
SimpleCamera camera ( poses [ i ] , * K ) ;
2012-07-22 12:52:01 +08:00
for ( size_t j = 0 ; j < points . size ( ) ; + + j ) {
Point2 measurement = camera . project ( points [ j ] ) ;
2013-08-17 01:13:45 +08:00
graph . push_back ( GenericProjectionFactor < Pose3 , Point3 , Cal3_S2 > ( measurement , measurementNoise , Symbol ( ' x ' , i ) , Symbol ( ' l ' , j ) , K ) ) ;
2012-07-22 12:52:01 +08:00
}
}
// Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained
// Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance
// between the first camera and the first landmark. All other landmark positions are interpreted using this scale.
noiseModel : : Isotropic : : shared_ptr pointNoise = noiseModel : : Isotropic : : Sigma ( 3 , 0.1 ) ;
2013-08-17 01:13:45 +08:00
graph . push_back ( PriorFactor < Point3 > ( Symbol ( ' l ' , 0 ) , points [ 0 ] , pointNoise ) ) ; // add directly to graph
2012-07-22 12:52:01 +08:00
graph . print ( " Factor Graph: \n " ) ;
2013-08-31 00:53:21 +08:00
// Create the data structure to hold the initial estimate to the solution
2012-07-22 12:52:01 +08:00
// Intentionally initialize the variables off from the ground truth
Values initialEstimate ;
for ( size_t i = 0 ; i < poses . size ( ) ; + + i )
initialEstimate . insert ( Symbol ( ' x ' , i ) , poses [ i ] . compose ( Pose3 ( Rot3 : : rodriguez ( - 0.1 , 0.2 , 0.25 ) , Point3 ( 0.05 , - 0.10 , 0.20 ) ) ) ) ;
for ( size_t j = 0 ; j < points . size ( ) ; + + j )
initialEstimate . insert ( Symbol ( ' l ' , j ) , points [ j ] . compose ( Point3 ( - 0.25 , 0.20 , 0.15 ) ) ) ;
initialEstimate . print ( " Initial Estimates: \n " ) ;
/* Optimize the graph and print results */
Values result = DoglegOptimizer ( graph , initialEstimate ) . optimize ( ) ;
result . print ( " Final results: \n " ) ;
2014-10-02 17:21:24 +08:00
cout < < " initial error = " < < graph . error ( initialEstimate ) < < endl ;
cout < < " final error = " < < graph . error ( result ) < < endl ;
2012-06-04 16:31:26 +08:00
return 0 ;
}
/* ************************************************************************* */