Cleaned up example
parent
3e0ee2052d
commit
efa35e6a82
|
@ -11,8 +11,8 @@
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file VisualISAM2Example.cpp
|
* @file VisualISAM2Example.cpp
|
||||||
* @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset
|
* @brief A visualSLAM example for the structure-from-motion problem on a
|
||||||
* This version uses iSAM2 to solve the problem incrementally
|
* simulated dataset This version uses iSAM2 to solve the problem incrementally
|
||||||
* @author Duy-Nguyen Ta
|
* @author Duy-Nguyen Ta
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
@ -25,27 +25,28 @@
|
||||||
// For loading the data
|
// For loading the data
|
||||||
#include "SFMdata.h"
|
#include "SFMdata.h"
|
||||||
|
|
||||||
// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
|
// Camera observations of landmarks will be stored as Point2 (x, y).
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
|
|
||||||
// Each variable in the system (poses and landmarks) must be identified with a unique key.
|
// Each variable in the system (poses and landmarks) must be identified with a
|
||||||
// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
|
// unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols
|
||||||
// Here we will use Symbols
|
// (X1, X2, L1). Here we will use Symbols
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
|
|
||||||
// We want to use iSAM2 to solve the structure-from-motion problem incrementally, so
|
// We want to use iSAM2 to solve the structure-from-motion problem
|
||||||
// include iSAM2 here
|
// incrementally, so include iSAM2 here
|
||||||
#include <gtsam/nonlinear/ISAM2.h>
|
#include <gtsam/nonlinear/ISAM2.h>
|
||||||
|
|
||||||
// iSAM2 requires as input a set set of new factors to be added stored in a factor graph,
|
// iSAM2 requires as input a set of new factors to be added stored in a factor
|
||||||
// and initial guesses for any new variables used in the added factors
|
// graph, and initial guesses for any new variables used in the added factors
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <gtsam/nonlinear/Values.h>
|
#include <gtsam/nonlinear/Values.h>
|
||||||
|
|
||||||
// In GTSAM, measurement functions are represented as 'factors'. Several common factors
|
// In GTSAM, measurement functions are represented as 'factors'. Several common
|
||||||
// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
|
// factors have been provided with the library for solving robotics/SLAM/Bundle
|
||||||
// Here we will use Projection factors to model the camera's landmark observations.
|
// Adjustment problems. Here we will use Projection factors to model the
|
||||||
// Also, we will initialize the robot at some location using a Prior factor.
|
// 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/PriorFactor.h>
|
||||||
#include <gtsam/slam/ProjectionFactor.h>
|
#include <gtsam/slam/ProjectionFactor.h>
|
||||||
|
|
||||||
|
@ -56,12 +57,11 @@ using namespace gtsam;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main(int argc, char* argv[]) {
|
int main(int argc, char* argv[]) {
|
||||||
|
|
||||||
// Define the camera calibration parameters
|
// Define the camera calibration parameters
|
||||||
Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
|
Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
|
||||||
|
|
||||||
// Define the camera observation noise model
|
// Define the camera observation noise model, 1 pixel stddev
|
||||||
noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
|
auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
|
||||||
|
|
||||||
// Create the set of ground-truth landmarks
|
// Create the set of ground-truth landmarks
|
||||||
vector<Point3> points = createPoints();
|
vector<Point3> points = createPoints();
|
||||||
|
@ -69,10 +69,12 @@ int main(int argc, char* argv[]) {
|
||||||
// Create the set of ground-truth poses
|
// Create the set of ground-truth poses
|
||||||
vector<Pose3> poses = createPoses();
|
vector<Pose3> poses = createPoses();
|
||||||
|
|
||||||
// Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization
|
// Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps
|
||||||
// and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter
|
// to maintain proper linearization and efficient variable ordering, iSAM2
|
||||||
// structure is available that allows the user to set various properties, such as the relinearization threshold
|
// performs partial relinearization/reordering at each step. A parameter
|
||||||
// and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result
|
// structure is available that allows the user to set various properties, such
|
||||||
|
// as the relinearization threshold and type of linear solver. For this
|
||||||
|
// example, we we set the relinearization threshold small so the iSAM2 result
|
||||||
// will approach the batch result.
|
// will approach the batch result.
|
||||||
ISAM2Params parameters;
|
ISAM2Params parameters;
|
||||||
parameters.relinearizeThreshold = 0.01;
|
parameters.relinearizeThreshold = 0.01;
|
||||||
|
@ -83,44 +85,52 @@ int main(int argc, char* argv[]) {
|
||||||
NonlinearFactorGraph graph;
|
NonlinearFactorGraph graph;
|
||||||
Values initialEstimate;
|
Values initialEstimate;
|
||||||
|
|
||||||
// Loop over the different poses, adding the observations to iSAM incrementally
|
// Loop over the poses, adding the observations to iSAM incrementally
|
||||||
for (size_t i = 0; i < poses.size(); ++i) {
|
for (size_t i = 0; i < poses.size(); ++i) {
|
||||||
|
|
||||||
// Add factors for each landmark observation
|
// Add factors for each landmark observation
|
||||||
for (size_t j = 0; j < points.size(); ++j) {
|
for (size_t j = 0; j < points.size(); ++j) {
|
||||||
SimpleCamera camera(poses[i], *K);
|
SimpleCamera camera(poses[i], *K);
|
||||||
Point2 measurement = camera.project(points[j]);
|
Point2 measurement = camera.project(points[j]);
|
||||||
graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
|
graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(
|
||||||
|
measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add an initial guess for the current pose
|
// Add an initial guess for the current pose
|
||||||
// Intentionally initialize the variables off from the ground truth
|
// Intentionally initialize the variables off from the ground truth
|
||||||
initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
|
static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
|
||||||
|
Point3(0.05, -0.10, 0.20));
|
||||||
|
initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose);
|
||||||
|
|
||||||
// If this is the first iteration, add a prior on the first pose to set the coordinate frame
|
// If this is the first iteration, add a prior on the first pose to set the
|
||||||
// and a prior on the first landmark to set the scale
|
// coordinate frame and a prior on the first landmark to set the scale Also,
|
||||||
// Also, as iSAM solves incrementally, we must wait until each is observed at least twice before
|
// as iSAM solves incrementally, we must wait until each is observed at
|
||||||
// adding it to iSAM.
|
// least twice before adding it to iSAM.
|
||||||
if( i == 0) {
|
if (i == 0) {
|
||||||
// Add a prior on pose x0
|
// Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw
|
||||||
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
|
static auto kPosePrior = noiseModel::Diagonal::Sigmas(
|
||||||
graph.emplace_shared<PriorFactor<Pose3> >(Symbol('x', 0), poses[0], poseNoise);
|
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1))
|
||||||
|
.finished());
|
||||||
|
graph.emplace_shared<PriorFactor<Pose3> >(Symbol('x', 0), poses[0],
|
||||||
|
kPosePrior);
|
||||||
|
|
||||||
// Add a prior on landmark l0
|
// Add a prior on landmark l0
|
||||||
noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1);
|
static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
|
||||||
graph.emplace_shared<PriorFactor<Point3> >(Symbol('l', 0), points[0], pointNoise); // add directly to graph
|
graph.emplace_shared<PriorFactor<Point3> >(Symbol('l', 0), points[0],
|
||||||
|
kPointPrior);
|
||||||
|
|
||||||
// Add initial guesses to all observed landmarks
|
// Add initial guesses to all observed landmarks
|
||||||
// Intentionally initialize the variables off from the ground truth
|
// Intentionally initialize the variables off from the ground truth
|
||||||
|
static Point3 kDeltaPoint(-0.25, 0.20, 0.15);
|
||||||
for (size_t j = 0; j < points.size(); ++j)
|
for (size_t j = 0; j < points.size(); ++j)
|
||||||
initialEstimate.insert<Point3>(Symbol('l', j), points[j] +Point3(-0.25, 0.20, 0.15));
|
initialEstimate.insert<Point3>(Symbol('l', j), points[j] + kDeltaPoint);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// Update iSAM with the new factors
|
// Update iSAM with the new factors
|
||||||
isam.update(graph, initialEstimate);
|
isam.update(graph, initialEstimate);
|
||||||
// Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver.
|
// Each call to iSAM2 update(*) performs one iteration of the iterative
|
||||||
// If accuracy is desired at the expense of time, update(*) can be called additional times
|
// nonlinear solver. If accuracy is desired at the expense of time,
|
||||||
// to perform multiple optimizer iterations every step.
|
// update(*) can be called additional times to perform multiple optimizer
|
||||||
|
// iterations every step.
|
||||||
isam.update();
|
isam.update();
|
||||||
Values currentEstimate = isam.calculateEstimate();
|
Values currentEstimate = isam.calculateEstimate();
|
||||||
cout << "****************************************************" << endl;
|
cout << "****************************************************" << endl;
|
||||||
|
|
Loading…
Reference in New Issue