gtsam/examples/SFMExample_SmartFactor.cpp

133 lines
5.0 KiB
C++
Raw Permalink Normal View History

2014-06-01 03:57:13 +08:00
/* ----------------------------------------------------------------------------
* 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 SFMExample_SmartFactor.cpp
* @brief A structure-from-motion problem on a simulated dataset, using smart projection factor
* @author Duy-Nguyen Ta
* @author Jing Dong
2014-06-23 06:39:11 +08:00
* @author Frank Dellaert
2014-06-01 03:57:13 +08:00
*/
// In GTSAM, measurement functions are represented as 'factors'.
// The factor we used here is SmartProjectionPoseFactor.
// Every smart factor represent a single landmark, seen from multiple cameras.
// The SmartProjectionPoseFactor only optimizes for the poses of a camera,
// not the calibration, which is assumed known.
2014-06-01 03:57:13 +08:00
#include <gtsam/slam/SmartProjectionPoseFactor.h>
// For an explanation of these headers, see SFMExample.cpp
#include "SFMdata.h"
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
2014-06-01 03:57:13 +08:00
using namespace std;
using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor;
2014-06-01 03:57:13 +08:00
// create a typedef to the camera type
typedef PinholePose<Cal3_S2> Camera;
2014-06-01 03:57:13 +08:00
/* ************************************************************************* */
int main(int argc, char* argv[]) {
// Define the camera calibration parameters
Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
// Define the camera observation noise model
2020-05-10 07:08:31 +08:00
auto measurementNoise =
2014-06-23 06:39:11 +08:00
noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
2014-06-01 03:57:13 +08:00
2014-06-23 06:39:11 +08:00
// Create the set of ground-truth landmarks and poses
2014-06-01 03:57:13 +08:00
vector<Point3> points = createPoints();
vector<Pose3> poses = createPoses();
// Create a factor graph
NonlinearFactorGraph graph;
// Simulated measurements from each camera pose, adding them to the factor graph
2014-06-23 06:39:11 +08:00
for (size_t j = 0; j < points.size(); ++j) {
2014-06-01 03:57:13 +08:00
// every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements.
2015-08-27 01:25:12 +08:00
SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
2014-06-01 03:57:13 +08:00
2014-06-23 06:39:11 +08:00
for (size_t i = 0; i < poses.size(); ++i) {
2014-06-01 03:57:13 +08:00
// generate the 2D measurement
Camera camera(poses[i], K);
2014-06-23 06:39:11 +08:00
Point2 measurement = camera.project(points[j]);
2014-06-01 03:57:13 +08:00
2014-06-23 06:39:11 +08:00
// call add() function to add measurement into a single factor, here we need to add:
2014-06-01 03:57:13 +08:00
// 1. the 2D measurement
// 2. the corresponding camera's key
// 3. camera noise model
// 4. camera calibration
2015-08-27 01:25:12 +08:00
smartfactor->add(measurement, i);
2014-06-01 03:57:13 +08:00
}
// insert the smart factor in the graph
graph.push_back(smartfactor);
}
// Add a prior on pose x0. This indirectly specifies where the origin is.
2014-06-23 06:39:11 +08:00
// 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
2020-05-10 07:08:31 +08:00
auto noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
2020-04-13 01:10:09 +08:00
graph.addPrior(0, poses[0], noise);
2014-06-23 06:39:11 +08:00
// Because the structure-from-motion problem has a scale ambiguity, the problem is
// still under-constrained. Here we add a prior on the second pose x1, so this will
// fix the scale by indicating the distance between x0 and x1.
// Because these two are fixed, the rest of the poses will be also be fixed.
2020-04-13 01:10:09 +08:00
graph.addPrior(1, poses[1], noise); // add directly to graph
2014-06-01 03:57:13 +08:00
graph.print("Factor Graph:\n");
2014-06-23 06:39:11 +08:00
// Create the initial estimate to the solution
2014-06-01 03:57:13 +08:00
// Intentionally initialize the variables off from the ground truth
Values initialEstimate;
2015-07-06 07:11:04 +08:00
Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
2014-06-01 03:57:13 +08:00
for (size_t i = 0; i < poses.size(); ++i)
2016-06-06 23:09:49 +08:00
initialEstimate.insert(i, poses[i].compose(delta));
2014-06-01 03:57:13 +08:00
initialEstimate.print("Initial Estimates:\n");
// Optimize the graph and print results
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
Values result = optimizer.optimize();
2014-06-01 03:57:13 +08:00
result.print("Final results:\n");
2014-06-23 06:39:11 +08:00
// A smart factor represent the 3D point inside the factor, not as a variable.
// The 3D position of the landmark is not explicitly calculated by the optimizer.
2014-06-23 06:39:11 +08:00
// To obtain the landmark's 3D position, we use the "point" method of the smart factor.
Values landmark_result;
2014-06-23 06:39:11 +08:00
for (size_t j = 0; j < points.size(); ++j) {
2014-06-23 06:39:11 +08:00
// The graph stores Factor shared_ptrs, so we cast back to a SmartFactor first
2023-01-18 06:39:55 +08:00
SmartFactor::shared_ptr smart = std::dynamic_pointer_cast<SmartFactor>(graph[j]);
2014-06-23 06:39:11 +08:00
if (smart) {
// The output of point() is in std::optional<Point3>, as sometimes
// the triangulation operation inside smart factor will encounter degeneracy.
2023-01-12 05:49:07 +08:00
auto point = smart->point(result);
if (point) // ignore if std::optional return nullptr
2014-06-23 06:39:11 +08:00
landmark_result.insert(j, *point);
}
}
landmark_result.print("Landmark results:\n");
cout << "final error: " << graph.error(result) << endl;
cout << "number of iterations: " << optimizer.iterations() << endl;
2014-06-01 03:57:13 +08:00
return 0;
}
/* ************************************************************************* */