Combined the PlanarSLAM examples into a single example without SLAM namespaces
parent
d259320aed
commit
5da5adb2f1
|
@ -11,22 +11,12 @@
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file PlanarSLAMExample.cpp
|
* @file PlanarSLAMExample.cpp
|
||||||
* @brief Simple robotics example using the pre-built planar SLAM domain
|
* @brief Simple robotics example using odometry measurements and bearing-range (laser) measurements
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// pull in the planar SLAM domain with all typedefs and helper functions defined
|
|
||||||
#include <gtsam/slam/planarSLAM.h>
|
|
||||||
|
|
||||||
// we will use Symbol keys
|
|
||||||
#include <gtsam/nonlinear/Symbol.h>
|
|
||||||
|
|
||||||
using namespace std;
|
|
||||||
using namespace gtsam;
|
|
||||||
using namespace gtsam::noiseModel;
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Example of a simple 2D planar slam example with landmarls
|
* A simple 2D planar slam example with landmarks
|
||||||
* - The robot and landmarks are on a 2 meter grid
|
* - The robot and landmarks are on a 2 meter grid
|
||||||
* - Robot poses are facing along the X axis (horizontal, to the right in 2D)
|
* - Robot poses are facing along the X axis (horizontal, to the right in 2D)
|
||||||
* - The robot moves 2 meters each step
|
* - The robot moves 2 meters each step
|
||||||
|
@ -34,29 +24,74 @@ using namespace gtsam::noiseModel;
|
||||||
* - We have bearing and range information for measurements
|
* - We have bearing and range information for measurements
|
||||||
* - Landmarks are 2 meters away from the robot trajectory
|
* - Landmarks are 2 meters away from the robot trajectory
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
// 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
|
||||||
|
#include <gtsam/nonlinear/Symbol.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 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;
|
||||||
|
|
||||||
int main(int argc, char** argv) {
|
int main(int argc, char** argv) {
|
||||||
|
|
||||||
// create the graph (defined in planarSlam.h, derived from NonlinearFactorGraph)
|
// Create a factor graph
|
||||||
planarSLAM::Graph graph;
|
NonlinearFactorGraph graph;
|
||||||
|
|
||||||
// Create some keys
|
// Create the keys we need for this simple example
|
||||||
static Symbol i1('x',1), i2('x',2), i3('x',3);
|
static Symbol x1('x',1), x2('x',2), x3('x',3);
|
||||||
static Symbol j1('l',1), j2('l',2);
|
static Symbol l1('l',1), l2('l',2);
|
||||||
|
|
||||||
// add a Gaussian prior on pose x_1
|
// Add a prior on pose x1 at the origin. A prior factor consists of a mean and a noise model (covariance matrix)
|
||||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior mean is at origin
|
Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
|
||||||
SharedDiagonal priorNoise = Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
|
noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
|
||||||
graph.addPosePrior(i1, priorMean, priorNoise); // add directly to graph
|
graph.add(PriorFactor<Pose2>(x1, prior, priorNoise)); // add directly to graph
|
||||||
|
|
||||||
// add two odometry factors
|
// Add two odometry factors
|
||||||
Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
|
Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
|
||||||
SharedDiagonal odometryNoise = Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
|
noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
|
||||||
graph.addRelativePose(i1, i2, odometry, odometryNoise);
|
graph.add(BetweenFactor<Pose2>(x1, x2, odometry, odometryNoise));
|
||||||
graph.addRelativePose(i2, i3, odometry, odometryNoise);
|
graph.add(BetweenFactor<Pose2>(x2, x3, odometry, odometryNoise));
|
||||||
|
|
||||||
|
// Add Range-Bearing measurements to two different landmarks
|
||||||
// create a noise model for the landmark measurements
|
// create a noise model for the landmark measurements
|
||||||
SharedDiagonal measurementNoise = Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range
|
noiseModel::Diagonal::shared_ptr measurementNoise = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range
|
||||||
|
|
||||||
// create the measurement values - indices are (pose id, landmark id)
|
// create the measurement values - indices are (pose id, landmark id)
|
||||||
Rot2 bearing11 = Rot2::fromDegrees(45),
|
Rot2 bearing11 = Rot2::fromDegrees(45),
|
||||||
bearing21 = Rot2::fromDegrees(90),
|
bearing21 = Rot2::fromDegrees(90),
|
||||||
|
@ -65,27 +100,42 @@ int main(int argc, char** argv) {
|
||||||
range21 = 2.0,
|
range21 = 2.0,
|
||||||
range32 = 2.0;
|
range32 = 2.0;
|
||||||
|
|
||||||
// add bearing/range factors (created by "addBearingRange")
|
// Add Bearing-Range factors
|
||||||
graph.addBearingRange(i1, j1, bearing11, range11, measurementNoise);
|
graph.add(BearingRangeFactor<Pose2, Point2>(x1, l1, bearing11, range11, measurementNoise));
|
||||||
graph.addBearingRange(i2, j1, bearing21, range21, measurementNoise);
|
graph.add(BearingRangeFactor<Pose2, Point2>(x2, l1, bearing21, range21, measurementNoise));
|
||||||
graph.addBearingRange(i3, j2, bearing32, range32, measurementNoise);
|
graph.add(BearingRangeFactor<Pose2, Point2>(x3, l2, bearing32, range32, measurementNoise));
|
||||||
|
|
||||||
// print
|
// Print
|
||||||
graph.print("Factor graph");
|
graph.print("Factor Graph:\n");
|
||||||
|
|
||||||
// create (deliberatly inaccurate) initial estimate
|
// Create (deliberately inaccurate) initial estimate
|
||||||
planarSLAM::Values initialEstimate;
|
Values initialEstimate;
|
||||||
initialEstimate.insertPose(i1, Pose2(0.5, 0.0, 0.2));
|
initialEstimate.insert(x1, Pose2(0.5, 0.0, 0.2));
|
||||||
initialEstimate.insertPose(i2, Pose2(2.3, 0.1,-0.2));
|
initialEstimate.insert(x2, Pose2(2.3, 0.1,-0.2));
|
||||||
initialEstimate.insertPose(i3, Pose2(4.1, 0.1, 0.1));
|
initialEstimate.insert(x3, Pose2(4.1, 0.1, 0.1));
|
||||||
initialEstimate.insertPoint(j1, Point2(1.8, 2.1));
|
initialEstimate.insert(l1, Point2(1.8, 2.1));
|
||||||
initialEstimate.insertPoint(j2, Point2(4.1, 1.8));
|
initialEstimate.insert(l2, Point2(4.1, 1.8));
|
||||||
|
|
||||||
initialEstimate.print("Initial estimate:\n ");
|
// Print
|
||||||
|
initialEstimate.print("Initial Estimate:\n");
|
||||||
|
|
||||||
// optimize using Levenberg-Marquardt optimization with an ordering from colamd
|
// Optimize using Levenberg-Marquardt optimization. The optimizer
|
||||||
planarSLAM::Values result = graph.optimize(initialEstimate);
|
// accepts an optional set of configuration parameters, controlling
|
||||||
result.print("Final result:\n ");
|
// 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");
|
||||||
|
|
||||||
|
// Calculate and print marginal covariances for all variables
|
||||||
|
Marginals marginals(graph, result);
|
||||||
|
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");
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,137 +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 PlanarSLAMExample_selfcontained.cpp
|
|
||||||
* @brief Simple robotics example with all typedefs internal to this script.
|
|
||||||
* @author Alex Cunningham
|
|
||||||
*/
|
|
||||||
|
|
||||||
// add in headers for specific factors
|
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
|
||||||
#include <gtsam/slam/BetweenFactor.h>
|
|
||||||
#include <gtsam/slam/BearingRangeFactor.h>
|
|
||||||
|
|
||||||
// for all nonlinear keys
|
|
||||||
#include <gtsam/nonlinear/Symbol.h>
|
|
||||||
|
|
||||||
// implementations for structures - needed if self-contained, and these should be included last
|
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
|
||||||
#include <gtsam/nonlinear/Marginals.h>
|
|
||||||
|
|
||||||
// for modeling measurement uncertainty - all models included here
|
|
||||||
#include <gtsam/linear/NoiseModel.h>
|
|
||||||
|
|
||||||
// for points and poses
|
|
||||||
#include <gtsam/geometry/Point2.h>
|
|
||||||
#include <gtsam/geometry/Pose2.h>
|
|
||||||
|
|
||||||
#include <cmath>
|
|
||||||
#include <iostream>
|
|
||||||
|
|
||||||
using namespace std;
|
|
||||||
using namespace gtsam;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* In this version of the system we make the following assumptions:
|
|
||||||
* - All values are axis aligned
|
|
||||||
* - Robot poses are facing along the X axis (horizontal, to the right in images)
|
|
||||||
* - We have bearing and range information for measurements
|
|
||||||
* - We have full odometry for measurements
|
|
||||||
* - The robot and landmarks are on a grid, moving 2 meters each step
|
|
||||||
* - Landmarks are 2 meters away from the robot trajectory
|
|
||||||
*/
|
|
||||||
int main(int argc, char** argv) {
|
|
||||||
// create keys for variables
|
|
||||||
Symbol i1('x',1), i2('x',2), i3('x',3);
|
|
||||||
Symbol j1('l',1), j2('l',2);
|
|
||||||
|
|
||||||
// create graph container and add factors to it
|
|
||||||
NonlinearFactorGraph graph;
|
|
||||||
|
|
||||||
/* add prior */
|
|
||||||
// gaussian for prior
|
|
||||||
SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1));
|
|
||||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
|
||||||
PriorFactor<Pose2> posePrior(i1, priorMean, priorNoise); // create the factor
|
|
||||||
graph.add(posePrior); // add the factor to the graph
|
|
||||||
|
|
||||||
/* add odometry */
|
|
||||||
// general noisemodel for odometry
|
|
||||||
SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1));
|
|
||||||
Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
|
|
||||||
// create between factors to represent odometry
|
|
||||||
BetweenFactor<Pose2> odom12(i1, i2, odometry, odometryNoise);
|
|
||||||
BetweenFactor<Pose2> odom23(i2, i3, odometry, odometryNoise);
|
|
||||||
graph.add(odom12); // add both to graph
|
|
||||||
graph.add(odom23);
|
|
||||||
|
|
||||||
/* add measurements */
|
|
||||||
// general noisemodel for measurements
|
|
||||||
SharedDiagonal measurementNoise = noiseModel::Diagonal::Sigmas(Vector_(2, 0.1, 0.2));
|
|
||||||
|
|
||||||
// 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 = sqrt(4.0+4.0),
|
|
||||||
range21 = 2.0,
|
|
||||||
range32 = 2.0;
|
|
||||||
|
|
||||||
// create bearing/range factors
|
|
||||||
BearingRangeFactor<Pose2, Point2> meas11(i1, j1, bearing11, range11, measurementNoise);
|
|
||||||
BearingRangeFactor<Pose2, Point2> meas21(i2, j1, bearing21, range21, measurementNoise);
|
|
||||||
BearingRangeFactor<Pose2, Point2> meas32(i3, j2, bearing32, range32, measurementNoise);
|
|
||||||
|
|
||||||
// add the factors
|
|
||||||
graph.add(meas11);
|
|
||||||
graph.add(meas21);
|
|
||||||
graph.add(meas32);
|
|
||||||
|
|
||||||
graph.print("Full Graph");
|
|
||||||
|
|
||||||
// initialize to noisy points
|
|
||||||
Values initial;
|
|
||||||
initial.insert(i1, Pose2(0.5, 0.0, 0.2));
|
|
||||||
initial.insert(i2, Pose2(2.3, 0.1,-0.2));
|
|
||||||
initial.insert(i3, Pose2(4.1, 0.1, 0.1));
|
|
||||||
initial.insert(j1, Point2(1.8, 2.1));
|
|
||||||
initial.insert(j2, Point2(4.1, 1.8));
|
|
||||||
|
|
||||||
initial.print("initial estimate");
|
|
||||||
|
|
||||||
// optimize using Levenberg-Marquardt optimization with an ordering from colamd
|
|
||||||
|
|
||||||
// first using sequential elimination
|
|
||||||
LevenbergMarquardtParams lmParams;
|
|
||||||
lmParams.linearSolverType = LevenbergMarquardtParams::SEQUENTIAL_CHOLESKY;
|
|
||||||
Values resultSequential = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize();
|
|
||||||
resultSequential.print("final result (solved with a sequential solver)");
|
|
||||||
|
|
||||||
// then using multifrontal, advanced interface
|
|
||||||
// Note that we keep the original optimizer object so we can use the COLAMD
|
|
||||||
// ordering it computes.
|
|
||||||
LevenbergMarquardtOptimizer optimizer(graph, initial);
|
|
||||||
Values resultMultifrontal = optimizer.optimize();
|
|
||||||
resultMultifrontal.print("final result (solved with a multifrontal solver)");
|
|
||||||
|
|
||||||
// Print marginals covariances for all variables
|
|
||||||
Marginals marginals(graph, resultMultifrontal, Marginals::CHOLESKY);
|
|
||||||
print(marginals.marginalCovariance(i1), "i1 covariance");
|
|
||||||
print(marginals.marginalCovariance(i2), "i2 covariance");
|
|
||||||
print(marginals.marginalCovariance(i3), "i3 covariance");
|
|
||||||
print(marginals.marginalCovariance(j1), "j1 covariance");
|
|
||||||
print(marginals.marginalCovariance(j2), "j2 covariance");
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
Loading…
Reference in New Issue