35 using namespace gtsam;
37 static std::mt19937
rng(42);
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;
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 * 1
e-3
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);
65 std::uniform_real_distribution<double> rand_xy(minXY, maxXY);
66 std::uniform_real_distribution<double> rand_z(minZ, maxZ);
69 for (
int i = 0;
i < nrCameras; ++
i) {
73 poses->push_back(wTi);
74 cameras->emplace_back(wTi, identityK);
75 measurements->push_back(cameras->back().project(*point));
89 cameras->push_back(camera1);
90 cameras->push_back(camera2);
91 *poses = {
pose1, pose2};
92 *measurements = {camera1.
project(*point), camera2.
project(*point)};
96 const double measurementSigma) {
97 std::normal_distribution<double>
normal(0.0, measurementSigma);
100 noisyMeasurements.reserve(measurements.size());
101 for (
const auto&
p : measurements) {
104 return noisyMeasurements;
108 int main(
int argc,
char* argv[]) {
110 std::vector<Pose3> poses;
115 const double measurementSigma = 1
e-2;
117 noiseModel::Isotropic::Sigma(2, measurementSigma);
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);
124 double rank_tol = 1
e-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;
130 for (
int i = 0;
i < nrTrials;
i++) {
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;
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;
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;
149 errorsLOST.row(
i) = estimateLOST -
landmark;
150 errorsDLT.row(
i) = estimateDLT -
landmark;
151 errorsDLTOpt.row(
i) = estimateDLTOpt -
landmark;
void PrintDuration(const std::chrono::nanoseconds dur, double num_samples, const std::string &method)
A set of cameras, all with their own calibration.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
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
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.
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Point2Vector AddNoiseToMeasurements(const Point2Vector &measurements, const double measurementSigma)
Jet< T, N > sqrt(const Jet< T, N > &f)
static std::mt19937 rng(42)
void PrintCovarianceStats(const Matrix &mat, const std::string &method)
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
3D rotation represented as a rotation matrix or quaternion