Removed SLAM namespaces from SPCG example. Still needs better documentation by someone who knows what SPCG is.
parent
45d1c4f0ed
commit
e3a6282ff8
|
@ -16,79 +16,115 @@
|
||||||
* @date June 2, 2012
|
* @date June 2, 2012
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* A simple 2D pose slam example solved using a Conjugate-Gradient method
|
||||||
|
* - 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>
|
||||||
|
|
||||||
|
// 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 <gtsam/linear/SimpleSPCGSolver.h>
|
#include <gtsam/linear/SimpleSPCGSolver.h>
|
||||||
#include <gtsam/linear/SubgraphSolver.h>
|
#include <gtsam/linear/SubgraphSolver.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
#include <gtsam/slam/pose2SLAM.h>
|
|
||||||
|
|
||||||
#include <boost/shared_ptr.hpp>
|
|
||||||
#include <boost/make_shared.hpp>
|
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace gtsam::noiseModel;
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
int main(int argc, char** argv) {
|
||||||
int main(void) {
|
|
||||||
|
|
||||||
// 1. Create graph container and add factors to it
|
// 1. Create a factor graph container and add factors to it
|
||||||
pose2SLAM::Graph graph ;
|
NonlinearFactorGraph graph;
|
||||||
|
|
||||||
// 2a. Add Gaussian prior
|
// 2a. Add a prior on the first pose, setting it to the origin
|
||||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
// A prior factor consists of a mean and a noise model (covariance matrix)
|
||||||
SharedDiagonal priorNoise = Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1));
|
Pose2 prior(0.0, 0.0, 0.0); // prior at origin
|
||||||
graph.addPosePrior(1, priorMean, priorNoise);
|
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
|
// 2b. Add odometry factors
|
||||||
SharedDiagonal odometryNoise = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
// For simplicity, we will use the same noise model for each odometry factor
|
||||||
graph.addRelativePose(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise);
|
noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
||||||
graph.addRelativePose(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
// Create odometry (Between) factors between consecutive poses
|
||||||
graph.addRelativePose(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
graph.add(BetweenFactor<Pose2>(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
|
||||||
graph.addRelativePose(4, 5, 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
|
// 2c. Add the loop closure constraint
|
||||||
SharedDiagonal constraintUncertainty = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
// This factor encodes the fact that we have returned to the same pose. In real systems,
|
||||||
graph.addRelativePose(5, 2, Pose2(2.0, 0.0, M_PI_2), constraintUncertainty);
|
// 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 estinmate to the solution
|
// 3. Create the data structure to hold the initialEstimate estimate to the solution
|
||||||
pose2SLAM::Values initialEstimate;
|
// For illustrative purposes, these have been deliberately set to incorrect values
|
||||||
Pose2 x1(0.5, 0.0, 0.2 ); initialEstimate.insertPose(1, x1);
|
Values initialEstimate;
|
||||||
Pose2 x2(2.3, 0.1,-0.2 ); initialEstimate.insertPose(2, x2);
|
initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
|
||||||
Pose2 x3(4.1, 0.1, M_PI_2); initialEstimate.insertPose(3, x3);
|
initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1));
|
||||||
Pose2 x4(4.0, 2.0, M_PI ); initialEstimate.insertPose(4, x4);
|
initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8));
|
||||||
Pose2 x5(2.1, 2.1,-M_PI_2); initialEstimate.insertPose(5, x5);
|
initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2));
|
||||||
initialEstimate.print("\nInitial estimate:\n ");
|
initialEstimate.insert(5, Pose2(0.1,-0.7, 5.8));
|
||||||
cout << "initial error = " << graph.error(initialEstimate) << endl ;
|
initialEstimate.print("\nInitial Estimate:\n"); // print
|
||||||
|
|
||||||
// 4. Single Step Optimization using Levenberg-Marquardt
|
// 4. Single Step Optimization using Levenberg-Marquardt
|
||||||
LevenbergMarquardtParams param;
|
LevenbergMarquardtParams parameters;
|
||||||
param.verbosity = NonlinearOptimizerParams::ERROR;
|
parameters.verbosity = NonlinearOptimizerParams::ERROR;
|
||||||
param.verbosityLM = LevenbergMarquardtParams::LAMBDA;
|
parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA;
|
||||||
param.linearSolverType = SuccessiveLinearizationParams::CG;
|
parameters.linearSolverType = SuccessiveLinearizationParams::CG;
|
||||||
|
|
||||||
{
|
{
|
||||||
param.iterativeParams = boost::make_shared<SimpleSPCGSolverParameters>();
|
parameters.iterativeParams = boost::make_shared<SimpleSPCGSolverParameters>();
|
||||||
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, param);
|
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
|
||||||
Values result = optimizer.optimize();
|
Values result = optimizer.optimize();
|
||||||
result.print("\nFinal result:\n");
|
result.print("Final Result:\n");
|
||||||
cout << "simple spcg solver final error = " << graph.error(result) << endl;
|
cout << "simple spcg solver final error = " << graph.error(result) << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
param.iterativeParams = boost::make_shared<SubgraphSolverParameters>();
|
parameters.iterativeParams = boost::make_shared<SubgraphSolverParameters>();
|
||||||
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, param);
|
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
|
||||||
Values result = optimizer.optimize();
|
Values result = optimizer.optimize();
|
||||||
result.print("\nFinal result:\n");
|
result.print("Final Result:\n");
|
||||||
cout << "subgraph solver final error = " << graph.error(result) << endl;
|
cout << "subgraph solver final error = " << graph.error(result) << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
return 0;
|
||||||
Values result = graph.optimizeSPCG(initialEstimate);
|
|
||||||
result.print("\nFinal result:\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0 ;
|
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue