| 
									
										
										
										
											2021-03-14 02:21:43 +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   SmartStereoProjectionFactorPP.h | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |  * @brief  Smart stereo factor on poses (P) and camera extrinsic pose (P) calibrations | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |  * @author Luca Carlone | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/SmartStereoProjectionFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * @addtogroup SLAM | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * If you are using the factor, please cite: | 
					
						
							|  |  |  |  * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, | 
					
						
							|  |  |  |  * Eliminating conditionally independent sets in factor graphs: | 
					
						
							|  |  |  |  * a unifying perspective based on smart factors, | 
					
						
							|  |  |  |  * Int. Conf. on Robotics and Automation (ICRA), 2014. | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |  * This factor optimizes the pose of the body as well as the extrinsic camera calibration (pose of camera wrt body). | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |  * Each camera may have its own extrinsic calibration or the same calibration can be shared by multiple cameras. | 
					
						
							|  |  |  |  * This factor requires that values contain the involved poses and extrinsics (both are Pose3 variables). | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |  * @addtogroup SLAM | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | class SmartStereoProjectionFactorPP : public SmartStereoProjectionFactor { | 
					
						
							|  |  |  |  protected: | 
					
						
							|  |  |  |   /// shared pointer to calibration object (one for each camera)
 | 
					
						
							|  |  |  |   std::vector<boost::shared_ptr<Cal3_S2Stereo>> K_all_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |   /// The keys corresponding to the pose of the body (with respect to an external world frame) for each view
 | 
					
						
							|  |  |  |   KeyVector world_P_body_keys_; | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |   /// The keys corresponding to the extrinsic pose calibration for each view (pose that transform from camera to body)
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:50:47 +08:00
										 |  |  |   KeyVector body_P_cam_keys_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   EIGEN_MAKE_ALIGNED_OPERATOR_NEW | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for base class type
 | 
					
						
							|  |  |  |   typedef SmartStereoProjectionFactor Base; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for this class
 | 
					
						
							|  |  |  |   typedef SmartStereoProjectionFactorPP This; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for a smart pointer to a factor
 | 
					
						
							|  |  |  |   typedef boost::shared_ptr<This> shared_ptr; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |   static const int Dim = 12;  ///< Camera dimension: 6 for body pose, 6 for extrinsic pose
 | 
					
						
							|  |  |  |   static const int DimPose = 6;  ///< Pose3 dimension
 | 
					
						
							|  |  |  |   static const int ZDim = 3;  ///< Measurement dimension (for a StereoPoint2 measurement)
 | 
					
						
							|  |  |  |   typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD;  // F blocks (derivatives wrt camera)
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |   typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks;  // vector of F blocks
 | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Constructor | 
					
						
							|  |  |  |    * @param Isotropic measurement noise | 
					
						
							|  |  |  |    * @param params internal parameters of the smart factors | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |   SmartStereoProjectionFactorPP(const SharedNoiseModel& sharedNoiseModel, | 
					
						
							|  |  |  |                                 const SmartStereoProjectionParams& params = | 
					
						
							|  |  |  |                                     SmartStereoProjectionParams()); | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Virtual destructor */ | 
					
						
							|  |  |  |   ~SmartStereoProjectionFactorPP() override = default; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * add a new measurement, with a pose key, and an extrinsic pose key | 
					
						
							|  |  |  |    * @param measured is the 3-dimensional location of the projection of a | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |    * single landmark in the a single (stereo) view (the measurement) | 
					
						
							|  |  |  |    * @param world_P_body_key is the key corresponding to the body poses observing the same landmark | 
					
						
							|  |  |  |    * @param body_P_cam_key is the key corresponding to the extrinsic camera-to-body pose calibration | 
					
						
							|  |  |  |    * @param K is the (fixed) camera intrinsic calibration | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |   void add(const StereoPoint2& measured, const Key& world_P_body_key, | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |            const Key& body_P_cam_key, | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |            const boost::shared_ptr<Cal3_S2Stereo>& K); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    *  Variant of the previous one in which we include a set of measurements | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |    * @param measurements vector of the 3m dimensional location of the projection | 
					
						
							|  |  |  |    * of a single landmark in the m (stereo) view (the measurements) | 
					
						
							|  |  |  |    * @param w_P_body_keys are the ordered keys corresponding to the body poses observing the same landmark | 
					
						
							|  |  |  |    * @param body_P_cam_keys are the ordered keys corresponding to the extrinsic camera-to-body poses calibration | 
					
						
							|  |  |  |    * (note: elements of this vector do not need to be unique: 2 camera views can share the same calibration) | 
					
						
							|  |  |  |    * @param Ks vector of intrinsic calibration objects | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |    */ | 
					
						
							|  |  |  |   void add(const std::vector<StereoPoint2>& measurements, | 
					
						
							|  |  |  |            const KeyVector& w_P_body_keys, const KeyVector& body_P_cam_keys, | 
					
						
							|  |  |  |            const std::vector<boost::shared_ptr<Cal3_S2Stereo>>& Ks); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Variant of the previous one in which we include a set of measurements with | 
					
						
							|  |  |  |    * the same noise and calibration | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |    * @param measurements vector of the 3m dimensional location of the projection | 
					
						
							|  |  |  |    * of a single landmark in the m (stereo) view (the measurements) | 
					
						
							|  |  |  |    * @param w_P_body_keys are the ordered keys corresponding to the body poses observing the same landmark | 
					
						
							|  |  |  |    * @param body_P_cam_keys are the ordered keys corresponding to the extrinsic camera-to-body poses calibration | 
					
						
							|  |  |  |    * (note: elements of this vector do not need to be unique: 2 camera views can share the same calibration) | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |    * @param K the (known) camera calibration (same for all measurements) | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   void add(const std::vector<StereoPoint2>& measurements, | 
					
						
							|  |  |  |            const KeyVector& w_P_body_keys, const KeyVector& body_P_cam_keys, | 
					
						
							|  |  |  |            const boost::shared_ptr<Cal3_S2Stereo>& K); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * 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 = | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |                  DefaultKeyFormatter) const override; | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// equals
 | 
					
						
							|  |  |  |   bool equals(const NonlinearFactor& p, double tol = 1e-9) const override; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:50:47 +08:00
										 |  |  |   /// equals
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |   const KeyVector& getExtrinsicPoseKeys() const { | 
					
						
							|  |  |  |     return body_P_cam_keys_; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2021-03-14 02:50:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * error calculates the error of the factor. | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   double error(const Values& values) const override; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** return the calibration object */ | 
					
						
							|  |  |  |   inline std::vector<boost::shared_ptr<Cal3_S2Stereo>> calibration() const { | 
					
						
							|  |  |  |     return K_all_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Collect all cameras involved in this factor | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses | 
					
						
							|  |  |  |    * corresponding | 
					
						
							|  |  |  |    * to keys involved in this factor | 
					
						
							|  |  |  |    * @return vector of Values | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   Base::Cameras cameras(const Values& values) const override; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Compute jacobian F, E and error vector at a given linearization point | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses | 
					
						
							|  |  |  |    * corresponding to keys involved in this factor | 
					
						
							|  |  |  |    * @return Return arguments are the camera jacobians Fs (including the jacobian with | 
					
						
							|  |  |  |    * respect to both the body pose and extrinsic pose), the point Jacobian E, | 
					
						
							|  |  |  |    * and the error vector b. Note that the jacobians are computed for a given point. | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-03-30 10:58:29 +08:00
										 |  |  |   void computeJacobiansAndCorrectForMissingMeasurements( | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       FBlocks& Fs, Matrix& E, Vector& b, const Values& values) const { | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     if (!result_) { | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       throw("computeJacobiansWithTriangulatedPoint"); | 
					
						
							|  |  |  |     } else {  // valid result: compute jacobians
 | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  |       size_t numViews = measured_.size(); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |       E = Matrix::Zero(3 * numViews, 3); // a StereoPoint2 for each view (point jacobian)
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       b = Vector::Zero(3 * numViews);  // a StereoPoint2 for each view
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |       Matrix dPoseCam_dPoseBody_i, dPoseCam_dPoseExt_i, dProject_dPoseCam_i, Ei; | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       for (size_t i = 0; i < numViews; i++) {  // for each camera/measurement
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |         Pose3 w_P_body = values.at<Pose3>(world_P_body_keys_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-03-14 11:34:37 +08:00
										 |  |  |         Pose3 body_P_cam = values.at<Pose3>(body_P_cam_keys_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         StereoCamera camera( | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |             w_P_body.compose(body_P_cam, dPoseCam_dPoseBody_i, dPoseCam_dPoseExt_i), | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |             K_all_[i]); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |         // get jacobians and error vector for current measurement
 | 
					
						
							|  |  |  |         StereoPoint2 reprojectionError_i = StereoPoint2( | 
					
						
							|  |  |  |             camera.project(*result_, dProject_dPoseCam_i, Ei) - measured_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         Eigen::Matrix<double, ZDim, Dim> J;  // 3 x 12
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |         J.block<ZDim, 6>(0, 0) = dProject_dPoseCam_i * dPoseCam_dPoseBody_i;  // (3x6) * (6x6)
 | 
					
						
							|  |  |  |         J.block<ZDim, 6>(0, 6) = dProject_dPoseCam_i * dPoseCam_dPoseExt_i;  // (3x6) * (6x6)
 | 
					
						
							|  |  |  |         // if the right pixel is invalid, fix jacobians
 | 
					
						
							|  |  |  |         if (std::isnan(measured_.at(i).uR())) | 
					
						
							|  |  |  |         { | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |           J.block<1, 12>(1, 0) = Matrix::Zero(1, 12); | 
					
						
							|  |  |  |           Ei.block<1, 3>(1, 0) = Matrix::Zero(1, 3); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |           reprojectionError_i = StereoPoint2(reprojectionError_i.uL(), 0.0, | 
					
						
							|  |  |  |                                            reprojectionError_i.v()); | 
					
						
							| 
									
										
										
										
											2021-03-30 10:58:29 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |         // fit into the output structures
 | 
					
						
							| 
									
										
										
										
											2021-03-14 12:49:33 +08:00
										 |  |  |         Fs.push_back(J); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         size_t row = 3 * i; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |         b.segment<ZDim>(row) = -reprojectionError_i.vector(); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         E.block<3, 3>(row, 0) = Ei; | 
					
						
							| 
									
										
										
										
											2021-03-14 11:34:37 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |   /// linearize and return a Hessianfactor that is an approximation of error(p)
 | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  |   boost::shared_ptr<RegularHessianFactor<DimPose> > createHessianFactor( | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       const Values& values, const double lambda = 0.0, bool diagonalDamping = | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |           false) const { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     // we may have multiple cameras sharing the same extrinsic cals, hence the number
 | 
					
						
							|  |  |  |     // of keys may be smaller than 2 * nrMeasurements (which is the upper bound where we
 | 
					
						
							|  |  |  |     // have a body key and an extrinsic calibration key for each measurement)
 | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  |     size_t nrUniqueKeys = keys_.size(); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     size_t nrNonuniqueKeys = world_P_body_keys_.size() | 
					
						
							|  |  |  |         + body_P_cam_keys_.size(); | 
					
						
							| 
									
										
										
										
											2021-03-15 10:43:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     // Create structures for Hessian Factors
 | 
					
						
							|  |  |  |     KeyVector js; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |     std::vector < Matrix > Gs(nrUniqueKeys * (nrUniqueKeys + 1) / 2); | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  |     std::vector<Vector> gs(nrUniqueKeys); | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     if (this->measured_.size() != cameras(values).size()) | 
					
						
							|  |  |  |       throw std::runtime_error("SmartStereoProjectionHessianFactor: this->" | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |                                "measured_.size() inconsistent with input"); | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     // triangulate 3D point at given linearization point
 | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     triangulateSafe(cameras(values)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     if (!result_) { // failed: return "empty/zero" Hessian
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       for (Matrix& m : Gs) | 
					
						
							|  |  |  |         m = Matrix::Zero(DimPose, DimPose); | 
					
						
							|  |  |  |       for (Vector& v : gs) | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  |         v = Vector::Zero(DimPose); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       return boost::make_shared < RegularHessianFactor<DimPose> | 
					
						
							|  |  |  |           > (keys_, Gs, gs, 0.0); | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2021-03-27 05:25:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     // compute Jacobian given triangulated 3D Point
 | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |     FBlocks Fs; | 
					
						
							|  |  |  |     Matrix F, E; | 
					
						
							|  |  |  |     Vector b; | 
					
						
							| 
									
										
										
										
											2021-03-30 10:58:29 +08:00
										 |  |  |     computeJacobiansAndCorrectForMissingMeasurements(Fs, E, b, values); | 
					
						
							| 
									
										
										
										
											2021-03-15 10:43:53 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Whiten using noise model
 | 
					
						
							|  |  |  |     noiseModel_->WhitenSystem(E, b); | 
					
						
							|  |  |  |     for (size_t i = 0; i < Fs.size(); i++) | 
					
						
							|  |  |  |       Fs[i] = noiseModel_->Whiten(Fs[i]); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     // build augmented Hessian (with last row/column being the information vector)
 | 
					
						
							| 
									
										
										
										
											2021-03-15 10:43:53 +08:00
										 |  |  |     Matrix3 P; | 
					
						
							|  |  |  |     Cameras::ComputePointCovariance<3>(P, E, lambda, diagonalDamping); | 
					
						
							| 
									
										
										
										
											2021-03-22 07:12:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     // marginalize point: note - we reuse the standard SchurComplement function
 | 
					
						
							|  |  |  |     SymmetricBlockMatrix augmentedHessian = | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         Cameras::SchurComplement<3, Dim>(Fs, E, P, b); | 
					
						
							| 
									
										
										
										
											2021-03-15 10:43:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  |     // now pack into an Hessian factor
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |     std::vector<DenseIndex> dims(nrUniqueKeys + 1);  // this also includes the b term
 | 
					
						
							| 
									
										
										
										
											2021-03-20 11:09:26 +08:00
										 |  |  |     std::fill(dims.begin(), dims.end() - 1, 6); | 
					
						
							|  |  |  |     dims.back() = 1; | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  |     SymmetricBlockMatrix augmentedHessianUniqueKeys; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // here we have to deal with the fact that some cameras may share the same extrinsic key
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |     if (nrUniqueKeys == nrNonuniqueKeys) {  // if there is 1 calibration key per camera
 | 
					
						
							|  |  |  |       augmentedHessianUniqueKeys = SymmetricBlockMatrix( | 
					
						
							|  |  |  |           dims, Matrix(augmentedHessian.selfadjointView())); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |     } else {  // if multiple cameras share a calibration we have to rearrange
 | 
					
						
							|  |  |  |       // the results of the Schur complement matrix
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       std::vector<DenseIndex> nonuniqueDims(nrNonuniqueKeys + 1);  // this also includes the b term
 | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |       std::fill(nonuniqueDims.begin(), nonuniqueDims.end() - 1, 6); | 
					
						
							|  |  |  |       nonuniqueDims.back() = 1; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       augmentedHessian = SymmetricBlockMatrix( | 
					
						
							|  |  |  |           nonuniqueDims, Matrix(augmentedHessian.selfadjointView())); | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // these are the keys that correspond to the blocks in augmentedHessian (output of SchurComplement)
 | 
					
						
							|  |  |  |       KeyVector nonuniqueKeys; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:45:02 +08:00
										 |  |  |       for (size_t i = 0; i < world_P_body_keys_.size(); i++) { | 
					
						
							|  |  |  |         nonuniqueKeys.push_back(world_P_body_keys_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |         nonuniqueKeys.push_back(body_P_cam_keys_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-03-27 05:25:27 +08:00
										 |  |  |       } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  |       // get map from key to location in the new augmented Hessian matrix (the one including only unique keys)
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       std::map<Key, size_t> keyToSlotMap; | 
					
						
							|  |  |  |       for (size_t k = 0; k < nrUniqueKeys; k++) { | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |         keyToSlotMap[keys_[k]] = k; | 
					
						
							| 
									
										
										
										
											2021-03-27 05:25:27 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-03-20 11:09:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |       // initialize matrix to zero
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       augmentedHessianUniqueKeys = SymmetricBlockMatrix( | 
					
						
							|  |  |  |           dims, Matrix::Zero(6 * nrUniqueKeys + 1, 6 * nrUniqueKeys + 1)); | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // add contributions for each key: note this loops over the hessian with nonUnique keys (augmentedHessian)
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |       // and populates an Hessian that only includes the unique keys (that is what we want to return)
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       for (size_t i = 0; i < nrNonuniqueKeys; i++) {  // rows
 | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |         Key key_i = nonuniqueKeys.at(i); | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // update information vector
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         augmentedHessianUniqueKeys.updateOffDiagonalBlock( | 
					
						
							|  |  |  |             keyToSlotMap[key_i], nrUniqueKeys, | 
					
						
							|  |  |  |             augmentedHessian.aboveDiagonalBlock(i, nrNonuniqueKeys)); | 
					
						
							| 
									
										
										
										
											2021-03-27 10:33:15 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // update blocks
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |         for (size_t j = i; j < nrNonuniqueKeys; j++) {  // cols
 | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |           Key key_j = nonuniqueKeys.at(j); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |           if (i == j) { | 
					
						
							|  |  |  |             augmentedHessianUniqueKeys.updateDiagonalBlock( | 
					
						
							|  |  |  |                 keyToSlotMap[key_i], augmentedHessian.diagonalBlock(i)); | 
					
						
							|  |  |  |           } else {  // (i < j)
 | 
					
						
							|  |  |  |             if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) { | 
					
						
							|  |  |  |               augmentedHessianUniqueKeys.updateOffDiagonalBlock( | 
					
						
							|  |  |  |                   keyToSlotMap[key_i], keyToSlotMap[key_j], | 
					
						
							|  |  |  |                   augmentedHessian.aboveDiagonalBlock(i, j)); | 
					
						
							|  |  |  |             } else { | 
					
						
							|  |  |  |               augmentedHessianUniqueKeys.updateDiagonalBlock( | 
					
						
							|  |  |  |                   keyToSlotMap[key_i], | 
					
						
							|  |  |  |                   augmentedHessian.aboveDiagonalBlock(i, j) | 
					
						
							|  |  |  |                       + augmentedHessian.aboveDiagonalBlock(i, j).transpose()); | 
					
						
							| 
									
										
										
										
											2021-03-28 11:03:05 +08:00
										 |  |  |             } | 
					
						
							| 
									
										
										
										
											2021-03-27 08:04:42 +08:00
										 |  |  |           } | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-04-04 05:59:45 +08:00
										 |  |  |       // update bottom right element of the matrix
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |       augmentedHessianUniqueKeys.updateDiagonalBlock( | 
					
						
							|  |  |  |           nrUniqueKeys, augmentedHessian.diagonalBlock(nrNonuniqueKeys)); | 
					
						
							| 
									
										
										
										
											2021-03-27 05:25:27 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |     return boost::make_shared < RegularHessianFactor<DimPose> | 
					
						
							|  |  |  |         > (keys_, augmentedHessianUniqueKeys); | 
					
						
							| 
									
										
										
										
											2021-03-14 08:19:12 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 11:34:37 +08:00
										 |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |    * Linearize to Gaussian Factor (possibly adding a damping factor Lambda for LM) | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses and extrinsic pose 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
 | 
					
						
							|  |  |  |     switch (params_.linearizationMode) { | 
					
						
							|  |  |  |       case HESSIAN: | 
					
						
							|  |  |  |         return createHessianFactor(values, lambda); | 
					
						
							|  |  |  |       default: | 
					
						
							|  |  |  |         throw std::runtime_error( | 
					
						
							|  |  |  |             "SmartStereoProjectionFactorPP: unknown linearization mode"); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// linearize
 | 
					
						
							|  |  |  |   boost::shared_ptr<GaussianFactor> linearize(const Values& values) const | 
					
						
							|  |  |  |       override { | 
					
						
							|  |  |  |     return linearizeDamped(values); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2021-03-14 11:34:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |  private: | 
					
						
							|  |  |  |   /// Serialization function
 | 
					
						
							|  |  |  |   friend class boost::serialization::access; | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |   template<class ARCHIVE> | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |   void serialize(ARCHIVE& ar, const unsigned int /*version*/) { | 
					
						
							|  |  |  |     ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  |     ar & BOOST_SERIALIZATION_NVP(K_all_); | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | // end of class declaration
 | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /// traits
 | 
					
						
							| 
									
										
										
										
											2021-04-04 05:37:36 +08:00
										 |  |  | template<> | 
					
						
							|  |  |  | struct traits<SmartStereoProjectionFactorPP> : public Testable< | 
					
						
							|  |  |  |     SmartStereoProjectionFactorPP> { | 
					
						
							|  |  |  | }; | 
					
						
							| 
									
										
										
										
											2021-03-14 02:21:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | }  // namespace gtsam
 |