45 std::runtime_error(
"Triangulation Underconstrained Exception.") {
54 "Triangulation Cheirality Exception: The resulting landmark is behind one or more cameras.") {
79 const std::vector<Unit3>& measurements,
double rank_tol = 1
e-9);
91 double rank_tol = 1
e-9);
98 const std::vector<Unit3>& measurements,
99 double rank_tol = 1
e-9);
114 double rank_tol = 1
e-9);
125 template<
class CALIBRATION>
127 const std::vector<Pose3>& poses, std::shared_ptr<CALIBRATION>
sharedCal,
129 const Point3& initialEstimate,
132 values.
insert(landmarkKey, initialEstimate);
134 for (
size_t i = 0;
i < measurements.size();
i++) {
135 const Pose3& pose_i = poses[
i];
137 Camera camera_i(pose_i, sharedCal);
139 (camera_i, measurements[
i],
model, landmarkKey);
141 return {
graph, values};
153 template<
class CAMERA>
156 const typename CAMERA::MeasurementVector& measurements,
Key landmarkKey,
157 const Point3& initialEstimate,
160 values.
insert(landmarkKey, initialEstimate);
164 for (
size_t i = 0;
i < measurements.size();
i++) {
165 const CAMERA& camera_i = cameras[
i];
167 (camera_i, measurements[
i],
model?
model : unit, landmarkKey);
169 return {
graph, values};
190 template<
class CALIBRATION>
192 std::shared_ptr<CALIBRATION> sharedCal,
197 const auto [
graph,
values] = triangulationGraph<CALIBRATION>
210 template<
class CAMERA>
213 const typename CAMERA::MeasurementVector& measurements,
const Point3& initialEstimate,
217 const auto [
graph,
values] = triangulationGraph<CAMERA>
218 (cameras, measurements,
Symbol(
'p', 0), initialEstimate,
model);
223 template<
class CAMERA>
224 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>
226 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
227 for (
const CAMERA &
camera: cameras) {
228 projection_matrices.push_back(
camera.cameraProjectionMatrix());
230 return projection_matrices;
234 template<
class CALIBRATION>
236 const std::vector<Pose3> &poses, std::shared_ptr<CALIBRATION> sharedCal) {
237 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
238 for (
size_t i = 0;
i < poses.size();
i++) {
240 projection_matrices.push_back(
camera.cameraProjectionMatrix());
242 return projection_matrices;
252 template <
class CALIBRATION>
254 const auto&
K = cal.K();
255 return Cal3_S2(
K(0, 0),
K(1, 1),
K(0, 1),
K(0, 2),
K(1, 2));
260 template <
class CALIBRATION,
class MEASUREMENT>
263 std::optional<Cal3_S2> pinholeCal = {}) {
267 return pinholeCal->uncalibrate(cal.calibrate(measurement));
281 template <
class CALIBRATION>
289 std::back_inserter(undistortedMeasurements),
291 return undistortMeasurementInternal<CALIBRATION>(
294 return undistortedMeasurements;
315 template <
class CAMERA>
318 const typename CAMERA::MeasurementVector& measurements) {
319 const size_t nrMeasurements = measurements.size();
320 assert(nrMeasurements == cameras.size());
321 typename CAMERA::MeasurementVector undistortedMeasurements(nrMeasurements);
322 for (
size_t ii = 0; ii < nrMeasurements; ++ii) {
325 undistortedMeasurements[ii] =
326 undistortMeasurementInternal<typename CAMERA::CalibrationType>(
327 cameras[ii].calibration(), measurements[ii]);
329 return undistortedMeasurements;
333 template <
class CAMERA = PinholeCamera<Cal3_S2>>
341 template <
class CAMERA = SphericalCamera>
356 template <
class CALIBRATION>
358 const CALIBRATION& cal,
const Point2Vector& measurements) {
363 std::back_inserter(calibratedMeasurements),
366 p << cal.calibrate(measurement), 1.0;
369 return calibratedMeasurements;
380 template <
class CAMERA>
383 const typename CAMERA::MeasurementVector& measurements) {
384 const size_t nrMeasurements = measurements.size();
385 assert(nrMeasurements == cameras.size());
387 for (
size_t ii = 0; ii < nrMeasurements; ++ii) {
388 calibratedMeasurements[ii]
389 << cameras[ii].calibration().calibrate(measurements[ii]),
392 return calibratedMeasurements;
396 template <
class CAMERA = SphericalCamera>
400 Point3Vector calibratedMeasurements(measurements.size());
401 for (
size_t ii = 0; ii < measurements.size(); ++ii) {
402 calibratedMeasurements[ii] << measurements[ii].point3();
404 return calibratedMeasurements;
420 template <
class CALIBRATION>
422 std::shared_ptr<CALIBRATION> sharedCal,
424 double rank_tol = 1
e-9,
bool optimize =
false,
426 const bool useLOST =
false) {
427 assert(poses.size() == measurements.size());
435 const double measurementSigma =
model ?
model->sigmas().mean() : 1
e-4;
440 auto calibratedMeasurements =
441 calibrateMeasurementsShared<CALIBRATION>(*
sharedCal, measurements);
443 point =
triangulateLOST(poses, calibratedMeasurements, measurementNoise,
450 auto undistortedMeasurements =
451 undistortMeasurements<CALIBRATION>(*
sharedCal, measurements);
454 triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol);
459 point = triangulateNonlinear<CALIBRATION>
462 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 465 const Point3& p_local =
pose.transformTo(point);
487 template <
class CAMERA>
489 const typename CAMERA::MeasurementVector& measurements,
490 double rank_tol = 1
e-9,
bool optimize =
false,
492 const bool useLOST =
false) {
493 size_t m = cameras.size();
494 assert(measurements.size() ==
m);
503 const double measurementSigma =
model ?
model->sigmas().mean() : 1
e-4;
508 std::vector<Pose3> poses;
509 poses.reserve(cameras.size());
510 for (
const auto&
camera : cameras) poses.push_back(
camera.pose());
514 auto calibratedMeasurements =
515 calibrateMeasurements<CAMERA>(cameras, measurements);
517 point =
triangulateLOST(poses, calibratedMeasurements, measurementNoise,
524 auto undistortedMeasurements =
525 undistortMeasurements<CAMERA>(cameras, measurements);
528 triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol);
533 point = triangulateNonlinear<CAMERA>(cameras, measurements,
point,
model);
536 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 538 for (
const CAMERA&
camera : cameras) {
539 const Point3& p_local =
camera.pose().transformTo(point);
548 template <
class CALIBRATION>
551 double rank_tol = 1
e-9,
bool optimize =
false,
553 const bool useLOST =
false) {
554 return triangulatePoint3<PinholeCamera<CALIBRATION>>
589 const bool _enableEPI =
false,
double _landmarkDistanceThreshold = -1,
590 double _dynamicOutlierRejectionThreshold = -1,
592 rankTolerance(_rankTolerance), enableEPI(_enableEPI),
593 landmarkDistanceThreshold(_landmarkDistanceThreshold),
594 dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold),
595 noiseModel(_noiseModel){
602 os <<
"enableEPI = " << p.
enableEPI << std::endl;
605 os <<
"dynamicOutlierRejectionThreshold = " 607 os <<
"noise model" << std::endl;
613 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 614 friend class boost::serialization::access; 616 template<
class ARCHIVE>
618 ar & BOOST_SERIALIZATION_NVP(rankTolerance);
619 ar & BOOST_SERIALIZATION_NVP(enableEPI);
620 ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold);
621 ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold);
632 enum Status {
VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
658 bool valid()
const {
return status == VALID; }
660 bool outlier()
const {
return status == OUTLIER; }
661 bool farPoint()
const {
return status == FAR_POINT; }
664 if (!has_value())
throw std::runtime_error(
"TriangulationResult has no value");
671 os <<
"point = " << *result << std::endl;
673 os <<
"no point, status = " << result.
status << std::endl;
678 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 679 friend class boost::serialization::access; 681 template <
class ARCHIVE>
683 ar& BOOST_SERIALIZATION_NVP(status);
689 template<
class CAMERA>
691 const typename CAMERA::MeasurementVector&
measured,
694 size_t m = cameras.size();
708 double maxReprojError = 0.0;
709 for(
const CAMERA&
camera: cameras) {
715 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 719 if (p_local.z() <= 0)
725 Point2 reprojectionError =
camera.reprojectionError(point, zi);
726 maxReprojError =
std::max(maxReprojError, reprojectionError.norm());
TriangulationParameters(const double _rankTolerance=1.0, const bool _enableEPI=false, double _landmarkDistanceThreshold=-1, double _dynamicOutlierRejectionThreshold=-1, const SharedNoiseModel &_noiseModel=nullptr)
std::vector< Point3, Eigen::aligned_allocator< Point3 > > Point3Vector
std::pair< NonlinearFactorGraph, Values > triangulationGraph(const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate, const SharedNoiseModel &model=noiseModel::Unit::Create(2))
TriangulationResult(Status s)
TriangulationResult(const Point3 &p)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
SharedNoiseModel noiseModel
used in the nonlinear triangulation
static TriangulationResult Outlier()
Factor Graph consisting of non-linear factors.
std::string serialize(const T &input)
serializes to a string
std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > projectionMatricesFromPoses(const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal)
noiseModel::Diagonal::shared_ptr model
Base class to create smart factors on poses or cameras.
PinholeCamera< Cal3Bundler0 > Camera
double dynamicOutlierRejectionThreshold
Point3Vector calibrateMeasurements(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measurements)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
noiseModel::Isotropic::shared_ptr SharedIsotropic
Calibrated camera with spherical projection.
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
NonlinearFactorGraph graph
A set of cameras, all with their own calibration.
static TriangulationResult BehindCamera()
static shared_ptr Create(size_t dim)
static const SmartProjectionParams params
TriangulationUnderconstrainedException()
friend std::ostream & operator<<(std::ostream &os, const TriangulationResult &result)
Base class for all pinhole cameras.
static Point2 measurement(323.0, 240.0)
std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 > > projectionMatricesFromCameras(const CameraSet< CAMERA > &cameras)
Point3 triangulateLOST(const std::vector< Pose3 > &poses, const Point3Vector &calibratedMeasurements, const SharedIsotropic &measurementNoise, double rank_tol)
Triangulation using the LOST (Linear Optimal Sine Triangulation) algorithm proposed in https://arxiv...
double landmarkDistanceThreshold
STL compatible allocator to use with types requiring a non standrad alignment.
Cal3_S2 createPinholeCalibration(const CALIBRATION &cal)
Point3 triangulateDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
bool enableEPI
if set to true, will refine triangulation using LM
double rankTolerance
(the rank is the number of singular values of the triangulation matrix which are larger than rankTole...
GenericMeasurement< Point2, Point2 > Measurement
static const std::shared_ptr< Cal3_S2 > sharedCal
Point2Vector undistortMeasurements(const CALIBRATION &cal, const Point2Vector &measurements)
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Exception thrown by triangulateDLT when SVD returns rank < 3.
The most common 5DOF 3D->2D calibration.
Point3 triangulatePoint3(const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false, const SharedNoiseModel &model=nullptr, const bool useLOST=false)
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Exception thrown by triangulateDLT when landmark is behind one or more of the cameras.
static TriangulationResult FarPoint()
friend std::ostream & operator<<(std::ostream &os, const TriangulationParameters &p)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
ofstream os("timeSchurFactors.csv")
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
static TriangulationResult Degenerate()
Vector4 triangulateHomogeneousDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
MEASUREMENT undistortMeasurementInternal(const CALIBRATION &cal, const MEASUREMENT &measurement, std::optional< Cal3_S2 > pinholeCal={})
void insert(Key j, const Value &val)
Point2Vector MeasurementVector
Calibration of a fisheye camera.
Point3 triangulateNonlinear(const std::vector< Pose3 > &poses, std::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, const Point3 &initialEstimate, const SharedNoiseModel &model=nullptr)
Unified Calibration Model, see Mei07icra for details.
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian< 1, 3 > H1, OptionalJacobian< 1, 3 > H2)
distance between two points
TriangulationCheiralityException()
static const CalibratedCamera camera(kDefaultPose)
std::vector< Unit3 > MeasurementVector
std::uint64_t Key
Integer nonlinear key type.
Calibration used by Bundler.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Point3Vector calibrateMeasurementsShared(const CALIBRATION &cal, const Point2Vector &measurements)
bool behindCamera() const