| 
									
										
										
										
											2014-06-03 23:21:11 +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   SmartStereoProjectionFactor.h | 
					
						
							|  |  |  |  * @brief  Base class to create smart factors on poses or cameras | 
					
						
							|  |  |  |  * @author Luca Carlone | 
					
						
							|  |  |  |  * @author Zsolt Kira | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-18 08:53:21 +08:00
										 |  |  | #include <gtsam/slam/SmartFactorBase.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/triangulation.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  | #include <gtsam/geometry/StereoCamera.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/optional.hpp>
 | 
					
						
							|  |  |  | #include <boost/make_shared.hpp>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Structure for storing some state memory, used to speed up optimization | 
					
						
							|  |  |  |  * @addtogroup SLAM | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | class SmartStereoProjectionFactorState { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | protected: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-01 20:40:27 +08:00
										 |  |  |   EIGEN_MAKE_ALIGNED_OPERATOR_NEW | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   SmartStereoProjectionFactorState() { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   // Hessian representation (after Schur complement)
 | 
					
						
							|  |  |  |   bool calculatedHessian; | 
					
						
							|  |  |  |   Matrix H; | 
					
						
							|  |  |  |   Vector gs_vector; | 
					
						
							|  |  |  |   std::vector<Matrix> Gs; | 
					
						
							|  |  |  |   std::vector<Vector> gs; | 
					
						
							|  |  |  |   double f; | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | enum LinearizationMode { | 
					
						
							|  |  |  |   HESSIAN, JACOBIAN_SVD, JACOBIAN_Q | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * SmartStereoProjectionFactor: triangulates point | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | template<class CALIBRATION, size_t D> | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | class SmartStereoProjectionFactor: public SmartFactorBase<StereoCamera> { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | protected: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Some triangulation parameters
 | 
					
						
							|  |  |  |   const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_
 | 
					
						
							|  |  |  |   const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate
 | 
					
						
							|  |  |  |   mutable std::vector<Pose3> cameraPosesTriangulation_; ///< current triangulation poses
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   const bool enableEPI_; ///< if set to true, will refine triangulation using LM
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   const double linearizationThreshold_; ///< threshold to decide whether to re-linearize
 | 
					
						
							|  |  |  |   mutable std::vector<Pose3> cameraPosesLinearization_; ///< current linearization poses
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   mutable Point3 point_; ///< Current estimate of the 3D point
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   mutable bool degenerate_; | 
					
						
							|  |  |  |   mutable bool cheiralityException_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // verbosity handling for Cheirality Exceptions
 | 
					
						
							|  |  |  |   const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false)
 | 
					
						
							|  |  |  |   const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false)
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   boost::shared_ptr<SmartStereoProjectionFactorState> state_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for smart projection factor state variable
 | 
					
						
							|  |  |  |   typedef boost::shared_ptr<SmartStereoProjectionFactorState> SmartFactorStatePtr; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for base class type
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |   typedef SmartFactorBase<StereoCamera> Base; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   double landmarkDistanceThreshold_; // if the landmark is triangulated at a
 | 
					
						
							|  |  |  |   // distance larger than that the factor is considered degenerate
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the
 | 
					
						
							|  |  |  |   // average reprojection error is smaller than this threshold after triangulation,
 | 
					
						
							|  |  |  |   // and the factor is disregarded if the error is large
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for this class
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   typedef SmartStereoProjectionFactor<CALIBRATION, D> This; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-23 06:41:42 +08:00
										 |  |  |   enum {ZDim = 3};    ///< Dimension trait of measurement type
 | 
					
						
							| 
									
										
										
										
											2014-11-18 08:10:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for a smart pointer to a factor
 | 
					
						
							|  |  |  |   typedef boost::shared_ptr<This> shared_ptr; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-10 08:39:04 +08:00
										 |  |  |   /// shorthand for a StereoCamera // TODO: Get rid of this?
 | 
					
						
							| 
									
										
										
										
											2014-06-05 21:25:06 +08:00
										 |  |  |   typedef StereoCamera Camera; | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-10 08:39:04 +08:00
										 |  |  |   /// Vector of cameras
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   typedef CameraSet<Camera> Cameras; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Constructor | 
					
						
							|  |  |  |    * @param rankTol tolerance used to check if point triangulation is degenerate | 
					
						
							|  |  |  |    * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) | 
					
						
							|  |  |  |    * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, | 
					
						
							|  |  |  |    * otherwise the factor is simply neglected | 
					
						
							|  |  |  |    * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations | 
					
						
							|  |  |  |    * @param body_P_sensor is the transform from body to sensor frame (default identity) | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   SmartStereoProjectionFactor(const double rankTol, const double linThreshold, | 
					
						
							|  |  |  |       const bool manageDegeneracy, const bool enableEPI, | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |       boost::optional<Pose3> body_P_sensor = boost::none, | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |       double landmarkDistanceThreshold = 1e10, | 
					
						
							|  |  |  |       double dynamicOutlierRejectionThreshold = -1, | 
					
						
							|  |  |  |       SmartFactorStatePtr state = SmartFactorStatePtr(new SmartStereoProjectionFactorState())) : | 
					
						
							|  |  |  |       Base(body_P_sensor), rankTolerance_(rankTol), retriangulationThreshold_( | 
					
						
							|  |  |  |           1e-5), manageDegeneracy_(manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( | 
					
						
							|  |  |  |           linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( | 
					
						
							|  |  |  |           false), verboseCheirality_(false), state_(state), | 
					
						
							|  |  |  |           landmarkDistanceThreshold_(landmarkDistanceThreshold), | 
					
						
							|  |  |  |           dynamicOutlierRejectionThreshold_(dynamicOutlierRejectionThreshold) { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Virtual destructor */ | 
					
						
							|  |  |  |   virtual ~SmartStereoProjectionFactor() { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * print | 
					
						
							|  |  |  |    * @param s optional string naming the factor | 
					
						
							|  |  |  |    * @param keyFormatter optional formatter useful for printing Symbols | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   void print(const std::string& s = "", const KeyFormatter& keyFormatter = | 
					
						
							|  |  |  |       DefaultKeyFormatter) const { | 
					
						
							|  |  |  |     std::cout << s << "SmartStereoProjectionFactor, z = \n"; | 
					
						
							|  |  |  |     std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; | 
					
						
							|  |  |  |     std::cout << "degenerate_ = " << degenerate_ << std::endl; | 
					
						
							|  |  |  |     std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; | 
					
						
							| 
									
										
										
										
											2014-07-23 10:03:04 +08:00
										 |  |  |     std::cout << "linearizationThreshold_ = " << linearizationThreshold_ << std::endl; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     Base::print("", keyFormatter); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Check if the new linearization point_ is the same as the one used for previous triangulation
 | 
					
						
							|  |  |  |   bool decideIfTriangulate(const Cameras& cameras) const { | 
					
						
							|  |  |  |     // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate
 | 
					
						
							|  |  |  |     // Note that this is not yet "selecting linearization", that will come later, and we only check if the
 | 
					
						
							|  |  |  |     // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     size_t m = cameras.size(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     bool retriangulate = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // if we do not have a previous linearization point_ or the new linearization point_ includes more poses
 | 
					
						
							|  |  |  |     if (cameraPosesTriangulation_.empty() | 
					
						
							|  |  |  |         || cameras.size() != cameraPosesTriangulation_.size()) | 
					
						
							|  |  |  |       retriangulate = true; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (!retriangulate) { | 
					
						
							|  |  |  |       for (size_t i = 0; i < cameras.size(); i++) { | 
					
						
							|  |  |  |         if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], | 
					
						
							|  |  |  |             retriangulationThreshold_)) { | 
					
						
							|  |  |  |           retriangulate = true; // at least two poses are different, hence we retriangulate
 | 
					
						
							|  |  |  |           break; | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (retriangulate) { // we store the current poses used for triangulation
 | 
					
						
							|  |  |  |       cameraPosesTriangulation_.clear(); | 
					
						
							|  |  |  |       cameraPosesTriangulation_.reserve(m); | 
					
						
							|  |  |  |       for (size_t i = 0; i < m; i++) | 
					
						
							|  |  |  |         // cameraPosesTriangulation_[i] = cameras[i].pose();
 | 
					
						
							|  |  |  |         cameraPosesTriangulation_.push_back(cameras[i].pose()); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// This function checks if the new linearization point_ is 'close'  to the previous one used for linearization
 | 
					
						
							|  |  |  |   bool decideIfLinearize(const Cameras& cameras) const { | 
					
						
							|  |  |  |     // "selective linearization"
 | 
					
						
							|  |  |  |     // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose
 | 
					
						
							|  |  |  |     // (we only care about the "rigidity" of the poses, not about their absolute pose)
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (this->linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize
 | 
					
						
							|  |  |  |       return true; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // if we do not have a previous linearization point_ or the new linearization point_ includes more poses
 | 
					
						
							|  |  |  |     if (cameraPosesLinearization_.empty() | 
					
						
							|  |  |  |         || (cameras.size() != cameraPosesLinearization_.size())) | 
					
						
							|  |  |  |       return true; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     Pose3 firstCameraPose, firstCameraPoseOld; | 
					
						
							|  |  |  |     for (size_t i = 0; i < cameras.size(); i++) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       if (i == 0) { // we store the initial pose, this is useful for selective re-linearization
 | 
					
						
							|  |  |  |         firstCameraPose = cameras[i].pose(); | 
					
						
							|  |  |  |         firstCameraPoseOld = cameraPosesLinearization_[i]; | 
					
						
							|  |  |  |         continue; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // we compare the poses in the frame of the first pose
 | 
					
						
							|  |  |  |       Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); | 
					
						
							|  |  |  |       Pose3 localCameraPoseOld = firstCameraPoseOld.between( | 
					
						
							|  |  |  |           cameraPosesLinearization_[i]); | 
					
						
							|  |  |  |       if (!localCameraPose.equals(localCameraPoseOld, | 
					
						
							|  |  |  |           this->linearizationThreshold_)) | 
					
						
							|  |  |  |         return true; // at least two "relative" poses are different, hence we re-linearize
 | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return false; // if we arrive to this point_ all poses are the same and we don't need re-linearize
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// triangulateSafe
 | 
					
						
							|  |  |  |   size_t triangulateSafe(const Values& values) const { | 
					
						
							|  |  |  |     return triangulateSafe(this->cameras(values)); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// triangulateSafe
 | 
					
						
							|  |  |  |   size_t triangulateSafe(const Cameras& cameras) const { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     size_t m = cameras.size(); | 
					
						
							|  |  |  |     if (m < 2) { // if we have a single pose the corresponding factor is uninformative
 | 
					
						
							|  |  |  |       degenerate_ = true; | 
					
						
							|  |  |  |       return m; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     bool retriangulate = decideIfTriangulate(cameras); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (retriangulate) { | 
					
						
							|  |  |  |       // We triangulate the 3D position of the landmark
 | 
					
						
							|  |  |  |       try { | 
					
						
							|  |  |  |         // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl;
 | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         //TODO: Chris will replace this with something else for stereo
 | 
					
						
							|  |  |  | //        point_ = triangulatePoint3<CALIBRATION>(cameras, this->measured_,
 | 
					
						
							|  |  |  | //            rankTolerance_, enableEPI_);
 | 
					
						
							| 
									
										
										
										
											2014-06-10 04:29:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  |         // // // Temporary hack to use monocular triangulation
 | 
					
						
							|  |  |  |         std::vector<Point2> mono_measurements; | 
					
						
							|  |  |  |         BOOST_FOREACH(const StereoPoint2& sp, this->measured_) { | 
					
						
							|  |  |  |           mono_measurements.push_back(sp.point2()); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         std::vector<PinholeCamera<Cal3_S2> > mono_cameras; | 
					
						
							|  |  |  |         BOOST_FOREACH(const Camera& camera, cameras) { | 
					
						
							|  |  |  |           const Pose3& pose = camera.pose(); | 
					
						
							|  |  |  |           const Cal3_S2& K = camera.calibration()->calibration(); | 
					
						
							|  |  |  |           mono_cameras.push_back(PinholeCamera<Cal3_S2>(pose, K)); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |         point_ = triangulatePoint3<Cal3_S2>(mono_cameras, mono_measurements, | 
					
						
							|  |  |  |             rankTolerance_, enableEPI_); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // // // End temporary hack
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-10 04:29:32 +08:00
										 |  |  |         // FIXME: temporary: triangulation using only first camera
 | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  | //        const StereoPoint2& z0 = this->measured_.at(0);
 | 
					
						
							|  |  |  | //        point_ = cameras[0].backproject(z0);
 | 
					
						
							| 
									
										
										
										
											2014-06-10 04:29:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |         degenerate_ = false; | 
					
						
							|  |  |  |         cheiralityException_ = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // Check landmark distance and reprojection errors to avoid outliers
 | 
					
						
							|  |  |  |         double totalReprojError = 0.0; | 
					
						
							|  |  |  |         size_t i=0; | 
					
						
							|  |  |  |         BOOST_FOREACH(const Camera& camera, cameras) { | 
					
						
							|  |  |  |           Point3 cameraTranslation = camera.pose().translation(); | 
					
						
							|  |  |  |           // we discard smart factors corresponding to points that are far away
 | 
					
						
							|  |  |  |           if(cameraTranslation.distance(point_) > landmarkDistanceThreshold_){ | 
					
						
							|  |  |  |             degenerate_ = true; | 
					
						
							|  |  |  |             break; | 
					
						
							|  |  |  |           } | 
					
						
							| 
									
										
										
										
											2014-06-05 21:25:06 +08:00
										 |  |  |           const StereoPoint2& zi = this->measured_.at(i); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |           try { | 
					
						
							| 
									
										
										
										
											2014-06-05 21:25:06 +08:00
										 |  |  |             StereoPoint2 reprojectionError(camera.project(point_) - zi); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |             totalReprojError += reprojectionError.vector().norm(); | 
					
						
							|  |  |  |           } catch (CheiralityException) { | 
					
						
							|  |  |  |             cheiralityException_ = true; | 
					
						
							|  |  |  |           } | 
					
						
							|  |  |  |           i += 1; | 
					
						
							|  |  |  |         } | 
					
						
							| 
									
										
										
										
											2014-07-15 22:14:23 +08:00
										 |  |  |         //std::cout << "totalReprojError error: " << totalReprojError << std::endl;
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |         // we discard smart factors that have large reprojection error
 | 
					
						
							|  |  |  |         if(dynamicOutlierRejectionThreshold_ > 0 && | 
					
						
							|  |  |  |             totalReprojError/m > dynamicOutlierRejectionThreshold_) | 
					
						
							|  |  |  |           degenerate_ = true; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       } catch (TriangulationUnderconstrainedException&) { | 
					
						
							|  |  |  |         // if TriangulationUnderconstrainedException can be
 | 
					
						
							|  |  |  |         // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before
 | 
					
						
							|  |  |  |         // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark)
 | 
					
						
							|  |  |  |         // in the second case we want to use a rotation-only smart factor
 | 
					
						
							|  |  |  |         degenerate_ = true; | 
					
						
							|  |  |  |         cheiralityException_ = false; | 
					
						
							|  |  |  |       } catch (TriangulationCheiralityException&) { | 
					
						
							|  |  |  |         // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers
 | 
					
						
							|  |  |  |         // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint
 | 
					
						
							|  |  |  |         cheiralityException_ = true; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return m; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// triangulate
 | 
					
						
							|  |  |  |   bool triangulateForLinearize(const Cameras& cameras) const { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     bool isDebug = false; | 
					
						
							|  |  |  |     size_t nrCameras = this->triangulateSafe(cameras); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (nrCameras < 2 | 
					
						
							|  |  |  |         || (!this->manageDegeneracy_ | 
					
						
							|  |  |  |             && (this->cheiralityException_ || this->degenerate_))) { | 
					
						
							|  |  |  |       if (isDebug) { | 
					
						
							|  |  |  |         std::cout << "createImplicitSchurFactor: degenerate configuration" | 
					
						
							|  |  |  |             << std::endl; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |       return false; | 
					
						
							|  |  |  |     } else { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // instead, if we want to manage the exception..
 | 
					
						
							|  |  |  |       if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors
 | 
					
						
							|  |  |  |         this->degenerate_ = true; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |       return true; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// linearize returns a Hessianfactor that is an approximation of error(p)
 | 
					
						
							|  |  |  |   boost::shared_ptr<RegularHessianFactor<D> > createHessianFactor( | 
					
						
							|  |  |  |       const Cameras& cameras, const double lambda = 0.0) const { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     bool isDebug = false; | 
					
						
							|  |  |  |     size_t numKeys = this->keys_.size(); | 
					
						
							|  |  |  |     // Create structures for Hessian Factors
 | 
					
						
							|  |  |  |     std::vector < Key > js; | 
					
						
							|  |  |  |     std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); | 
					
						
							|  |  |  |     std::vector < Vector > gs(numKeys); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (this->measured_.size() != cameras.size()) { | 
					
						
							|  |  |  |       std::cout | 
					
						
							|  |  |  |           << "SmartProjectionHessianFactor: this->measured_.size() inconsistent with input" | 
					
						
							|  |  |  |           << std::endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     this->triangulateSafe(cameras); | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  |     if (isDebug) std::cout << "point_ = " << point_ << std::endl; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (numKeys < 2 | 
					
						
							|  |  |  |         || (!this->manageDegeneracy_ | 
					
						
							|  |  |  |             && (this->cheiralityException_ || this->degenerate_))) { | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  |       if (isDebug) std::cout << "In linearize: exception" << std::endl; | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |       BOOST_FOREACH(Matrix& m, Gs) | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |         m = zeros(D, D); | 
					
						
							|  |  |  |       BOOST_FOREACH(Vector& v, gs) | 
					
						
							|  |  |  |         v = zero(D); | 
					
						
							|  |  |  |       return boost::make_shared<RegularHessianFactor<D> >(this->keys_, Gs, gs, | 
					
						
							|  |  |  |           0.0); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // instead, if we want to manage the exception..
 | 
					
						
							|  |  |  |     if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors
 | 
					
						
							|  |  |  |       this->degenerate_ = true; | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  |       if (isDebug) std::cout << "degenerate_ = true" << std::endl; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     bool doLinearize = this->decideIfLinearize(cameras); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  |     if (isDebug) std::cout << "doLinearize = " << doLinearize << std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize
 | 
					
						
							|  |  |  |       for (size_t i = 0; i < cameras.size(); i++) | 
					
						
							|  |  |  |         this->cameraPosesLinearization_[i] = cameras[i].pose(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (!doLinearize) { // return the previous Hessian factor
 | 
					
						
							|  |  |  |       std::cout << "=============================" << std::endl; | 
					
						
							|  |  |  |       std::cout << "doLinearize " << doLinearize << std::endl; | 
					
						
							|  |  |  |       std::cout << "this->linearizationThreshold_ " | 
					
						
							|  |  |  |           << this->linearizationThreshold_ << std::endl; | 
					
						
							|  |  |  |       std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; | 
					
						
							|  |  |  |       std::cout | 
					
						
							|  |  |  |           << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" | 
					
						
							|  |  |  |           << std::endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |       return boost::make_shared<RegularHessianFactor<D> >(this->keys_, | 
					
						
							|  |  |  |           this->state_->Gs, this->state_->gs, this->state_->f); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // ==================================================================
 | 
					
						
							|  |  |  |     Matrix F, E; | 
					
						
							|  |  |  |     Vector b; | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |     double f = computeJacobians(F, E, b, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Schur complement trick
 | 
					
						
							|  |  |  |     // Frank says: should be possible to do this more efficiently?
 | 
					
						
							|  |  |  |     // And we care, as in grouped factors this is called repeatedly
 | 
					
						
							|  |  |  |     Matrix H(D * numKeys, D * numKeys); | 
					
						
							|  |  |  |     Vector gs_vector; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |     Matrix3 P = Base::PointCov(E,lambda); | 
					
						
							|  |  |  |     H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); | 
					
						
							|  |  |  |     gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); | 
					
						
							| 
									
										
										
										
											2014-07-10 20:48:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (isDebug) std::cout << "gs_vector size " << gs_vector.size() << std::endl; | 
					
						
							|  |  |  |     if (isDebug) std::cout << "H:\n" << H << std::endl; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Populate Gs and gs
 | 
					
						
							|  |  |  |     int GsCount2 = 0; | 
					
						
							|  |  |  |     for (DenseIndex i1 = 0; i1 < (DenseIndex)numKeys; i1++) { // for each camera
 | 
					
						
							|  |  |  |       DenseIndex i1D = i1 * D; | 
					
						
							|  |  |  |       gs.at(i1) = gs_vector.segment < D > (i1D); | 
					
						
							|  |  |  |       for (DenseIndex i2 = 0; i2 < (DenseIndex)numKeys; i2++) { | 
					
						
							|  |  |  |         if (i2 >= i1) { | 
					
						
							|  |  |  |           Gs.at(GsCount2) = H.block < D, D > (i1D, i2 * D); | 
					
						
							|  |  |  |           GsCount2++; | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     // ==================================================================
 | 
					
						
							|  |  |  |     if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables
 | 
					
						
							|  |  |  |       this->state_->Gs = Gs; | 
					
						
							|  |  |  |       this->state_->gs = gs; | 
					
						
							|  |  |  |       this->state_->f = f; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return boost::make_shared<RegularHessianFactor<D> >(this->keys_, Gs, gs, f); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //  // create factor
 | 
					
						
							|  |  |  | //  boost::shared_ptr<ImplicitSchurFactor<D> > createImplicitSchurFactor(
 | 
					
						
							|  |  |  | //      const Cameras& cameras, double lambda) const {
 | 
					
						
							|  |  |  | //    if (triangulateForLinearize(cameras))
 | 
					
						
							|  |  |  | //      return Base::createImplicitSchurFactor(cameras, point_, lambda);
 | 
					
						
							|  |  |  | //    else
 | 
					
						
							|  |  |  | //      return boost::shared_ptr<ImplicitSchurFactor<D> >();
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// create factor
 | 
					
						
							|  |  |  | //  boost::shared_ptr<JacobianFactorQ<D> > createJacobianQFactor(
 | 
					
						
							|  |  |  | //      const Cameras& cameras, double lambda) const {
 | 
					
						
							|  |  |  | //    if (triangulateForLinearize(cameras))
 | 
					
						
							|  |  |  | //      return Base::createJacobianQFactor(cameras, point_, lambda);
 | 
					
						
							|  |  |  | //    else
 | 
					
						
							|  |  |  | //      return boost::make_shared< JacobianFactorQ<D> >(this->keys_);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// Create a factor, takes values
 | 
					
						
							|  |  |  | //  boost::shared_ptr<JacobianFactorQ<D> > createJacobianQFactor(
 | 
					
						
							|  |  |  | //      const Values& values, double lambda) const {
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | //    Cameras cameras;
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    // TODO triangulate twice ??
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | //    bool nonDegenerate = computeCamerasAndTriangulate(values, cameras);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    if (nonDegenerate)
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | //      return createJacobianQFactor(cameras, lambda);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    else
 | 
					
						
							|  |  |  | //      return boost::make_shared< JacobianFactorQ<D> >(this->keys_);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |   /// different (faster) way to compute Jacobian factor
 | 
					
						
							|  |  |  |   boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, | 
					
						
							|  |  |  |       double lambda) const { | 
					
						
							|  |  |  |     if (triangulateForLinearize(cameras)) | 
					
						
							|  |  |  |       return Base::createJacobianSVDFactor(cameras, point_, lambda); | 
					
						
							|  |  |  |     else | 
					
						
							| 
									
										
										
										
											2014-12-21 03:36:54 +08:00
										 |  |  |       return boost::make_shared< JacobianFactorSVD<D, ZDim> >(this->keys_); | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Returns true if nonDegenerate
 | 
					
						
							|  |  |  |   bool computeCamerasAndTriangulate(const Values& values, | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |       Cameras& cameras) const { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     Values valuesFactor; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Select only the cameras
 | 
					
						
							|  |  |  |     BOOST_FOREACH(const Key key, this->keys_) | 
					
						
							|  |  |  |       valuesFactor.insert(key, values.at(key)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |     cameras = this->cameras(valuesFactor); | 
					
						
							|  |  |  |     size_t nrCameras = this->triangulateSafe(cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (nrCameras < 2 | 
					
						
							|  |  |  |         || (!this->manageDegeneracy_ | 
					
						
							|  |  |  |             && (this->cheiralityException_ || this->degenerate_))) | 
					
						
							|  |  |  |       return false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // instead, if we want to manage the exception..
 | 
					
						
							|  |  |  |     if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors
 | 
					
						
							|  |  |  |       this->degenerate_ = true; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (this->degenerate_) { | 
					
						
							|  |  |  |       std::cout << "SmartStereoProjectionFactor: this is not ready" << std::endl; | 
					
						
							|  |  |  |       std::cout << "this->cheiralityException_ " << this->cheiralityException_ | 
					
						
							|  |  |  |           << std::endl; | 
					
						
							|  |  |  |       std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return true; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   /// Assumes non-degenerate !
 | 
					
						
							|  |  |  |   void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras) const { | 
					
						
							|  |  |  |     Base::computeEP(E, PointCov, cameras, point_); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   /// Takes values
 | 
					
						
							|  |  |  |   bool computeEP(Matrix& E, Matrix& PointCov, const Values& values) const { | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |     Cameras cameras; | 
					
						
							|  |  |  |     bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (nonDegenerate) | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |       computeEP(E, PointCov, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     return nonDegenerate; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Version that takes values, and creates the point
 | 
					
						
							|  |  |  |   bool computeJacobians(std::vector<typename Base::KeyMatrix2D>& Fblocks, | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |       Matrix& E, Vector& b, const Values& values) const { | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |     Cameras cameras; | 
					
						
							|  |  |  |     bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (nonDegenerate) | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |       computeJacobians(Fblocks, E, b, cameras, 0.0); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     return nonDegenerate; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Compute F, E only (called below in both vanilla and SVD versions)
 | 
					
						
							|  |  |  |   /// Assumes the point has been computed
 | 
					
						
							|  |  |  |   /// Note E can be 2m*3 or 2m*2, in case point is degenerate
 | 
					
						
							|  |  |  |   double computeJacobians(std::vector<typename Base::KeyMatrix2D>& Fblocks, | 
					
						
							|  |  |  |       Matrix& E, Vector& b, const Cameras& cameras) const { | 
					
						
							|  |  |  |     if (this->degenerate_) { | 
					
						
							| 
									
										
										
										
											2014-06-05 23:01:23 +08:00
										 |  |  |       throw("FIXME: computeJacobians degenerate case commented out!"); | 
					
						
							|  |  |  | //      std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl;
 | 
					
						
							|  |  |  | //      std::cout << "point " << point_ << std::endl;
 | 
					
						
							|  |  |  | //      std::cout
 | 
					
						
							|  |  |  | //          << "SmartStereoProjectionFactor: Management of degeneracy is disabled - not ready to be used"
 | 
					
						
							|  |  |  | //          << std::endl;
 | 
					
						
							|  |  |  | //      if (D > 6) {
 | 
					
						
							|  |  |  | //        std::cout
 | 
					
						
							|  |  |  | //            << "Management of degeneracy is not yet ready when one also optimizes for the calibration "
 | 
					
						
							|  |  |  | //            << std::endl;
 | 
					
						
							|  |  |  | //      }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //      int numKeys = this->keys_.size();
 | 
					
						
							|  |  |  | //      E = zeros(2 * numKeys, 2);
 | 
					
						
							|  |  |  | //      b = zero(2 * numKeys);
 | 
					
						
							|  |  |  | //      double f = 0;
 | 
					
						
							|  |  |  | //      for (size_t i = 0; i < this->measured_.size(); i++) {
 | 
					
						
							|  |  |  | //        if (i == 0) { // first pose
 | 
					
						
							|  |  |  | //          this->point_ = cameras[i].backprojectPointAtInfinity(
 | 
					
						
							|  |  |  | //              this->measured_.at(i));
 | 
					
						
							|  |  |  | //          // 3D parametrization of point at infinity: [px py 1]
 | 
					
						
							|  |  |  | //        }
 | 
					
						
							|  |  |  | //        Matrix Fi, Ei;
 | 
					
						
							|  |  |  | //        Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei)
 | 
					
						
							|  |  |  | //            - this->measured_.at(i)).vector();
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //        this->noise_.at(i)->WhitenSystem(Fi, Ei, bi);
 | 
					
						
							|  |  |  | //        f += bi.squaredNorm();
 | 
					
						
							|  |  |  | //        Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi));
 | 
					
						
							|  |  |  | //        E.block < 2, 2 > (2 * i, 0) = Ei;
 | 
					
						
							|  |  |  | //        subInsert(b, bi, 2 * i);
 | 
					
						
							|  |  |  | //      }
 | 
					
						
							|  |  |  | //      return f;
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } else { | 
					
						
							|  |  |  |       // nondegenerate: just return Base version
 | 
					
						
							|  |  |  |       return Base::computeJacobians(Fblocks, E, b, cameras, point_); | 
					
						
							|  |  |  |     } // end else
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //  /// Version that computes PointCov, with optional lambda parameter
 | 
					
						
							|  |  |  | //  double computeJacobians(std::vector<typename Base::KeyMatrix2D>& Fblocks,
 | 
					
						
							|  |  |  | //      Matrix& E, Matrix& PointCov, Vector& b, const Cameras& cameras,
 | 
					
						
							|  |  |  | //      const double lambda = 0.0) const {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //    double f = computeJacobians(Fblocks, E, b, cameras);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //    // Point covariance inv(E'*E)
 | 
					
						
							|  |  |  | //    PointCov.noalias() = (E.transpose() * E + lambda * eye(E.cols())).inverse();
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //    return f;
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// takes values
 | 
					
						
							|  |  |  | //  bool computeJacobiansSVD(std::vector<typename Base::KeyMatrix2D>& Fblocks,
 | 
					
						
							|  |  |  | //      Matrix& Enull, Vector& b, const Values& values) const {
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | //    typename Base::Cameras cameras;
 | 
					
						
							|  |  |  | //    double good = computeCamerasAndTriangulate(values, cameras);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    if (good)
 | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  | //      computeJacobiansSVD(Fblocks, Enull, b, cameras);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    return true;
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// SVD version
 | 
					
						
							|  |  |  | //  double computeJacobiansSVD(std::vector<typename Base::KeyMatrix2D>& Fblocks,
 | 
					
						
							|  |  |  | //      Matrix& Enull, Vector& b, const Cameras& cameras) const {
 | 
					
						
							|  |  |  | //    return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// Returns Matrix, TODO: maybe should not exist -> not sparse !
 | 
					
						
							|  |  |  | //  // TODO should there be a lambda?
 | 
					
						
							|  |  |  | //  double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b,
 | 
					
						
							|  |  |  | //      const Cameras& cameras) const {
 | 
					
						
							|  |  |  | //    return Base::computeJacobiansSVD(F, Enull, b, cameras, point_);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Returns Matrix, TODO: maybe should not exist -> not sparse !
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   double computeJacobians(Matrix& F, Matrix& E, Vector& b, | 
					
						
							|  |  |  |       const Cameras& cameras) const { | 
					
						
							|  |  |  |     return Base::computeJacobians(F, E, b, cameras, point_); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Calculate vector of re-projection errors, before applying noise model
 | 
					
						
							| 
									
										
										
										
											2015-02-25 08:14:36 +08:00
										 |  |  |   Vector reprojectionErrorAfterTriangulation(const Values& values) const { | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |     Cameras cameras; | 
					
						
							|  |  |  |     bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (nonDegenerate) | 
					
						
							| 
									
										
										
										
											2015-02-25 08:14:36 +08:00
										 |  |  |       return Base::reprojectionError(cameras, point_); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     else | 
					
						
							| 
									
										
										
										
											2015-02-23 19:43:43 +08:00
										 |  |  |       return zero(cameras.size() * 3); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Calculate the error of the factor. | 
					
						
							|  |  |  |    * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. | 
					
						
							|  |  |  |    * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model | 
					
						
							|  |  |  |    * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   double totalReprojectionError(const Cameras& cameras, | 
					
						
							|  |  |  |       boost::optional<Point3> externalPoint = boost::none) const { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     size_t nrCameras; | 
					
						
							|  |  |  |     if (externalPoint) { | 
					
						
							|  |  |  |       nrCameras = this->keys_.size(); | 
					
						
							|  |  |  |       point_ = *externalPoint; | 
					
						
							|  |  |  |       degenerate_ = false; | 
					
						
							|  |  |  |       cheiralityException_ = false; | 
					
						
							|  |  |  |     } else { | 
					
						
							|  |  |  |       nrCameras = this->triangulateSafe(cameras); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (nrCameras < 2 | 
					
						
							|  |  |  |         || (!this->manageDegeneracy_ | 
					
						
							|  |  |  |             && (this->cheiralityException_ || this->degenerate_))) { | 
					
						
							|  |  |  |       // if we don't want to manage the exceptions we discard the factor
 | 
					
						
							|  |  |  |       // std::cout << "In error evaluation: exception" << std::endl;
 | 
					
						
							|  |  |  |       return 0.0; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors
 | 
					
						
							|  |  |  |       std::cout | 
					
						
							|  |  |  |           << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" | 
					
						
							|  |  |  |           << std::endl; | 
					
						
							|  |  |  |       this->degenerate_ = true; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (this->degenerate_) { | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  |        return 0.0; // TODO: this maybe should be zero?
 | 
					
						
							|  |  |  | //      std::cout
 | 
					
						
							|  |  |  | //          << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!"
 | 
					
						
							|  |  |  | //          << std::endl;
 | 
					
						
							|  |  |  | //      size_t i = 0;
 | 
					
						
							|  |  |  | //      double overallError = 0;
 | 
					
						
							|  |  |  | //      BOOST_FOREACH(const Camera& camera, cameras) {
 | 
					
						
							| 
									
										
										
										
											2014-06-05 21:25:06 +08:00
										 |  |  | //        const StereoPoint2& zi = this->measured_.at(i);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  | //        if (i == 0) // first pose
 | 
					
						
							|  |  |  | //          this->point_ = camera.backprojectPointAtInfinity(zi); // 3D parametrization of point at infinity
 | 
					
						
							| 
									
										
										
										
											2014-06-05 21:25:06 +08:00
										 |  |  | //        StereoPoint2 reprojectionError(
 | 
					
						
							| 
									
										
										
										
											2014-06-04 05:11:01 +08:00
										 |  |  | //            camera.projectPointAtInfinity(this->point_) - zi);
 | 
					
						
							|  |  |  | //        overallError += 0.5
 | 
					
						
							|  |  |  | //            * this->noise_.at(i)->distance(reprojectionError.vector());
 | 
					
						
							|  |  |  | //        i += 1;
 | 
					
						
							|  |  |  | //      }
 | 
					
						
							|  |  |  | //      return overallError;
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } else { | 
					
						
							|  |  |  |       // Just use version in base class
 | 
					
						
							|  |  |  |       return Base::totalReprojectionError(cameras, point_); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Cameras are computed in derived class
 | 
					
						
							|  |  |  |   virtual Cameras cameras(const Values& values) const = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return the landmark */ | 
					
						
							|  |  |  |   boost::optional<Point3> point() const { | 
					
						
							|  |  |  |     return point_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** COMPUTE the landmark */ | 
					
						
							|  |  |  |   boost::optional<Point3> point(const Values& values) const { | 
					
						
							|  |  |  |     triangulateSafe(values); | 
					
						
							|  |  |  |     return point_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return the degenerate state */ | 
					
						
							|  |  |  |   inline bool isDegenerate() const { | 
					
						
							|  |  |  |     return (cheiralityException_ || degenerate_); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return the cheirality status flag */ | 
					
						
							|  |  |  |   inline bool isPointBehindCamera() const { | 
					
						
							|  |  |  |     return cheiralityException_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   /** return chirality verbosity */ | 
					
						
							|  |  |  |   inline bool verboseCheirality() const { | 
					
						
							|  |  |  |     return verboseCheirality_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return flag for throwing cheirality exceptions */ | 
					
						
							|  |  |  |   inline bool throwCheirality() const { | 
					
						
							|  |  |  |     return throwCheirality_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | private: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Serialization function
 | 
					
						
							|  |  |  |   friend class boost::serialization::access; | 
					
						
							|  |  |  |   template<class ARCHIVE> | 
					
						
							|  |  |  |   void serialize(ARCHIVE & ar, const unsigned int version) { | 
					
						
							|  |  |  |     ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); | 
					
						
							|  |  |  |     ar & BOOST_SERIALIZATION_NVP(throwCheirality_); | 
					
						
							|  |  |  |     ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | /// traits
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | template<class CALIBRATION, size_t D> | 
					
						
							|  |  |  | struct traits<SmartStereoProjectionFactor<CALIBRATION, D> > : | 
					
						
							|  |  |  |     public Testable<SmartStereoProjectionFactor<CALIBRATION, D> > { | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | } // \ namespace gtsam
 |