Combined the two versions of Pose2SLAMExample into a single example without SLAM namespaces
parent
9e278b394a
commit
d259320aed
|
@ -11,55 +11,126 @@
|
|||
|
||||
/**
|
||||
* @file Pose2SLAMExample.cpp
|
||||
* @brief A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h
|
||||
* @brief A 2D Pose SLAM example
|
||||
* @date Oct 21, 2010
|
||||
* @author Yong Dian Jian
|
||||
*/
|
||||
|
||||
// pull in the Pose2 SLAM domain with all typedefs and helper functions defined
|
||||
#include <gtsam/slam/pose2SLAM.h>
|
||||
#include <cmath>
|
||||
/**
|
||||
* A simple 2D pose slam example
|
||||
* - The robot moves in a 2 meter square
|
||||
* - The robot moves 2 meters each step, turning 90 degrees after each step
|
||||
* - The robot initially faces along the X axis (horizontal, to the right in 2D)
|
||||
* - We have full odometry between pose
|
||||
* - We have a loop closure constraint when the robot returns to the first position
|
||||
*/
|
||||
|
||||
// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
|
||||
// the robot positions
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
// Each variable in the system (poses) 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 simple integer keys
|
||||
#include <gtsam/nonlinear/Key.h>
|
||||
|
||||
// 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 Between factors for the relative motion described by odometry measurements.
|
||||
// We will also use a Between Factor to encode the loop closure constraint
|
||||
// Also, we will initialize the robot at the origin using a Prior factor.
|
||||
#include <gtsam/slam/PriorFactor.h>
|
||||
#include <gtsam/slam/BetweenFactor.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
|
||||
// a Gauss-Newton solver
|
||||
#include <gtsam/nonlinear/GaussNewtonOptimizer.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;
|
||||
using namespace gtsam::noiseModel;
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
|
||||
// 1. Create graph container and add factors to it
|
||||
pose2SLAM::Graph graph;
|
||||
// 1. Create a factor graph container and add factors to it
|
||||
NonlinearFactorGraph graph;
|
||||
|
||||
// 2a. Add Gaussian prior
|
||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
||||
SharedDiagonal priorNoise = Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1));
|
||||
graph.addPosePrior(1, priorMean, priorNoise);
|
||||
// 2a. Add a prior on the first pose, setting it to the origin
|
||||
// A prior factor consists of a mean and a noise model (covariance matrix)
|
||||
Pose2 prior(0.0, 0.0, 0.0); // prior at origin
|
||||
noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1));
|
||||
graph.add(PriorFactor<Pose2>(1, prior, priorNoise));
|
||||
|
||||
// 2b. Add odometry factors
|
||||
SharedDiagonal odometryNoise = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
||||
graph.addRelativePose(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise);
|
||||
graph.addRelativePose(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
graph.addRelativePose(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
graph.addRelativePose(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
// For simplicity, we will use the same noise model for each odometry factor
|
||||
noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
||||
// Create odometry (Between) factors between consecutive poses
|
||||
graph.add(BetweenFactor<Pose2>(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
|
||||
graph.add(BetweenFactor<Pose2>(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
|
||||
graph.add(BetweenFactor<Pose2>(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
|
||||
graph.add(BetweenFactor<Pose2>(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
|
||||
|
||||
// 2c. Add pose constraint
|
||||
SharedDiagonal model = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
||||
graph.addRelativePose(5, 2, Pose2(2.0, 0.0, M_PI_2), model);
|
||||
// 2c. Add the loop closure constraint
|
||||
// This factor encodes the fact that we have returned to the same pose. In real systems,
|
||||
// these constraints may be identified in many ways, such as appearance-based techniques
|
||||
// with camera images.
|
||||
// We will use another Between Factor to enforce this constraint, with the distance set to zero,
|
||||
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
||||
graph.add(BetweenFactor<Pose2>(5, 1, Pose2(0.0, 0.0, 0.0), model));
|
||||
graph.print("\nFactor Graph:\n"); // print
|
||||
|
||||
// print
|
||||
graph.print("\nFactor graph:\n");
|
||||
|
||||
// 3. Create the data structure to hold the initialEstimate estimate to the solution
|
||||
pose2SLAM::Values initialEstimate;
|
||||
initialEstimate.insertPose(1, Pose2(0.5, 0.0, 0.2));
|
||||
initialEstimate.insertPose(2, Pose2(2.3, 0.1, -0.2));
|
||||
initialEstimate.insertPose(3, Pose2(4.1, 0.1, M_PI_2));
|
||||
initialEstimate.insertPose(4, Pose2(4.0, 2.0, M_PI));
|
||||
initialEstimate.insertPose(5, Pose2(2.1, 2.1, -M_PI_2));
|
||||
initialEstimate.print("\nInitial estimate:\n");
|
||||
// For illustrative purposes, these have been deliberately set to incorrect values
|
||||
Values initialEstimate;
|
||||
initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
|
||||
initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1));
|
||||
initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8));
|
||||
initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2));
|
||||
initialEstimate.insert(5, Pose2(0.1,-0.7, 5.8));
|
||||
initialEstimate.print("\nInitial Estimate:\n"); // print
|
||||
|
||||
// 4. Single Step Optimization using Levenberg-Marquardt
|
||||
pose2SLAM::Values result = graph.optimize(initialEstimate);
|
||||
result.print("\nFinal result:\n");
|
||||
// 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
|
||||
// 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. We will set a few parameters as a demonstration.
|
||||
GaussNewtonParams parameters;
|
||||
// Stop iterating once the change in error between steps is less than this value
|
||||
parameters.relativeErrorTol = 1e-5;
|
||||
// Do not perform more than N iteration steps
|
||||
parameters.maxIterations = 100;
|
||||
// Create the optimizer ...
|
||||
GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters);
|
||||
// ... and optimize
|
||||
Values result = optimizer.optimize();
|
||||
result.print("Final Result:\n");
|
||||
|
||||
// 5. Calculate and print marginal covariances for all variables
|
||||
Marginals marginals(graph, result);
|
||||
cout << "Pose 1 covariance:\n" << marginals.marginalCovariance(1) << endl;
|
||||
cout << "Pose 2 covariance:\n" << marginals.marginalCovariance(2) << endl;
|
||||
cout << "Pose 3 covariance:\n" << marginals.marginalCovariance(3) << endl;
|
||||
cout << "Pose 4 covariance:\n" << marginals.marginalCovariance(4) << endl;
|
||||
cout << "Pose 5 covariance:\n" << marginals.marginalCovariance(5) << endl;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -1,82 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 Pose2SLAMExample_advanced.cpp
|
||||
* @brief Simple Pose2SLAM Example using
|
||||
* pre-built pose2SLAM domain
|
||||
* @author Chris Beall
|
||||
*/
|
||||
|
||||
// pull in the Pose2 SLAM domain with all typedefs and helper functions defined
|
||||
#include <gtsam/slam/pose2SLAM.h>
|
||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/nonlinear/Marginals.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::noiseModel;
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
/* 1. create graph container and add factors to it */
|
||||
pose2SLAM::Graph graph;
|
||||
|
||||
/* 2.a add prior */
|
||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
||||
SharedDiagonal priorNoise = Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
|
||||
graph.addPosePrior(1, priorMean, priorNoise); // add directly to graph
|
||||
|
||||
/* 2.b add odometry */
|
||||
SharedDiagonal odometryNoise = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
|
||||
Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
|
||||
graph.addRelativePose(1, 2, odometry, odometryNoise);
|
||||
graph.addRelativePose(2, 3, odometry, odometryNoise);
|
||||
graph.print("full graph");
|
||||
|
||||
/* 3. Create the data structure to hold the initial estimate to the solution
|
||||
* initialize to noisy points */
|
||||
pose2SLAM::Values initial;
|
||||
initial.insertPose(1, Pose2(0.5, 0.0, 0.2));
|
||||
initial.insertPose(2, Pose2(2.3, 0.1, -0.2));
|
||||
initial.insertPose(3, Pose2(4.1, 0.1, 0.1));
|
||||
initial.print("initial estimate");
|
||||
|
||||
/* 4.2.1 Alternatively, you can go through the process step by step
|
||||
* Choose an ordering */
|
||||
Ordering ordering = *graph.orderingCOLAMD(initial);
|
||||
|
||||
/* 4.2.2 set up solver and optimize */
|
||||
LevenbergMarquardtParams params;
|
||||
params.absoluteErrorTol = 1e-15;
|
||||
params.relativeErrorTol = 1e-15;
|
||||
params.ordering = ordering;
|
||||
LevenbergMarquardtOptimizer optimizer(graph, initial, params);
|
||||
|
||||
pose2SLAM::Values result = optimizer.optimize();
|
||||
result.print("final result");
|
||||
|
||||
/* Get covariances */
|
||||
Marginals marginals(graph, result, Marginals::CHOLESKY);
|
||||
Matrix covariance1 = marginals.marginalCovariance(1);
|
||||
Matrix covariance2 = marginals.marginalCovariance(2);
|
||||
|
||||
print(covariance1, "Covariance1");
|
||||
print(covariance2, "Covariance2");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue