24 #include <gtsam/slam/TriangulationFactor.h> 27 #include <gtsam/inference/Symbol.h> 35 std::runtime_error(
"Triangulation Underconstrained Exception.") {
44 "Triangulation Cheirality Exception: The resulting landmark is behind one or more cameras.") {
56 const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
57 const Point2Vector& measurements,
double rank_tol = 1e-9);
67 const std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>>& projection_matrices,
68 const Point2Vector& measurements,
69 double rank_tol = 1e-9);
80 template<
class CALIBRATION>
82 const std::vector<Pose3>& poses, boost::shared_ptr<CALIBRATION> sharedCal,
83 const Point2Vector& measurements,
Key landmarkKey,
84 const Point3& initialEstimate) {
86 values.
insert(landmarkKey, initialEstimate);
90 for (
size_t i = 0; i < measurements.size(); i++) {
91 const Pose3& pose_i = poses[i];
93 Camera camera_i(pose_i, sharedCal);
95 (camera_i, measurements[i], unit2, landmarkKey);
97 return std::make_pair(graph, values);
109 template<
class CAMERA>
112 const typename CAMERA::MeasurementVector& measurements,
Key landmarkKey,
113 const Point3& initialEstimate) {
115 values.
insert(landmarkKey, initialEstimate);
119 for (
size_t i = 0; i < measurements.size(); i++) {
120 const CAMERA& camera_i = cameras[i];
122 (camera_i, measurements[i], unit, landmarkKey);
124 return std::make_pair(graph, values);
128 template<
class CALIBRATION>
131 const Point2Vector& measurements,
Key landmarkKey,
132 const Point3& initialEstimate) {
133 return triangulationGraph<PinholeCamera<CALIBRATION> >
134 (cameras, measurements, landmarkKey, initialEstimate);
144 GTSAM_EXPORT Point3
optimize(
const NonlinearFactorGraph& graph,
145 const Values& values,
Key landmarkKey);
155 template<
class CALIBRATION>
157 boost::shared_ptr<CALIBRATION> sharedCal,
158 const Point2Vector& measurements,
const Point3& initialEstimate) {
163 boost::tie(graph, values) = triangulationGraph<CALIBRATION>
164 (poses, sharedCal, measurements,
Symbol(
'p', 0), initialEstimate);
176 template<
class CAMERA>
179 const typename CAMERA::MeasurementVector& measurements,
const Point3& initialEstimate) {
184 boost::tie(graph, values) = triangulationGraph<CAMERA>
185 (cameras, measurements,
Symbol(
'p', 0), initialEstimate);
191 template<
class CALIBRATION>
194 const Point2Vector& measurements,
const Point3& initialEstimate) {
195 return triangulateNonlinear<PinholeCamera<CALIBRATION> >
196 (cameras, measurements, initialEstimate);
206 template<
class CALIBRATION>
209 K_(calibration.K()) {
211 Matrix34 operator()(
const Pose3& pose)
const {
217 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
232 template<
class CALIBRATION>
234 boost::shared_ptr<CALIBRATION> sharedCal,
235 const Point2Vector& measurements,
double rank_tol = 1e-9,
238 assert(poses.size() == measurements.size());
239 if (poses.size() < 2)
243 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
245 for(
const Pose3& pose: poses)
246 projection_matrices.push_back(createP(pose));
253 point = triangulateNonlinear<CALIBRATION>
254 (poses, sharedCal, measurements, point);
256 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 258 for(
const Pose3& pose: poses) {
259 const Point3& p_local = pose.transformTo(point);
260 if (p_local.
z() <= 0)
280 template<
class CAMERA>
283 const typename CAMERA::MeasurementVector& measurements,
double rank_tol = 1e-9,
286 size_t m = cameras.size();
287 assert(measurements.size() == m);
293 std::vector<Matrix34, Eigen::aligned_allocator<Matrix34>> projection_matrices;
294 for(
const CAMERA& camera: cameras)
295 projection_matrices.push_back(
302 point = triangulateNonlinear<CAMERA>(cameras, measurements, point);
304 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 306 for(
const CAMERA& camera: cameras) {
307 const Point3& p_local = camera.pose().transformTo(point);
308 if (p_local.
z() <= 0)
317 template<
class CALIBRATION>
320 const Point2Vector& measurements,
double rank_tol = 1e-9,
322 return triangulatePoint3<PinholeCamera<CALIBRATION> >
323 (cameras, measurements, rank_tol,
optimize);
354 const bool _enableEPI =
false,
double _landmarkDistanceThreshold = -1,
355 double _dynamicOutlierRejectionThreshold = -1) :
356 rankTolerance(_rankTolerance), enableEPI(_enableEPI),
357 landmarkDistanceThreshold(_landmarkDistanceThreshold),
358 dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold) {
362 friend std::ostream &operator<<(std::ostream &os,
365 os <<
"enableEPI = " << p.
enableEPI << std::endl;
368 os <<
"dynamicOutlierRejectionThreshold = " 376 friend class boost::serialization::access;
377 template<
class ARCHIVE>
378 void serialize(ARCHIVE & ar,
const unsigned int version) {
379 ar & BOOST_SERIALIZATION_NVP(rankTolerance);
380 ar & BOOST_SERIALIZATION_NVP(enableEPI);
381 ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold);
382 ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold);
391 VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT
414 static TriangulationResult Outlier() {
415 return TriangulationResult(OUTLIER);
417 static TriangulationResult FarPoint() {
418 return TriangulationResult(FAR_POINT);
420 static TriangulationResult BehindCamera() {
421 return TriangulationResult(BEHIND_CAMERA);
424 return status_ == VALID;
426 bool degenerate()
const {
427 return status_ == DEGENERATE;
429 bool outlier()
const {
430 return status_ == OUTLIER;
432 bool farPoint()
const {
433 return status_ == FAR_POINT;
435 bool behindCamera()
const {
436 return status_ == BEHIND_CAMERA;
439 friend std::ostream &operator<<(std::ostream &os,
440 const TriangulationResult& result) {
442 os <<
"point = " << *result << std::endl;
444 os <<
"no point, status = " << result.status_ << std::endl;
451 friend class boost::serialization::access;
452 template<
class ARCHIVE>
453 void serialize(ARCHIVE & ar,
const unsigned int version) {
454 ar & BOOST_SERIALIZATION_NVP(status_);
459 template<
class CAMERA>
461 const typename CAMERA::MeasurementVector& measured,
464 size_t m = cameras.size();
468 return TriangulationResult::Degenerate();
472 Point3 point = triangulatePoint3<CAMERA>(cameras, measured,
477 double maxReprojError = 0.0;
478 for(
const CAMERA& camera: cameras) {
479 const Pose3& pose = camera.pose();
483 return TriangulationResult::FarPoint();
484 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 488 if (p_local.
z() <= 0)
489 return TriangulationResult::BehindCamera();
493 const Point2& zi = measured.at(i);
494 Point2 reprojectionError(camera.project(point) - zi);
495 maxReprojError = std::max(maxReprojError, reprojectionError.norm());
502 return TriangulationResult::Outlier();
510 return TriangulationResult::Degenerate();
513 return TriangulationResult::BehindCamera();
void insert(Key j, const Value &val)
Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present.
Definition: Values.cpp:133
Exception thrown by triangulateDLT when landmark is behind one or more of the cameras.
Definition: triangulation.h:40
Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 6 > Dpose=boost::none, OptionalJacobian< 3, 3 > Dpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:328
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Optimize for triangulation.
Definition: triangulation.cpp:73
Definition: PinholeCamera.h:33
Character and index key used to refer to variables.
Definition: Symbol.h:33
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
const Point3 & translation(OptionalJacobian< 3, 6 > H=boost::none) const
get translation
Definition: Pose3.cpp:265
double dynamicOutlierRejectionThreshold
If this is nonnegative the we will check if the average reprojection error is smaller than this thres...
Definition: triangulation.h:343
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Definition: TriangulationFactor.h:31
Definition: PinholePose.h:237
double landmarkDistanceThreshold
if the landmark is triangulated at distance larger than this, result is flagged as degenerate.
Definition: triangulation.h:336
TriangulationResult(const Point3 &p)
Constructor.
Definition: triangulation.h:407
Definition: triangulation.h:326
Exception thrown by triangulateDLT when SVD returns rank < 3.
Definition: triangulation.h:32
Base class for all pinhole cameras.
Factor Graph Constsiting of non-linear factors.
bool enableEPI
if set to true, will refine triangulation using LM
Definition: triangulation.h:330
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:460
static shared_ptr Create(size_t dim)
Create a unit covariance noise model.
Definition: NoiseModel.h:601
Create a 3*4 camera projection matrix from calibration and pose.
Definition: triangulation.h:207
Point3 triangulateDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312.
Definition: triangulation.cpp:56
Vector4 triangulateHomogeneousDLT(const std::vector< Matrix34, Eigen::aligned_allocator< Matrix34 >> &projection_matrices, const Point2Vector &measurements, double rank_tol)
DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312.
Definition: triangulation.cpp:26
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Point3 triangulatePoint3(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false)
Function to triangulate 3D landmark point from an arbitrary number of poses (at least 2) using the DL...
Definition: triangulation.h:233
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition: triangulation.h:389
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
TriangulationParameters(const double _rankTolerance=1.0, const bool _enableEPI=false, double _landmarkDistanceThreshold=-1, double _dynamicOutlierRejectionThreshold=-1)
Constructor.
Definition: triangulation.h:353
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:47
Base class to create smart factors on poses or cameras.
Matrix4 matrix() const
convert to 4*4 matrix
Definition: Pose3.cpp:280
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
TriangulationResult()
Default constructor, only for serialization.
Definition: triangulation.h:402
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:561
Point3 triangulateNonlinear(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, const Point3 &initialEstimate)
Given an initial estimate , refine a point using measurements in several cameras.
Definition: triangulation.h:156
std::pair< NonlinearFactorGraph, Values > triangulationGraph(const std::vector< Pose3 > &poses, boost::shared_ptr< CALIBRATION > sharedCal, const Point2Vector &measurements, Key landmarkKey, const Point3 &initialEstimate)
Create a factor graph with projection factors from poses and one calibration.
Definition: triangulation.h:81
double rankTolerance
threshold to decide whether triangulation is result.degenerate
Definition: triangulation.h:328
double z() const
get z
Definition: Point3.h:114
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian< 1, 3 > H1, OptionalJacobian< 1, 3 > H2)
distance between two points
Definition: Point3.cpp:84