| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											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) | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |  * See LICENSE for the license information | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @file   SmartStereoProjectionFactor.h | 
					
						
							| 
									
										
										
										
											2015-08-26 00:14:52 +08:00
										 |  |  |  * @brief  Smart stereo factor on StereoCameras (pose + calibration) | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |  * @author Luca Carlone | 
					
						
							|  |  |  |  * @author Zsolt Kira | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							| 
									
										
										
										
											2015-08-19 22:58:19 +08:00
										 |  |  |  * @author Chris Beall | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #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>
 | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  | #include <gtsam/slam/StereoFactor.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 { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 00:58:03 +08:00
										 |  |  | /// Linearization mode: what factor to linearize to
 | 
					
						
							|  |  |  |  enum LinearizationMode { | 
					
						
							|  |  |  |    HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD | 
					
						
							|  |  |  |  }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | /// How to manage degeneracy
 | 
					
						
							|  |  |  | enum DegeneracyMode { | 
					
						
							|  |  |  |    IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY | 
					
						
							|  |  |  |  }; | 
					
						
							| 
									
										
										
										
											2015-07-16 00:58:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |  /*
 | 
					
						
							|  |  |  |   *  Parameters for the smart stereo projection factors | 
					
						
							|  |  |  |   */ | 
					
						
							| 
									
										
										
										
											2015-08-19 22:58:19 +08:00
										 |  |  |  struct GTSAM_EXPORT SmartStereoProjectionParams { | 
					
						
							| 
									
										
										
										
											2015-04-09 09:36:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    LinearizationMode linearizationMode; ///< How to linearize the factor
 | 
					
						
							|  |  |  |    DegeneracyMode degeneracyMode; ///< How to linearize the factor
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    /// @name Parameters governing the triangulation
 | 
					
						
							|  |  |  |    /// @{
 | 
					
						
							| 
									
										
										
										
											2015-08-19 22:58:19 +08:00
										 |  |  |    TriangulationParameters triangulation; | 
					
						
							|  |  |  |    double retriangulationThreshold; ///< threshold to decide whether to re-triangulate
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    /// @}
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    /// @name Parameters governing how triangulation result is treated
 | 
					
						
							|  |  |  |    /// @{
 | 
					
						
							| 
									
										
										
										
											2015-08-19 22:58:19 +08:00
										 |  |  |    bool throwCheirality; ///< If true, re-throws Cheirality exceptions (default: false)
 | 
					
						
							|  |  |  |    bool verboseCheirality; ///< If true, prints text for Cheirality exceptions (default: false)
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    /// @}
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    /// Constructor
 | 
					
						
							|  |  |  |    SmartStereoProjectionParams(LinearizationMode linMode = HESSIAN, | 
					
						
							|  |  |  |        DegeneracyMode degMode = IGNORE_DEGENERACY, bool throwCheirality = false, | 
					
						
							|  |  |  |        bool verboseCheirality = false) : | 
					
						
							|  |  |  |        linearizationMode(linMode), degeneracyMode(degMode), retriangulationThreshold( | 
					
						
							|  |  |  |            1e-5), throwCheirality(throwCheirality), verboseCheirality( | 
					
						
							|  |  |  |            verboseCheirality) { | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    virtual ~SmartStereoProjectionParams() { | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    void print(const std::string& str) const { | 
					
						
							|  |  |  |      std::cout << "linearizationMode: " << linearizationMode << "\n"; | 
					
						
							|  |  |  |      std::cout << "   degeneracyMode: " << degeneracyMode << "\n"; | 
					
						
							|  |  |  |      std::cout << triangulation << std::endl; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |    LinearizationMode getLinearizationMode() const { | 
					
						
							|  |  |  |      return linearizationMode; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    DegeneracyMode getDegeneracyMode() const { | 
					
						
							|  |  |  |      return degeneracyMode; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    TriangulationParameters getTriangulationParameters() const { | 
					
						
							|  |  |  |      return triangulation; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    bool getVerboseCheirality() const { | 
					
						
							|  |  |  |      return verboseCheirality; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    bool getThrowCheirality() const { | 
					
						
							|  |  |  |      return throwCheirality; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setLinearizationMode(LinearizationMode linMode) { | 
					
						
							|  |  |  |      linearizationMode = linMode; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setDegeneracyMode(DegeneracyMode degMode) { | 
					
						
							|  |  |  |      degeneracyMode = degMode; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setRankTolerance(double rankTol) { | 
					
						
							|  |  |  |      triangulation.rankTolerance = rankTol; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setEnableEPI(bool enableEPI) { | 
					
						
							|  |  |  |      triangulation.enableEPI = enableEPI; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setLandmarkDistanceThreshold(double landmarkDistanceThreshold) { | 
					
						
							|  |  |  |      triangulation.landmarkDistanceThreshold = landmarkDistanceThreshold; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |    void setDynamicOutlierRejectionThreshold(double dynOutRejectionThreshold) { | 
					
						
							|  |  |  |      triangulation.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; | 
					
						
							|  |  |  |    } | 
					
						
							|  |  |  |  }; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * SmartStereoProjectionFactor: triangulates point and keeps an estimate of it around. | 
					
						
							| 
									
										
										
										
											2015-08-26 00:14:52 +08:00
										 |  |  |  * This factor operates with StereoCamera. This factor requires that values | 
					
						
							|  |  |  |  * contains the involved StereoCameras. Calibration is assumed to be fixed, as this | 
					
						
							|  |  |  |  * is also assumed in StereoCamera. | 
					
						
							|  |  |  |  * If you'd like to store poses in values instead of cameras, use | 
					
						
							|  |  |  |  * SmartStereoProjectionPoseFactor instead | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | */ | 
					
						
							|  |  |  | class SmartStereoProjectionFactor: public SmartFactorBase<StereoCamera> { | 
					
						
							|  |  |  | private: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   typedef SmartFactorBase<StereoCamera> Base; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | protected: | 
					
						
							| 
									
										
										
										
											2014-11-18 08:10:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /// @name Parameters
 | 
					
						
							| 
									
										
										
										
											2015-04-09 05:52:25 +08:00
										 |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   const SmartStereoProjectionParams params_; | 
					
						
							|  |  |  |   /// @}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// @name Caching triangulation
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  |   mutable TriangulationResult result_; ///< result from triangulateSafe
 | 
					
						
							|  |  |  |   mutable std::vector<Pose3> cameraPosesTriangulation_; ///< current triangulation poses
 | 
					
						
							|  |  |  |   /// @}
 | 
					
						
							| 
									
										
										
										
											2015-04-09 05:52:25 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for a smart pointer to a factor
 | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  |   typedef boost::shared_ptr<SmartStereoProjectionFactor> shared_ptr; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-10 08:39:04 +08:00
										 |  |  |   /// Vector of cameras
 | 
					
						
							| 
									
										
										
										
											2015-07-16 00:58:03 +08:00
										 |  |  |   typedef CameraSet<StereoCamera> Cameras; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Constructor | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |    * @param params internal parameters of the smart factors | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2015-08-27 01:02:39 +08:00
										 |  |  |   SmartStereoProjectionFactor(const SharedNoiseModel& sharedNoiseModel, | 
					
						
							|  |  |  |       const SmartStereoProjectionParams& params = | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       SmartStereoProjectionParams()) : | 
					
						
							| 
									
										
										
										
											2015-08-27 01:02:39 +08:00
										 |  |  |       Base(sharedNoiseModel), //
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       params_(params), //
 | 
					
						
							|  |  |  |       result_(TriangulationResult::Degenerate()) { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** 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 { | 
					
						
							| 
									
										
										
										
											2015-04-09 09:36:11 +08:00
										 |  |  |     std::cout << s << "SmartStereoProjectionFactor\n"; | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; | 
					
						
							|  |  |  |     std::cout << "triangulationParameters:\n" << params_.triangulation << std::endl; | 
					
						
							|  |  |  |     std::cout << "result:\n" << result_ << std::endl; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     Base::print("", keyFormatter); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /// equals
 | 
					
						
							|  |  |  |   virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  |     const SmartStereoProjectionFactor *e = | 
					
						
							|  |  |  |         dynamic_cast<const SmartStereoProjectionFactor*>(&p); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     return e && params_.linearizationMode == e->params_.linearizationMode | 
					
						
							|  |  |  |         && Base::equals(p, tol); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   /// 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], | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |             params_.retriangulationThreshold)) { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |           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
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //  /// triangulateSafe
 | 
					
						
							|  |  |  | //  size_t triangulateSafe(const Values& values) const {
 | 
					
						
							|  |  |  | //    return triangulateSafe(this->cameras(values));
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// triangulateSafe
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   TriangulationResult triangulateSafe(const Cameras& cameras) const { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     size_t m = cameras.size(); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     bool retriangulate = decideIfTriangulate(cameras); | 
					
						
							| 
									
										
										
										
											2015-07-30 02:05:48 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | //    if(!retriangulate)
 | 
					
						
							|  |  |  | //      std::cout << "retriangulate = false" << std::endl;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //    bool retriangulate = true;
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (retriangulate) { | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  | //      std::cout << "Retriangulate " << std::endl;
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       std::vector<Point3> reprojections; | 
					
						
							|  |  |  |       reprojections.reserve(m); | 
					
						
							|  |  |  |       for(size_t i = 0; i < m; i++) { | 
					
						
							|  |  |  |         reprojections.push_back(cameras[i].backproject(measured_[i])); | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2015-07-16 11:16:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |       Point3 pw_sum(0,0,0); | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       BOOST_FOREACH(const Point3& pw, reprojections) { | 
					
						
							|  |  |  |         pw_sum = pw_sum + pw; | 
					
						
							| 
									
										
										
										
											2015-07-16 23:26:07 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       // average reprojected landmark
 | 
					
						
							|  |  |  |       Point3 pw_avg = pw_sum / double(m); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       double totalReprojError = 0; | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // check if it lies in front of all cameras
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       for(size_t i = 0; i < m; i++) { | 
					
						
							|  |  |  |         const Pose3& pose = cameras[i].pose(); | 
					
						
							|  |  |  |         const Point3& pl = pose.transform_to(pw_avg); | 
					
						
							|  |  |  |         if (pl.z() <= 0) { | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  |           result_ = TriangulationResult::BehindCamera(); | 
					
						
							|  |  |  |           return result_; | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2015-07-16 11:16:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |         // check landmark distance
 | 
					
						
							|  |  |  |         if (params_.triangulation.landmarkDistanceThreshold > 0 && | 
					
						
							|  |  |  |             pl.norm() > params_.triangulation.landmarkDistanceThreshold) { | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  |           result_ = TriangulationResult::Degenerate(); | 
					
						
							|  |  |  |           return result_; | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |         } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         if (params_.triangulation.dynamicOutlierRejectionThreshold > 0) { | 
					
						
							|  |  |  |           const StereoPoint2& zi = measured_[i]; | 
					
						
							|  |  |  |           StereoPoint2 reprojectionError(cameras[i].project(pw_avg) - zi); | 
					
						
							|  |  |  |           totalReprojError += reprojectionError.vector().norm(); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } // for
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       if (params_.triangulation.dynamicOutlierRejectionThreshold > 0 | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  |           && totalReprojError / m > params_.triangulation.dynamicOutlierRejectionThreshold) { | 
					
						
							|  |  |  |         result_ = TriangulationResult::Degenerate(); | 
					
						
							|  |  |  |         return result_; | 
					
						
							| 
									
										
										
										
											2015-07-16 23:26:07 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2015-07-28 11:27:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  |       if(params_.triangulation.enableEPI) { | 
					
						
							|  |  |  |         try { | 
					
						
							|  |  |  |          pw_avg = triangulateNonlinear(cameras, measured_, pw_avg); | 
					
						
							|  |  |  |         } catch(StereoCheiralityException& e) { | 
					
						
							|  |  |  |           if(params_.verboseCheirality) | 
					
						
							|  |  |  |             std::cout << "Cheirality Exception in SmartStereoProjectionFactor" << std::endl; | 
					
						
							|  |  |  |           if(params_.throwCheirality) | 
					
						
							|  |  |  |             throw; | 
					
						
							|  |  |  |           result_ = TriangulationResult::BehindCamera(); | 
					
						
							|  |  |  |           return TriangulationResult::BehindCamera(); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2015-07-28 11:27:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       result_ = TriangulationResult(pw_avg); | 
					
						
							| 
									
										
										
										
											2015-07-16 23:26:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-08-19 12:11:35 +08:00
										 |  |  |     } // if retriangulate
 | 
					
						
							| 
									
										
										
										
											2015-07-16 11:16:45 +08:00
										 |  |  |     return result_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// triangulate
 | 
					
						
							|  |  |  |   bool triangulateForLinearize(const Cameras& cameras) const { | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     triangulateSafe(cameras); // imperative, might reset result_
 | 
					
						
							| 
									
										
										
										
											2015-10-21 02:44:00 +08:00
										 |  |  |     return bool(result_); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// linearize returns a Hessianfactor that is an approximation of error(p)
 | 
					
						
							| 
									
										
										
										
											2015-04-09 02:21:40 +08:00
										 |  |  |   boost::shared_ptr<RegularHessianFactor<Base::Dim> > createHessianFactor( | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       const Cameras& cameras, const double lambda = 0.0,  bool diagonalDamping = | 
					
						
							|  |  |  |           false) const { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     size_t numKeys = this->keys_.size(); | 
					
						
							|  |  |  |     // Create structures for Hessian Factors
 | 
					
						
							| 
									
										
										
										
											2015-03-05 15:11:01 +08:00
										 |  |  |     std::vector<Key> js; | 
					
						
							|  |  |  |     std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2); | 
					
						
							|  |  |  |     std::vector<Vector> gs(numKeys); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (this->measured_.size() != cameras.size()) { | 
					
						
							|  |  |  |       std::cout | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |           << "SmartStereoProjectionHessianFactor: this->measured_.size() inconsistent with input" | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |           << std::endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-04-09 05:52:25 +08:00
										 |  |  |     triangulateSafe(cameras); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !result_) { | 
					
						
							|  |  |  |       // failed: return"empty" Hessian
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |       BOOST_FOREACH(Matrix& m, Gs) | 
					
						
							| 
									
										
										
										
											2015-04-09 02:21:40 +08:00
										 |  |  |         m = zeros(Base::Dim, Base::Dim); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |       BOOST_FOREACH(Vector& v, gs) | 
					
						
							| 
									
										
										
										
											2015-04-09 02:21:40 +08:00
										 |  |  |         v = zero(Base::Dim); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->keys_, | 
					
						
							|  |  |  |           Gs, gs, 0.0); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols().
 | 
					
						
							| 
									
										
										
										
											2015-07-29 03:12:02 +08:00
										 |  |  |     std::vector<Base::MatrixZD> Fblocks; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     Matrix F, E; | 
					
						
							|  |  |  |     Vector b; | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Whiten using noise model
 | 
					
						
							|  |  |  |     Base::whitenJacobians(Fblocks, E, b); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // build augmented hessian
 | 
					
						
							|  |  |  |     SymmetricBlockMatrix augmentedHessian = //
 | 
					
						
							|  |  |  |         Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->keys_, | 
					
						
							|  |  |  |         augmentedHessian); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   // create factor
 | 
					
						
							|  |  |  | //  boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> > createRegularImplicitSchurFactor(
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //      const Cameras& cameras, double lambda) const {
 | 
					
						
							|  |  |  | //    if (triangulateForLinearize(cameras))
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    else
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      // failed: return empty
 | 
					
						
							|  |  |  | //      return boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> >();
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// create factor
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //  boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > createJacobianQFactor(
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //      const Cameras& cameras, double lambda) const {
 | 
					
						
							|  |  |  | //    if (triangulateForLinearize(cameras))
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      return Base::createJacobianQFactor(cameras, *result_, lambda);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //    else
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      // failed: return empty
 | 
					
						
							|  |  |  | //      return boost::make_shared<JacobianFactorQ<Base::Dim, Base::ZDim> >(this->keys_);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// Create a factor, takes values
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //  boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > createJacobianQFactor(
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //      const Values& values, double lambda) const {
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //    return createJacobianQFactor(this->cameras(values), lambda);
 | 
					
						
							| 
									
										
										
										
											2014-06-04 04:51:03 +08:00
										 |  |  | //  }
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |   /// different (faster) way to compute Jacobian factor
 | 
					
						
							| 
									
										
										
										
											2015-03-05 15:11:01 +08:00
										 |  |  |   boost::shared_ptr<JacobianFactor> createJacobianSVDFactor( | 
					
						
							|  |  |  |       const Cameras& cameras, double lambda) const { | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |     if (triangulateForLinearize(cameras)) | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       return Base::createJacobianSVDFactor(cameras, *result_, lambda); | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |     else | 
					
						
							| 
									
										
										
										
											2015-04-09 02:21:40 +08:00
										 |  |  |       return boost::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->keys_); | 
					
						
							| 
									
										
										
										
											2014-07-16 02:43:01 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  | //  /// linearize to a Hessianfactor
 | 
					
						
							|  |  |  | //  virtual boost::shared_ptr<RegularHessianFactor<Base::Dim> > linearizeToHessian(
 | 
					
						
							|  |  |  | //      const Values& values, double lambda = 0.0) const {
 | 
					
						
							|  |  |  | //    return createHessianFactor(this->cameras(values), lambda);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //  /// linearize to an Implicit Schur factor
 | 
					
						
							|  |  |  | //  virtual boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> > linearizeToImplicit(
 | 
					
						
							|  |  |  | //      const Values& values, double lambda = 0.0) const {
 | 
					
						
							|  |  |  | //    return createRegularImplicitSchurFactor(this->cameras(values), lambda);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //  /// linearize to a JacobianfactorQ
 | 
					
						
							|  |  |  | //  virtual boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > linearizeToJacobian(
 | 
					
						
							|  |  |  | //      const Values& values, double lambda = 0.0) const {
 | 
					
						
							|  |  |  | //    return createJacobianQFactor(this->cameras(values), lambda);
 | 
					
						
							|  |  |  | //  }
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Linearize to Gaussian Factor | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses for this factor | 
					
						
							|  |  |  |    * @return a Gaussian factor | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   boost::shared_ptr<GaussianFactor> linearizeDamped(const Cameras& cameras, | 
					
						
							|  |  |  |       const double lambda = 0.0) const { | 
					
						
							|  |  |  |     // depending on flag set on construction we may linearize to different linear factors
 | 
					
						
							|  |  |  |     switch (params_.linearizationMode) { | 
					
						
							|  |  |  |     case HESSIAN: | 
					
						
							|  |  |  |       return createHessianFactor(cameras, lambda); | 
					
						
							|  |  |  | //    case IMPLICIT_SCHUR:
 | 
					
						
							|  |  |  | //      return createRegularImplicitSchurFactor(cameras, lambda);
 | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |     case JACOBIAN_SVD: | 
					
						
							|  |  |  |       return createJacobianSVDFactor(cameras, lambda); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //    case JACOBIAN_Q:
 | 
					
						
							|  |  |  | //      return createJacobianQFactor(cameras, lambda);
 | 
					
						
							|  |  |  |     default: | 
					
						
							|  |  |  |       throw std::runtime_error("SmartStereoFactorlinearize: unknown mode"); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Linearize to Gaussian Factor | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses for this factor | 
					
						
							|  |  |  |    * @return a Gaussian factor | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   boost::shared_ptr<GaussianFactor> linearizeDamped(const Values& values, | 
					
						
							|  |  |  |       const double lambda = 0.0) const { | 
					
						
							|  |  |  |     // depending on flag set on construction we may linearize to different linear factors
 | 
					
						
							|  |  |  |     Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |     return linearizeDamped(cameras, lambda); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /// linearize
 | 
					
						
							|  |  |  |   virtual boost::shared_ptr<GaussianFactor> linearize( | 
					
						
							|  |  |  |       const Values& values) const { | 
					
						
							|  |  |  |     return linearizeDamped(values); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-26 03:52:16 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Triangulate and compute derivative of error with respect to point | 
					
						
							|  |  |  |    * @return whether triangulation worked | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   bool triangulateAndComputeE(Matrix& E, const Cameras& cameras) const { | 
					
						
							|  |  |  |     bool nonDegenerate = triangulateForLinearize(cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (nonDegenerate) | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       cameras.project2(*result_, boost::none, E); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     return nonDegenerate; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Triangulate and compute derivative of error with respect to point | 
					
						
							|  |  |  |    * @return whether triangulation worked | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   bool triangulateAndComputeE(Matrix& E, const Values& values) const { | 
					
						
							|  |  |  |     Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |     return triangulateAndComputeE(E, cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   /// 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
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   void computeJacobiansWithTriangulatedPoint( | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  |       std::vector<Base::MatrixZD>& Fblocks, Matrix& E, Vector& b, | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       const Cameras& cameras) const { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (!result_) { | 
					
						
							|  |  |  |       throw ("computeJacobiansWithTriangulatedPoint"); | 
					
						
							|  |  |  | //      // Handle degeneracy
 | 
					
						
							|  |  |  | //      // TODO check flag whether we should do this
 | 
					
						
							|  |  |  | //      Unit3 backProjected; /* = cameras[0].backprojectPointAtInfinity(
 | 
					
						
							|  |  |  | //          this->measured_.at(0)); */
 | 
					
						
							| 
									
										
										
										
											2014-06-05 23:01:23 +08:00
										 |  |  | //
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      Base::computeJacobians(Fblocks, E, b, cameras, backProjected);
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } else { | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       // valid result: just return Base version
 | 
					
						
							|  |  |  |       Base::computeJacobians(Fblocks, E, b, cameras, *result_); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Version that takes values, and creates the point
 | 
					
						
							|  |  |  |   bool triangulateAndComputeJacobians( | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  |       std::vector<Base::MatrixZD>& Fblocks, Matrix& E, Vector& b, | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       const Values& values) const { | 
					
						
							|  |  |  |     Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |     bool nonDegenerate = triangulateForLinearize(cameras); | 
					
						
							|  |  |  |     if (nonDegenerate) | 
					
						
							|  |  |  |       computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); | 
					
						
							|  |  |  |     return nonDegenerate; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-26 02:30:17 +08:00
										 |  |  |   /// takes values
 | 
					
						
							|  |  |  |   bool triangulateAndComputeJacobiansSVD( | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  |       std::vector<Base::MatrixZD>& Fblocks, Matrix& Enull, Vector& b, | 
					
						
							| 
									
										
										
										
											2015-03-05 15:11:01 +08:00
										 |  |  |       const Values& values) const { | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |     bool nonDegenerate = triangulateForLinearize(cameras); | 
					
						
							|  |  |  |     if (nonDegenerate) | 
					
						
							|  |  |  |       Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, *result_); | 
					
						
							|  |  |  |     return nonDegenerate; | 
					
						
							| 
									
										
										
										
											2015-02-26 02:30:17 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											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-07-16 04:53:04 +08:00
										 |  |  |     Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |     bool nonDegenerate = triangulateForLinearize(cameras); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     if (nonDegenerate) | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       return Base::unwhitenedError(cameras, *result_); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     else | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |       return zero(cameras.size() * Base::ZDim); | 
					
						
							| 
									
										
										
										
											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 { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     if (externalPoint) | 
					
						
							|  |  |  |       result_ = TriangulationResult(*externalPoint); | 
					
						
							|  |  |  |     else | 
					
						
							|  |  |  |       result_ = triangulateSafe(cameras); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (result_) | 
					
						
							|  |  |  |       // All good, just use version in base class
 | 
					
						
							|  |  |  |       return Base::totalReprojectionError(cameras, *result_); | 
					
						
							|  |  |  |     else if (params_.degeneracyMode == HANDLE_INFINITY) { | 
					
						
							| 
									
										
										
										
											2015-07-20 08:37:16 +08:00
										 |  |  |       throw(std::runtime_error("Backproject at infinity not implemented for SmartStereo.")); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  | //      // Otherwise, manage the exceptions with rotation-only factors
 | 
					
						
							|  |  |  | //      const StereoPoint2& z0 = this->measured_.at(0);
 | 
					
						
							|  |  |  | //      Unit3 backprojected; //= cameras.front().backprojectPointAtInfinity(z0);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //      return Base::totalReprojectionError(cameras, backprojected);
 | 
					
						
							| 
									
										
										
										
											2015-07-16 23:26:07 +08:00
										 |  |  |     } else { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |       // if we don't want to manage the exceptions we discard the factor
 | 
					
						
							|  |  |  |       return 0.0; | 
					
						
							| 
									
										
										
										
											2015-07-16 23:26:07 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |   /// Calculate total reprojection error
 | 
					
						
							|  |  |  |   virtual double error(const Values& values) const { | 
					
						
							|  |  |  |     if (this->active(values)) { | 
					
						
							|  |  |  |       return totalReprojectionError(Base::cameras(values)); | 
					
						
							|  |  |  |     } else { // else of active flag
 | 
					
						
							|  |  |  |       return 0.0; | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return the landmark */ | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     TriangulationResult point() const { | 
					
						
							|  |  |  |       return result_; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     /** COMPUTE the landmark */ | 
					
						
							|  |  |  |     TriangulationResult point(const Values& values) const { | 
					
						
							|  |  |  |       Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  |       return triangulateSafe(cameras); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     /// Is result valid?
 | 
					
						
							|  |  |  |     bool isValid() const { | 
					
						
							| 
									
										
										
										
											2015-10-21 02:44:00 +08:00
										 |  |  |       return bool(result_); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     /** return the degenerate state */ | 
					
						
							|  |  |  |     bool isDegenerate() const { | 
					
						
							|  |  |  |       return result_.degenerate(); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     /** return the cheirality status flag */ | 
					
						
							|  |  |  |     bool isPointBehindCamera() const { | 
					
						
							|  |  |  |       return result_.behindCamera(); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | private: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Serialization function
 | 
					
						
							|  |  |  |   friend class boost::serialization::access; | 
					
						
							|  |  |  |   template<class ARCHIVE> | 
					
						
							| 
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 |  |  |   void serialize(ARCHIVE & ar, const unsigned int /*version*/) { | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |     ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); | 
					
						
							| 
									
										
										
										
											2015-07-16 04:53:04 +08:00
										 |  |  |     ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality); | 
					
						
							|  |  |  |     ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality); | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | /// traits
 | 
					
						
							| 
									
										
										
										
											2015-07-29 02:56:45 +08:00
										 |  |  | template<> | 
					
						
							|  |  |  | struct traits<SmartStereoProjectionFactor > : public Testable< | 
					
						
							|  |  |  |     SmartStereoProjectionFactor> { | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-03 23:21:11 +08:00
										 |  |  | } // \ namespace gtsam
 |