diff --git a/examples/VisualSLAMExampleData.h b/examples/VisualSLAMExampleData.h new file mode 100644 index 000000000..f0ee4d2b5 --- /dev/null +++ b/examples/VisualSLAMExampleData.h @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualSLAMSimulatedData.cpp + * @brief Generate ground-truth simulated data for VisualSLAM examples (SFM and ISAM2) + * @author Duy-Nguyen Ta + */ + +#pragma once + +#include +#include +#include + +/* ************************************************************************* */ +/** + * Simulated data for the example: + * - 8 Landmarks: (10,10,10) (-10,10,10) (-10,-10,10) (10,-10,10) + * (10,10,-10) (-10,10,-10) (-10,-10,-10) (10,-10,-10) + * - n 90-deg-FoV cameras with the same calibration parameters: + * f = 50.0, Image: 100x100, center: 50.0, 50.0 + * and ground-truth poses on a circle around the landmarks looking at the world's origin: + * Rot3(-sin(theta), 0, -cos(theta), + * cos(theta), 0, -sin(theta), + * 0, -1, 0 ), + * Point3(r*cos(theta), r*sin(theta), 0.0) + * (theta += 2*pi/N) + * - Measurement noise: 1 pix sigma + */ +struct VisualSLAMExampleData { + gtsam::shared_ptrK sK; // camera calibration parameters + std::vector poses; // ground-truth camera poses + gtsam::Pose3 odometry; // ground-truth odometry between 2 consecutive poses (simulated data for iSAM) + std::vector landmarks; // ground-truth landmarks + std::map > z; // 2D measurements of landmarks in each camera frame + gtsam::SharedDiagonal noiseZ; // measurement noise (noiseModel::Isotropic::Sigma(2, 5.0f)); + gtsam::SharedDiagonal noiseX; // noise for camera poses + gtsam::SharedDiagonal noiseL; // noise for landmarks + + static const VisualSLAMExampleData generate() { + VisualSLAMExampleData data; + // Landmarks (ground truth) + data.landmarks.push_back(gtsam::Point3(10.0,10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,-10.0,10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(-10.0,-10.0,-10.0)); + data.landmarks.push_back(gtsam::Point3(10.0,-10.0,-10.0)); + + // Camera calibration parameters + data.sK = gtsam::shared_ptrK(new gtsam::Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + // n camera poses + int n = 8; + double theta = 0.0; + double r = 30.0; + for (int i=0; isample())); + } + } + data.noiseX = gtsam::sharedSigmas(gtsam::Vector_(6, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1)); + data.noiseL = gtsam::sharedSigma(3, 0.1); + + return data; + } +}; diff --git a/examples/VisualSLAMforSFMExample.cpp b/examples/VisualSLAMforSFMExample.cpp new file mode 100644 index 000000000..17f457908 --- /dev/null +++ b/examples/VisualSLAMforSFMExample.cpp @@ -0,0 +1,64 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualSLAMforSFMExample.cpp + * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset + * @author Duy-Nguyen Ta + */ + +#include +#include +#include +#include +#include "VisualSLAMExampleData.h" + +using namespace std; +using namespace gtsam; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + VisualSLAMExampleData data = VisualSLAMExampleData::generate(); + + /* 1. Create graph *///using the 2D measurements (features) and the calibration data + visualSLAM::Graph graph; + + /* 2. Add factors to the graph */ + // 2a. Measurement factors + for (size_t i=0; isample())); + for (size_t j=0; jsample())); + initial.print("Intial Estimates: "); + + /* 4. Optimize the graph and print results */ + visualSLAM::Values result = GaussNewtonOptimizer(graph, initial).optimize(); +// visualSLAM::Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + result.print("Final results: "); + + return 0; +} +/* ************************************************************************* */ + diff --git a/examples/VisualSLAMwISAM2Example.cpp b/examples/VisualSLAMwISAM2Example.cpp new file mode 100644 index 000000000..07fe0433c --- /dev/null +++ b/examples/VisualSLAMwISAM2Example.cpp @@ -0,0 +1,113 @@ +/* ---------------------------------------------------------------------------- + + * 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 VisualSLAMwISAM2Example.cpp + * @brief An ISAM example for synthesis sequence, single camera + * @author Duy-Nguyen Ta + */ + +#include +#include +#include +#include +#include "VisualSLAMExampleData.h" + +using namespace std; +using namespace gtsam; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +/* ************************************************************************* */ +int main(int argc, char* argv[]) { + + VisualSLAMExampleData data = VisualSLAMExampleData::generate(); + + /* 1. Create a NonlinearISAM which will be relinearized and reordered after every "relinearizeInterval" updates */ + int relinearizeInterval = 3; + NonlinearISAM<> isam(relinearizeInterval); + + /* 2. At each frame (poseId) with new camera pose and set of associated measurements, + * create a graph of new factors and update ISAM */ + + // Store the current best estimate from ISAM + Values currentEstimate; + + // First two frames: + // Add factors and initial values for the first two poses and landmarks then update ISAM. + // Note: measurements from the first pose only are not enough to update ISAM: + // the system is underconstrained. + { + visualSLAM::Graph newFactors; + + // First pose with prior factor + newFactors.addPosePrior(X(0), data.poses[0], data.noiseX); + + // Second pose with odometry measurement, simulated by adding Gaussian noise to the ground-truth. + Pose3 odoMeasurement = data.odometry*Pose3::Expmap(data.noiseX->sample()); + newFactors.push_back( boost::shared_ptr >( + new BetweenFactor(X(0), X(1), odoMeasurement, data.noiseX))); + + // Visual measurements at both poses + for (size_t i=0; i<2; ++i) { + for (size_t j=0; jsample()); + initials.insert(X(0), pose0Init); + initials.insert(X(1), pose0Init*odoMeasurement); + + // Initial values for the landmarks, simulated with Gaussian noise + for (size_t j=0; jsample())); + + // Update ISAM the first time and obtain the current estimate + isam.update(newFactors, initials); + currentEstimate = isam.estimate(); + cout << "Pose 0 and 1: " << endl; + currentEstimate.print("Current estimate: "); + } + + // Subsequent frames: Add new odometry and measurement factors and initial values, + // then update ISAM at each frame + for (size_t i=2; isample()); + newFactors.push_back( boost::shared_ptr >( + new BetweenFactor(X(i-1), X(i), odoMeasurement, data.noiseX))); + // Factors for visual measurements + for (size_t j=0; j(X(i-1))*odoMeasurement); + + // update ISAM + isam.update(newFactors, initials); + currentEstimate = isam.estimate(); + cout << "****************************************************" << endl; + cout << "Pose " << i << ": " << endl; + currentEstimate.print("Current estimate: "); + } + + return 0; +} +/* ************************************************************************* */ +