2010-10-14 12:54:38 +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
* - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - */
2010-08-27 05:21:15 +08:00
/**
* @ file PlanarSLAMExample . cpp
2012-07-22 12:36:40 +08:00
* @ brief Simple robotics example using odometry measurements and bearing - range ( laser ) measurements
2010-08-27 05:21:15 +08:00
* @ author Alex Cunningham
*/
/**
2012-07-22 12:36:40 +08:00
* A simple 2 D planar slam example with landmarks
2012-05-21 04:31:33 +08:00
* - The robot and landmarks are on a 2 meter grid
* - Robot poses are facing along the X axis ( horizontal , to the right in 2 D )
* - The robot moves 2 meters each step
* - We have full odometry between poses
2010-08-27 05:21:15 +08:00
* - We have bearing and range information for measurements
* - Landmarks are 2 meters away from the robot trajectory
*/
2012-07-22 12:36:40 +08:00
// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
// the robot positions and Point2 variables (x, y) to represent the landmark coordinates.
# include <gtsam/geometry/Pose2.h>
# 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:36:40 +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 a RangeBearing factor for the range-bearing measurements to identified
// landmarks, and Between factors for the relative motion described by odometry measurements.
// Also, we will initialize the robot at the origin using a Prior factor.
# include <gtsam/slam/PriorFactor.h>
# include <gtsam/slam/BetweenFactor.h>
# include <gtsam/slam/BearingRangeFactor.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 the
// common Levenberg-Marquardt solver
# include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
// Once the optimized values have been calculated, we can also calculate the marginal covariance
// of desired variables
# include <gtsam/nonlinear/Marginals.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>
using namespace std ;
using namespace gtsam ;
2010-08-27 05:21:15 +08:00
int main ( int argc , char * * argv ) {
2012-07-22 12:36:40 +08:00
// Create a factor graph
2012-10-02 22:40:07 +08:00
NonlinearFactorGraph graph ;
// Create the keys we need for this simple example
static Symbol x1 ( ' x ' , 1 ) , x2 ( ' x ' , 2 ) , x3 ( ' x ' , 3 ) ;
static Symbol l1 ( ' l ' , 1 ) , l2 ( ' l ' , 2 ) ;
// Add a prior on pose x1 at the origin. A prior factor consists of a mean and a noise model (covariance matrix)
Pose2 prior ( 0.0 , 0.0 , 0.0 ) ; // prior mean is at origin
2014-11-23 08:35:27 +08:00
noiseModel : : Diagonal : : shared_ptr priorNoise = noiseModel : : Diagonal : : Sigmas ( ( Vector ( 3 ) < < 0.3 , 0.3 , 0.1 ) . finished ( ) ) ; // 30cm std on x,y, 0.1 rad on theta
2014-09-25 20:30:41 +08:00
graph . add ( PriorFactor < Pose2 > ( x1 , prior , priorNoise ) ) ; // add directly to graph
2012-10-02 22:40:07 +08:00
// Add two odometry factors
Pose2 odometry ( 2.0 , 0.0 , 0.0 ) ; // create a measurement for both factors (the same in this case)
2014-11-23 08:35:27 +08:00
noiseModel : : Diagonal : : shared_ptr odometryNoise = noiseModel : : Diagonal : : Sigmas ( ( Vector ( 3 ) < < 0.2 , 0.2 , 0.1 ) . finished ( ) ) ; // 20cm std on x,y, 0.1 rad on theta
2014-09-25 20:30:41 +08:00
graph . add ( BetweenFactor < Pose2 > ( x1 , x2 , odometry , odometryNoise ) ) ;
graph . add ( BetweenFactor < Pose2 > ( x2 , x3 , odometry , odometryNoise ) ) ;
2012-10-02 22:40:07 +08:00
// Add Range-Bearing measurements to two different landmarks
// create a noise model for the landmark measurements
2014-11-23 08:35:27 +08:00
noiseModel : : Diagonal : : shared_ptr measurementNoise = noiseModel : : Diagonal : : Sigmas ( ( Vector ( 2 ) < < 0.1 , 0.2 ) . finished ( ) ) ; // 0.1 rad std on bearing, 20cm on range
2012-10-02 22:40:07 +08:00
// create the measurement values - indices are (pose id, landmark id)
Rot2 bearing11 = Rot2 : : fromDegrees ( 45 ) ,
bearing21 = Rot2 : : fromDegrees ( 90 ) ,
bearing32 = Rot2 : : fromDegrees ( 90 ) ;
double range11 = std : : sqrt ( 4.0 + 4.0 ) ,
range21 = 2.0 ,
range32 = 2.0 ;
// Add Bearing-Range factors
2014-09-25 20:30:41 +08:00
graph . add ( BearingRangeFactor < Pose2 , Point2 > ( x1 , l1 , bearing11 , range11 , measurementNoise ) ) ;
graph . add ( BearingRangeFactor < Pose2 , Point2 > ( x2 , l1 , bearing21 , range21 , measurementNoise ) ) ;
graph . add ( BearingRangeFactor < Pose2 , Point2 > ( x3 , l2 , bearing32 , range32 , measurementNoise ) ) ;
2012-10-02 22:40:07 +08:00
// Print
graph . print ( " Factor Graph: \n " ) ;
// Create (deliberately inaccurate) initial estimate
Values initialEstimate ;
initialEstimate . insert ( x1 , Pose2 ( 0.5 , 0.0 , 0.2 ) ) ;
initialEstimate . insert ( x2 , Pose2 ( 2.3 , 0.1 , - 0.2 ) ) ;
initialEstimate . insert ( x3 , Pose2 ( 4.1 , 0.1 , 0.1 ) ) ;
initialEstimate . insert ( l1 , Point2 ( 1.8 , 2.1 ) ) ;
initialEstimate . insert ( l2 , Point2 ( 4.1 , 1.8 ) ) ;
// Print
initialEstimate . print ( " Initial Estimate: \n " ) ;
// Optimize using Levenberg-Marquardt optimization. The optimizer
// accepts an optional set of configuration parameters, controlling
// things like convergence criteria, the type of linear system solver
// to use, and the amount of information displayed during optimization.
// Here we will use the default set of parameters. See the
// documentation for the full set of parameters.
LevenbergMarquardtOptimizer optimizer ( graph , initialEstimate ) ;
Values result = optimizer . optimize ( ) ;
result . print ( " Final Result: \n " ) ;
2012-07-22 12:36:40 +08:00
// Calculate and print marginal covariances for all variables
2012-10-02 22:40:07 +08:00
Marginals marginals ( graph , result ) ;
2012-07-22 12:36:40 +08:00
print ( marginals . marginalCovariance ( x1 ) , " x1 covariance " ) ;
print ( marginals . marginalCovariance ( x2 ) , " x2 covariance " ) ;
print ( marginals . marginalCovariance ( x3 ) , " x3 covariance " ) ;
print ( marginals . marginalCovariance ( l1 ) , " l1 covariance " ) ;
print ( marginals . marginalCovariance ( l2 ) , " l2 covariance " ) ;
2010-08-27 05:21:15 +08:00
2012-10-02 22:40:07 +08:00
return 0 ;
2010-08-27 05:21:15 +08:00
}