TriangulationLOSTExample.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
21 #include <gtsam/geometry/Cal3_S2.h>
23 #include <gtsam/geometry/Point2.h>
24 #include <gtsam/geometry/Point3.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/geometry/Rot3.h>
28 
29 #include <chrono>
30 #include <iostream>
31 #include <random>
32 #include <optional>
33 
34 using namespace std;
35 using namespace gtsam;
36 
37 static std::mt19937 rng(42);
38 
39 void PrintCovarianceStats(const Matrix& mat, const std::string& method) {
40  Matrix centered = mat.rowwise() - mat.colwise().mean();
41  Matrix cov = (centered.adjoint() * centered) / double(mat.rows() - 1);
42  std::cout << method << " covariance: " << std::endl;
43  std::cout << cov << std::endl;
44  std::cout << "Trace sqrt: " << sqrt(cov.trace()) << std::endl << std::endl;
45 }
46 
47 void PrintDuration(const std::chrono::nanoseconds dur, double num_samples,
48  const std::string& method) {
49  double nanoseconds = dur.count() / num_samples;
50  std::cout << "Time taken by " << method << ": " << nanoseconds * 1e-3
51  << std::endl;
52 }
53 
55  std::vector<Pose3>* poses, Point3* point,
56  Point2Vector* measurements) {
57  const double minXY = -10, maxXY = 10;
58  const double minZ = -20, maxZ = 0;
59  const int nrCameras = 500;
60  cameras->reserve(nrCameras);
61  poses->reserve(nrCameras);
62  measurements->reserve(nrCameras);
63  *point = Point3(0.0, 0.0, 10.0);
64 
65  std::uniform_real_distribution<double> rand_xy(minXY, maxXY);
66  std::uniform_real_distribution<double> rand_z(minZ, maxZ);
67  Cal3_S2 identityK;
68 
69  for (int i = 0; i < nrCameras; ++i) {
70  Point3 wti(rand_xy(rng), rand_xy(rng), rand_z(rng));
71  Pose3 wTi(Rot3(), wti);
72 
73  poses->push_back(wTi);
74  cameras->emplace_back(wTi, identityK);
75  measurements->push_back(cameras->back().project(*point));
76  }
77 }
78 
80  std::vector<Pose3>* poses, Point3* point,
81  Point2Vector* measurements) {
82  Pose3 pose1;
83  Pose3 pose2(Rot3(), Point3(5., 0., -5.));
84  Cal3_S2 identityK;
85  PinholeCamera<Cal3_S2> camera1(pose1, identityK);
86  PinholeCamera<Cal3_S2> camera2(pose2, identityK);
87 
88  *point = Point3(0, 0, 1);
89  cameras->push_back(camera1);
90  cameras->push_back(camera2);
91  *poses = {pose1, pose2};
92  *measurements = {camera1.project(*point), camera2.project(*point)};
93 }
94 
96  const double measurementSigma) {
97  std::normal_distribution<double> normal(0.0, measurementSigma);
98 
99  Point2Vector noisyMeasurements;
100  noisyMeasurements.reserve(measurements.size());
101  for (const auto& p : measurements) {
102  noisyMeasurements.emplace_back(p.x() + normal(rng), p.y() + normal(rng));
103  }
104  return noisyMeasurements;
105 }
106 
107 /* ************************************************************************* */
108 int main(int argc, char* argv[]) {
110  std::vector<Pose3> poses;
112  Point2Vector measurements;
113  GetLargeCamerasDataset(&cameras, &poses, &landmark, &measurements);
114  // GetSmallCamerasDataset(&cameras, &poses, &landmark, &measurements);
115  const double measurementSigma = 1e-2;
116  SharedNoiseModel measurementNoise =
117  noiseModel::Isotropic::Sigma(2, measurementSigma);
118 
119  const long int nrTrials = 1000;
120  Matrix errorsDLT = Matrix::Zero(nrTrials, 3);
121  Matrix errorsLOST = Matrix::Zero(nrTrials, 3);
122  Matrix errorsDLTOpt = Matrix::Zero(nrTrials, 3);
123 
124  double rank_tol = 1e-9;
125  std::shared_ptr<Cal3_S2> calib = std::make_shared<Cal3_S2>();
126  std::chrono::nanoseconds durationDLT;
127  std::chrono::nanoseconds durationDLTOpt;
128  std::chrono::nanoseconds durationLOST;
129 
130  for (int i = 0; i < nrTrials; i++) {
131  Point2Vector noisyMeasurements =
132  AddNoiseToMeasurements(measurements, measurementSigma);
133 
134  auto lostStart = std::chrono::high_resolution_clock::now();
135  auto estimateLOST = triangulatePoint3<Cal3_S2>(
136  cameras, noisyMeasurements, rank_tol, false, measurementNoise, true);
137  durationLOST += std::chrono::high_resolution_clock::now() - lostStart;
138 
139  auto dltStart = std::chrono::high_resolution_clock::now();
140  auto estimateDLT = triangulatePoint3<Cal3_S2>(
141  cameras, noisyMeasurements, rank_tol, false, measurementNoise, false);
142  durationDLT += std::chrono::high_resolution_clock::now() - dltStart;
143 
144  auto dltOptStart = std::chrono::high_resolution_clock::now();
145  auto estimateDLTOpt = triangulatePoint3<Cal3_S2>(
146  cameras, noisyMeasurements, rank_tol, true, measurementNoise, false);
147  durationDLTOpt += std::chrono::high_resolution_clock::now() - dltOptStart;
148 
149  errorsLOST.row(i) = estimateLOST - landmark;
150  errorsDLT.row(i) = estimateDLT - landmark;
151  errorsDLTOpt.row(i) = estimateDLTOpt - landmark;
152  }
153  PrintCovarianceStats(errorsLOST, "LOST");
154  PrintCovarianceStats(errorsDLT, "DLT");
155  PrintCovarianceStats(errorsDLTOpt, "DLT_OPT");
156 
157  PrintDuration(durationLOST, nrTrials, "LOST");
158  PrintDuration(durationDLT, nrTrials, "DLT");
159  PrintDuration(durationDLTOpt, nrTrials, "DLT_OPT");
160 }
void PrintDuration(const std::chrono::nanoseconds dur, double num_samples, const std::string &method)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Definition: BFloat16.h:88
A set of cameras, all with their own calibration.
Definition: CameraSet.h:36
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
int main(int argc, char *argv[])
static Point3 landmark(0, 0, 5)
Base class for all pinhole cameras.
void GetLargeCamerasDataset(CameraSet< PinholeCamera< Cal3_S2 >> *cameras, std::vector< Pose3 > *poses, Point3 *point, Point2Vector *measurements)
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
Functions for triangulation.
void GetSmallCamerasDataset(CameraSet< PinholeCamera< Cal3_S2 >> *cameras, std::vector< Pose3 > *poses, Point3 *point, Point2Vector *measurements)
static const Camera2 camera2(pose1, K2)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Unit3_ normal(const OrientedPlane3_ &p)
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
traits
Definition: chartTesting.h:28
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
3D Point
float * p
Point2Vector AddNoiseToMeasurements(const Point2Vector &measurements, const double measurementSigma)
static Pose3 pose2
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
Vector3 Point3
Definition: Point3.h:38
static std::mt19937 rng(42)
void PrintCovarianceStats(const Matrix &mat, const std::string &method)
2D Point
3D Pose
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:35