| 
									
										
										
										
											2013-07-31 02:52:06 +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 triangulation.h | 
					
						
							|  |  |  |  * @brief Functions for triangulation | 
					
						
							|  |  |  |  * @date July 31, 2013 | 
					
						
							|  |  |  |  * @author Chris Beall | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-03-03 04:51:02 +08:00
										 |  |  | #include <gtsam_unstable/base/dllexport.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/geometry/TriangulationFactor.h>
 | 
					
						
							| 
									
										
										
										
											2014-03-03 02:34:43 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | #include <vector>
 | 
					
						
							| 
									
										
										
										
											2013-10-19 10:05:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  | /// Exception thrown by triangulateDLT when SVD returns rank < 3
 | 
					
						
							| 
									
										
										
										
											2013-11-06 00:06:10 +08:00
										 |  |  | class TriangulationUnderconstrainedException: public std::runtime_error { | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  | public: | 
					
						
							|  |  |  |   TriangulationUnderconstrainedException() : | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  |       std::runtime_error("Triangulation Underconstrained Exception.") { | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-20 04:25:04 +08:00
										 |  |  | /// Exception thrown by triangulateDLT when landmark is behind one or more of the cameras
 | 
					
						
							| 
									
										
										
										
											2013-11-06 00:06:10 +08:00
										 |  |  | class TriangulationCheiralityException: public std::runtime_error { | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  | public: | 
					
						
							|  |  |  |   TriangulationCheiralityException() : | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  |       std::runtime_error( | 
					
						
							|  |  |  |           "Triangulation Cheirality Exception: The resulting landmark is behind one or more cameras.") { | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-10-22 23:52:10 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |  * DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312 | 
					
						
							| 
									
										
										
										
											2013-10-22 23:52:10 +08:00
										 |  |  |  * @param projection_matrices Projection matrices (K*P^-1) | 
					
						
							|  |  |  |  * @param measurements 2D measurements | 
					
						
							|  |  |  |  * @param rank_tol SVD rank tolerance | 
					
						
							|  |  |  |  * @return Triangulated Point3 | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-03-03 02:34:43 +08:00
										 |  |  | GTSAM_UNSTABLE_EXPORT Point3 triangulateDLT( | 
					
						
							|  |  |  |     const std::vector<Matrix>& projection_matrices, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, double rank_tol); | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | ///
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create a factor graph with projection factors from poses and one calibration | 
					
						
							|  |  |  |  * @param poses Camera poses | 
					
						
							|  |  |  |  * @param sharedCal shared pointer to single calibration object | 
					
						
							|  |  |  |  * @param measurements 2D measurements | 
					
						
							|  |  |  |  * @param landmarkKey to refer to landmark | 
					
						
							|  |  |  |  * @param initialEstimate | 
					
						
							|  |  |  |  * @return graph and initial values | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | template<class CALIBRATION> | 
					
						
							|  |  |  | std::pair<NonlinearFactorGraph, Values> triangulationGraph( | 
					
						
							|  |  |  |     const std::vector<Pose3>& poses, boost::shared_ptr<CALIBRATION> sharedCal, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, Key landmarkKey, | 
					
						
							|  |  |  |     const Point3& initialEstimate) { | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   values.insert(landmarkKey, initialEstimate); // Initial landmark value
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); | 
					
						
							|  |  |  |   static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); | 
					
						
							|  |  |  |   for (size_t i = 0; i < measurements.size(); i++) { | 
					
						
							|  |  |  |     const Pose3& pose_i = poses[i]; | 
					
						
							| 
									
										
										
										
											2014-03-03 04:51:02 +08:00
										 |  |  |     PinholeCamera<CALIBRATION> camera_i(pose_i, *sharedCal); | 
					
						
							|  |  |  |     graph.push_back(TriangulationFactor<CALIBRATION> //
 | 
					
						
							|  |  |  |         (camera_i, measurements[i], unit2, landmarkKey)); | 
					
						
							| 
									
										
										
										
											2013-10-19 10:05:49 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   return std::make_pair(graph, values); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-10-19 10:05:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * Create a factor graph with projection factors from pinhole cameras | 
					
						
							|  |  |  |  * (each camera has a pose and calibration) | 
					
						
							|  |  |  |  * @param cameras pinhole cameras | 
					
						
							|  |  |  |  * @param measurements 2D measurements | 
					
						
							|  |  |  |  * @param landmarkKey to refer to landmark | 
					
						
							|  |  |  |  * @param initialEstimate | 
					
						
							|  |  |  |  * @return graph and initial values | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | template<class CALIBRATION> | 
					
						
							|  |  |  | std::pair<NonlinearFactorGraph, Values> triangulationGraph( | 
					
						
							|  |  |  |     const std::vector<PinholeCamera<CALIBRATION> >& cameras, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, Key landmarkKey, | 
					
						
							|  |  |  |     const Point3& initialEstimate) { | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   values.insert(landmarkKey, initialEstimate); // Initial landmark value
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); | 
					
						
							|  |  |  |   static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); | 
					
						
							|  |  |  |   for (size_t i = 0; i < measurements.size(); i++) { | 
					
						
							|  |  |  |     const PinholeCamera<CALIBRATION>& camera_i = cameras[i]; | 
					
						
							| 
									
										
										
										
											2014-03-03 04:51:02 +08:00
										 |  |  |     graph.push_back(TriangulationFactor<CALIBRATION> //
 | 
					
						
							|  |  |  |         (camera_i, measurements[i], unit2, landmarkKey)); | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   return std::make_pair(graph, values); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Optimize for triangulation | 
					
						
							|  |  |  |  * @param graph nonlinear factors for projection | 
					
						
							|  |  |  |  * @param values initial values | 
					
						
							|  |  |  |  * @param landmarkKey to refer to landmark | 
					
						
							|  |  |  |  * @return refined Point3 | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-03-03 02:34:43 +08:00
										 |  |  | GTSAM_UNSTABLE_EXPORT Point3 optimize(const NonlinearFactorGraph& graph, | 
					
						
							|  |  |  |     const Values& values, Key landmarkKey); | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Given an initial estimate , refine a point using measurements in several cameras | 
					
						
							|  |  |  |  * @param poses Camera poses | 
					
						
							|  |  |  |  * @param sharedCal shared pointer to single calibration object | 
					
						
							|  |  |  |  * @param measurements 2D measurements | 
					
						
							|  |  |  |  * @param initialEstimate | 
					
						
							|  |  |  |  * @return refined Point3 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | template<class CALIBRATION> | 
					
						
							|  |  |  | Point3 triangulateNonlinear(const std::vector<Pose3>& poses, | 
					
						
							|  |  |  |     boost::shared_ptr<CALIBRATION> sharedCal, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, const Point3& initialEstimate) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a factor graph and initial values
 | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   boost::tie(graph, values) = triangulationGraph(poses, sharedCal, measurements, | 
					
						
							|  |  |  |       Symbol('p', 0), initialEstimate); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return optimize(graph, values, Symbol('p', 0)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Given an initial estimate , refine a point using measurements in several cameras | 
					
						
							|  |  |  |  * @param cameras pinhole cameras | 
					
						
							|  |  |  |  * @param measurements 2D measurements | 
					
						
							|  |  |  |  * @param initialEstimate | 
					
						
							|  |  |  |  * @return refined Point3 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | template<class CALIBRATION> | 
					
						
							|  |  |  | Point3 triangulateNonlinear( | 
					
						
							|  |  |  |     const std::vector<PinholeCamera<CALIBRATION> >& cameras, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, const Point3& initialEstimate) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a factor graph and initial values
 | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   boost::tie(graph, values) = triangulationGraph(cameras, measurements, | 
					
						
							|  |  |  |       Symbol('p', 0), initialEstimate); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return optimize(graph, values, Symbol('p', 0)); | 
					
						
							| 
									
										
										
										
											2013-10-19 10:05:49 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-10-18 10:56:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * Function to triangulate 3D landmark point from an arbitrary number | 
					
						
							|  |  |  |  * of poses (at least 2) using the DLT. The function checks that the | 
					
						
							|  |  |  |  * resulting point lies in front of all cameras, but has no other checks | 
					
						
							|  |  |  |  * to verify the quality of the triangulation. | 
					
						
							|  |  |  |  * @param poses A vector of camera poses | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |  * @param sharedCal shared pointer to single calibration object | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  |  * @param measurements A vector of camera measurements | 
					
						
							| 
									
										
										
										
											2013-08-20 04:10:36 +08:00
										 |  |  |  * @param rank tolerance, default 1e-9 | 
					
						
							| 
									
										
										
										
											2013-10-22 23:31:46 +08:00
										 |  |  |  * @param optimize Flag to turn on nonlinear refinement of triangulation | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |  * @return Returns a Point3 | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  | template<class CALIBRATION> | 
					
						
							| 
									
										
										
										
											2013-10-29 12:24:14 +08:00
										 |  |  | Point3 triangulatePoint3(const std::vector<Pose3>& poses, | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |     boost::shared_ptr<CALIBRATION> sharedCal, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, double rank_tol = 1e-9, | 
					
						
							|  |  |  |     bool optimize = false) { | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  |   assert(poses.size() == measurements.size()); | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  |   if (poses.size() < 2) | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  |     throw(TriangulationUnderconstrainedException()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // construct projection matrices from poses & calibration
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   std::vector<Matrix> projection_matrices; | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  |   BOOST_FOREACH(const Pose3& pose, poses) { | 
					
						
							|  |  |  |     projection_matrices.push_back( | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |         sharedCal->K() * sub(pose.inverse().matrix(), 0, 3, 0, 4)); | 
					
						
							| 
									
										
										
										
											2013-10-16 08:54:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   // Triangulate linearly
 | 
					
						
							|  |  |  |   Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); | 
					
						
							| 
									
										
										
										
											2013-10-22 23:31:46 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   // The n refine using non-linear optimization
 | 
					
						
							|  |  |  |   if (optimize) | 
					
						
							|  |  |  |     point = triangulateNonlinear(poses, sharedCal, measurements, point); | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  | #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
 | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  |   // verify that the triangulated point lies infront of all cameras
 | 
					
						
							|  |  |  |   BOOST_FOREACH(const Pose3& pose, poses) { | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |     const Point3& p_local = pose.transform_to(point); | 
					
						
							|  |  |  |     if (p_local.z() <= 0) | 
					
						
							| 
									
										
										
										
											2014-03-03 02:34:43 +08:00
										 |  |  |     throw(TriangulationCheiralityException()); | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   return point; | 
					
						
							| 
									
										
										
										
											2013-10-16 06:43:10 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-10-22 23:31:46 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * Function to triangulate 3D landmark point from an arbitrary number | 
					
						
							|  |  |  |  * of poses (at least 2) using the DLT. This function is similar to the one | 
					
						
							|  |  |  |  * above, except that each camera has its own calibration. The function | 
					
						
							|  |  |  |  * checks that the resulting point lies in front of all cameras, but has | 
					
						
							|  |  |  |  * no other checks to verify the quality of the triangulation. | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |  * @param cameras pinhole cameras | 
					
						
							| 
									
										
										
										
											2013-10-22 23:31:46 +08:00
										 |  |  |  * @param measurements A vector of camera measurements | 
					
						
							|  |  |  |  * @param rank tolerance, default 1e-9 | 
					
						
							|  |  |  |  * @param optimize Flag to turn on nonlinear refinement of triangulation | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |  * @return Returns a Point3 | 
					
						
							| 
									
										
										
										
											2013-10-22 23:31:46 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | template<class CALIBRATION> | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | Point3 triangulatePoint3( | 
					
						
							|  |  |  |     const std::vector<PinholeCamera<CALIBRATION> >& cameras, | 
					
						
							|  |  |  |     const std::vector<Point2>& measurements, double rank_tol = 1e-9, | 
					
						
							|  |  |  |     bool optimize = false) { | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   size_t m = cameras.size(); | 
					
						
							|  |  |  |   assert(measurements.size()==m); | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   if (m < 2) | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  |     throw(TriangulationUnderconstrainedException()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // construct projection matrices from poses & calibration
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   typedef PinholeCamera<CALIBRATION> Camera; | 
					
						
							|  |  |  |   std::vector<Matrix> projection_matrices; | 
					
						
							|  |  |  |   BOOST_FOREACH(const Camera& camera, cameras) | 
					
						
							| 
									
										
										
										
											2014-03-03 04:51:02 +08:00
										 |  |  |     projection_matrices.push_back( | 
					
						
							|  |  |  |         camera.calibration().K() | 
					
						
							|  |  |  |             * sub(camera.pose().inverse().matrix(), 0, 3, 0, 4)); | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   // The n refine using non-linear optimization
 | 
					
						
							|  |  |  |   if (optimize) | 
					
						
							|  |  |  |     point = triangulateNonlinear(cameras, measurements, point); | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
 | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  |   // verify that the triangulated point lies infront of all cameras
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   BOOST_FOREACH(const Camera& camera, cameras) { | 
					
						
							|  |  |  |     const Point3& p_local = camera.pose().transform_to(point); | 
					
						
							| 
									
										
										
										
											2013-11-01 09:04:34 +08:00
										 |  |  |     if (p_local.z() <= 0) | 
					
						
							| 
									
										
										
										
											2014-03-03 02:34:43 +08:00
										 |  |  |     throw(TriangulationCheiralityException()); | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-06 14:31:46 +08:00
										 |  |  |   return point; | 
					
						
							| 
									
										
										
										
											2013-10-16 02:01:06 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-07-31 02:52:06 +08:00
										 |  |  | } // \namespace gtsam
 | 
					
						
							|  |  |  | 
 |