| 
									
										
										
										
											2021-07-20 02:38:26 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |  * @file   SmartProjectionPoseFactorRollingShutter.h | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |  * @brief  Smart projection factor on poses modeling rolling shutter effect with | 
					
						
							|  |  |  |  * given readout time | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |  * @author Luca Carlone | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  | #include <gtsam/geometry/CameraSet.h>
 | 
					
						
							| 
									
										
										
										
											2021-07-23 09:45:26 +08:00
										 |  |  | #include <gtsam/slam/SmartProjectionFactor.h>
 | 
					
						
							| 
									
										
										
										
											2021-12-09 22:37:21 +08:00
										 |  |  | #include <gtsam_unstable/dllexport.h>
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * | 
					
						
							| 
									
										
										
										
											2022-07-27 04:44:30 +08:00
										 |  |  |  * @ingroup slam | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |  * | 
					
						
							|  |  |  |  * 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-11-08 01:02:33 +08:00
										 |  |  |  * This factor optimizes two consecutive poses of the body assuming a rolling | 
					
						
							|  |  |  |  * shutter model of the camera with given readout time. The factor requires that | 
					
						
							|  |  |  |  * values contain (for each pixel observation) two consecutive camera poses from | 
					
						
							|  |  |  |  * which the pixel observation pose can be interpolated. | 
					
						
							| 
									
										
										
										
											2022-07-27 04:44:30 +08:00
										 |  |  |  * @ingroup slam | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2021-08-29 08:09:24 +08:00
										 |  |  | template <class CAMERA> | 
					
						
							| 
									
										
										
										
											2021-12-09 22:37:21 +08:00
										 |  |  | class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter | 
					
						
							| 
									
										
										
										
											2021-08-29 08:09:24 +08:00
										 |  |  |     : public SmartProjectionFactor<CAMERA> { | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |  private: | 
					
						
							|  |  |  |   typedef SmartProjectionFactor<CAMERA> Base; | 
					
						
							|  |  |  |   typedef SmartProjectionPoseFactorRollingShutter<CAMERA> This; | 
					
						
							| 
									
										
										
										
											2021-08-26 23:29:34 +08:00
										 |  |  |   typedef typename CAMERA::CalibrationType CALIBRATION; | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   typedef typename CAMERA::Measurement MEASUREMENT; | 
					
						
							|  |  |  |   typedef typename CAMERA::MeasurementVector MEASUREMENTS; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |  protected: | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   /// The keys of the pose of the body (with respect to an external world
 | 
					
						
							|  |  |  |   /// frame): two consecutive poses for each observation
 | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |   std::vector<std::pair<Key, Key>> world_P_body_key_pairs_; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   /// interpolation factor (one for each observation) to interpolate between
 | 
					
						
							|  |  |  |   /// pair of consecutive poses
 | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |   std::vector<double> alphas_; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |   /// one or more cameras taking observations (fixed poses wrt body + fixed
 | 
					
						
							|  |  |  |   /// intrinsics)
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   std::shared_ptr<typename Base::Cameras> cameraRig_; | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |   /// vector of camera Ids (one for each observation, in the same order),
 | 
					
						
							|  |  |  |   /// identifying which camera took the measurement
 | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |   FastVector<size_t> cameraIds_; | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   EIGEN_MAKE_ALIGNED_OPERATOR_NEW | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |   static const int DimBlock = | 
					
						
							|  |  |  |       12;  ///< size of the variable stacking 2 poses from which the observation
 | 
					
						
							|  |  |  |            ///< pose is interpolated
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |   static const int DimPose = 6;  ///< Pose3 dimension
 | 
					
						
							| 
									
										
										
										
											2021-08-29 08:09:24 +08:00
										 |  |  |   static const int ZDim = 2;     ///< Measurement dimension (Point2)
 | 
					
						
							|  |  |  |   typedef Eigen::Matrix<double, ZDim, DimBlock> | 
					
						
							|  |  |  |       MatrixZD;  // F blocks (derivatives wrt block of 2 poses)
 | 
					
						
							|  |  |  |   typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD>> | 
					
						
							|  |  |  |       FBlocks;  // vector of F blocks
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   typedef CAMERA Camera; | 
					
						
							|  |  |  |   typedef CameraSet<CAMERA> Cameras; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// shorthand for a smart pointer to a factor
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   typedef std::shared_ptr<This> shared_ptr; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   /// Default constructor, only for serialization
 | 
					
						
							| 
									
										
										
										
											2021-11-08 03:23:14 +08:00
										 |  |  |   SmartProjectionPoseFactorRollingShutter() {} | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Constructor | 
					
						
							|  |  |  |    * @param Isotropic measurement noise | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |    * @param cameraRig set of cameras (fixed poses wrt body and intrinsics) | 
					
						
							|  |  |  |    * taking the measurements | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |    * @param params internal parameters of the smart factors | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |   SmartProjectionPoseFactorRollingShutter( | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |       const SharedNoiseModel& sharedNoiseModel, | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |       const std::shared_ptr<Cameras>& cameraRig, | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |       const SmartProjectionParams& params = SmartProjectionParams()) | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |       : Base(sharedNoiseModel, params), cameraRig_(cameraRig) { | 
					
						
							| 
									
										
										
										
											2021-11-07 07:22:28 +08:00
										 |  |  |     // throw exception if configuration is not supported by this factor
 | 
					
						
							|  |  |  |     if (Base::params_.degeneracyMode != gtsam::ZERO_ON_DEGENERACY) | 
					
						
							|  |  |  |       throw std::runtime_error( | 
					
						
							|  |  |  |           "SmartProjectionRigFactor: " | 
					
						
							|  |  |  |           "degeneracyMode must be set to ZERO_ON_DEGENERACY"); | 
					
						
							|  |  |  |     if (Base::params_.linearizationMode != gtsam::HESSIAN) | 
					
						
							|  |  |  |       throw std::runtime_error( | 
					
						
							|  |  |  |           "SmartProjectionRigFactor: " | 
					
						
							|  |  |  |           "linearizationMode must be set to HESSIAN"); | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Virtual destructor */ | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |   ~SmartProjectionPoseFactorRollingShutter() override = default; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2021-10-06 11:29:20 +08:00
										 |  |  |    * add a new measurement, with 2 pose keys, interpolation factor, and cameraId | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |    * @param measured 2-dimensional location of the projection of a single | 
					
						
							|  |  |  |    *  landmark in a single view (the measurement), interpolated from the 2 poses | 
					
						
							|  |  |  |    * @param world_P_body_key1 key corresponding to the first body poses (time <= | 
					
						
							|  |  |  |    *  time pixel is acquired) | 
					
						
							|  |  |  |    * @param world_P_body_key2 key corresponding to the second body poses (time | 
					
						
							|  |  |  |    *  >= time pixel is acquired) | 
					
						
							|  |  |  |    * @param alpha interpolation factor in [0,1], such that if alpha = 0 the | 
					
						
							|  |  |  |    *  interpolated pose is the same as world_P_body_key1 | 
					
						
							| 
									
										
										
										
											2021-10-06 11:29:20 +08:00
										 |  |  |    * @param cameraId ID of the camera taking the measurement (default 0) | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   void add(const MEASUREMENT& measured, const Key& world_P_body_key1, | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |            const Key& world_P_body_key2, const double& alpha, | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |            const size_t& cameraId = 0) { | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |     // store measurements in base class
 | 
					
						
							| 
									
										
										
										
											2021-07-22 02:30:55 +08:00
										 |  |  |     this->measured_.push_back(measured); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |     // store the pair of keys for each measurement, in the same order
 | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |     world_P_body_key_pairs_.push_back( | 
					
						
							|  |  |  |         std::make_pair(world_P_body_key1, world_P_body_key2)); | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     //  also store keys in the keys_ vector: these keys are assumed to be
 | 
					
						
							|  |  |  |     //  unique, so we avoid duplicates here
 | 
					
						
							|  |  |  |     if (std::find(this->keys_.begin(), this->keys_.end(), world_P_body_key1) == | 
					
						
							|  |  |  |         this->keys_.end()) | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |       this->keys_.push_back(world_P_body_key1);  // add only unique keys
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     if (std::find(this->keys_.begin(), this->keys_.end(), world_P_body_key2) == | 
					
						
							|  |  |  |         this->keys_.end()) | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |       this->keys_.push_back(world_P_body_key2);  // add only unique keys
 | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |     // store interpolation factor
 | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |     alphas_.push_back(alpha); | 
					
						
							| 
									
										
										
										
											2021-07-22 02:30:55 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |     // store id of the camera taking the measurement
 | 
					
						
							|  |  |  |     cameraIds_.push_back(cameraId); | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |    * Variant of the previous "add" function in which we include multiple | 
					
						
							|  |  |  |    * measurements | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |    * @param measurements vector of the 2m dimensional location of the projection | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |    *  of a single landmark in the m views (the measurements) | 
					
						
							|  |  |  |    * @param world_P_body_key_pairs vector where the i-th element contains a pair | 
					
						
							|  |  |  |    *  of keys corresponding to the pair of poses from which the observation pose | 
					
						
							|  |  |  |    *  for the i0-th measurement can be interpolated | 
					
						
							|  |  |  |    * @param alphas vector of interpolation params (in [0,1]), one for each | 
					
						
							|  |  |  |    * measurement (in the same order) | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |    * @param cameraIds IDs of the cameras taking each measurement (same order as | 
					
						
							|  |  |  |    * the measurements) | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   void add(const MEASUREMENTS& measurements, | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |            const std::vector<std::pair<Key, Key>>& world_P_body_key_pairs, | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |            const std::vector<double>& alphas, | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |            const FastVector<size_t>& cameraIds = FastVector<size_t>()) { | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |     if (world_P_body_key_pairs.size() != measurements.size() || | 
					
						
							|  |  |  |         world_P_body_key_pairs.size() != alphas.size() || | 
					
						
							|  |  |  |         (world_P_body_key_pairs.size() != cameraIds.size() && | 
					
						
							|  |  |  |          cameraIds.size() != 0)) {  // cameraIds.size()=0 is default
 | 
					
						
							|  |  |  |       throw std::runtime_error( | 
					
						
							|  |  |  |           "SmartProjectionPoseFactorRollingShutter: " | 
					
						
							|  |  |  |           "trying to add inconsistent inputs"); | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |     if (cameraIds.size() == 0 && cameraRig_->size() > 1) { | 
					
						
							| 
									
										
										
										
											2021-10-06 11:10:45 +08:00
										 |  |  |       throw std::runtime_error( | 
					
						
							|  |  |  |           "SmartProjectionPoseFactorRollingShutter: " | 
					
						
							| 
									
										
										
										
											2021-11-08 03:50:56 +08:00
										 |  |  |           "camera rig includes multiple camera " | 
					
						
							|  |  |  |           "but add did not input cameraIds"); | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     for (size_t i = 0; i < measurements.size(); i++) { | 
					
						
							|  |  |  |       add(measurements[i], world_P_body_key_pairs[i].first, | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |           world_P_body_key_pairs[i].second, alphas[i], | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |           cameraIds.size() == 0 ? 0 | 
					
						
							|  |  |  |                                 : cameraIds[i]);  // use 0 as default if
 | 
					
						
							|  |  |  |                                                   // cameraIds was not specified
 | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   /// return (for each observation) the keys of the pair of poses from which we
 | 
					
						
							|  |  |  |   /// interpolate
 | 
					
						
							|  |  |  |   const std::vector<std::pair<Key, Key>>& world_P_body_key_pairs() const { | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  |     return world_P_body_key_pairs_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |   /// return the interpolation factors alphas
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   const std::vector<double>& alphas() const { return alphas_; } | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |   /// return the calibration object
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   const std::shared_ptr<Cameras>& cameraRig() const { return cameraRig_; } | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |   /// return the calibration object
 | 
					
						
							| 
									
										
										
										
											2021-11-07 06:34:34 +08:00
										 |  |  |   const FastVector<size_t>& cameraIds() const { return cameraIds_; } | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * print | 
					
						
							|  |  |  |    * @param s optional string naming the factor | 
					
						
							|  |  |  |    * @param keyFormatter optional formatter useful for printing Symbols | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   void print( | 
					
						
							|  |  |  |       const std::string& s = "", | 
					
						
							|  |  |  |       const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |     std::cout << s << "SmartProjectionPoseFactorRollingShutter: \n "; | 
					
						
							| 
									
										
										
										
											2021-10-06 11:29:20 +08:00
										 |  |  |     for (size_t i = 0; i < cameraIds_.size(); i++) { | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |       std::cout << "-- Measurement nr " << i << std::endl; | 
					
						
							|  |  |  |       std::cout << " pose1 key: " | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |                 << keyFormatter(world_P_body_key_pairs_[i].first) << std::endl; | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |       std::cout << " pose2 key: " | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |                 << keyFormatter(world_P_body_key_pairs_[i].second) << std::endl; | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |       std::cout << " alpha: " << alphas_[i] << std::endl; | 
					
						
							| 
									
										
										
										
											2021-10-05 09:33:26 +08:00
										 |  |  |       std::cout << "cameraId: " << cameraIds_[i] << std::endl; | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |       (*cameraRig_)[cameraIds_[i]].print("camera in rig:\n"); | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     Base::print("", keyFormatter); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// equals
 | 
					
						
							| 
									
										
										
										
											2021-07-20 04:11:18 +08:00
										 |  |  |   bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { | 
					
						
							| 
									
										
										
										
											2021-08-26 23:29:34 +08:00
										 |  |  |     const SmartProjectionPoseFactorRollingShutter<CAMERA>* e = | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         dynamic_cast<const SmartProjectionPoseFactorRollingShutter<CAMERA>*>( | 
					
						
							|  |  |  |             &p); | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  |     double keyPairsEqual = true; | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     if (this->world_P_body_key_pairs_.size() == | 
					
						
							|  |  |  |         e->world_P_body_key_pairs().size()) { | 
					
						
							|  |  |  |       for (size_t k = 0; k < this->world_P_body_key_pairs_.size(); k++) { | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  |         const Key key1own = world_P_body_key_pairs_[k].first; | 
					
						
							|  |  |  |         const Key key1e = e->world_P_body_key_pairs()[k].first; | 
					
						
							|  |  |  |         const Key key2own = world_P_body_key_pairs_[k].second; | 
					
						
							|  |  |  |         const Key key2e = e->world_P_body_key_pairs()[k].second; | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         if (!(key1own == key1e) || !(key2own == key2e)) { | 
					
						
							|  |  |  |           keyPairsEqual = false; | 
					
						
							|  |  |  |           break; | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     } else { | 
					
						
							|  |  |  |       keyPairsEqual = false; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |     return e && Base::equals(p, tol) && alphas_ == e->alphas() && | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |            keyPairsEqual && cameraRig_->equals(*(e->cameraRig())) && | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |            std::equal(cameraIds_.begin(), cameraIds_.end(), | 
					
						
							|  |  |  |                       e->cameraIds().begin()); | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 03:50:56 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Collect all cameras involved in this factor | 
					
						
							|  |  |  |    * @param values Values structure which must contain camera poses | 
					
						
							|  |  |  |    * corresponding to keys involved in this factor | 
					
						
							|  |  |  |    * @return Cameras | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   typename Base::Cameras cameras(const Values& values) const override { | 
					
						
							|  |  |  |     typename Base::Cameras cameras; | 
					
						
							|  |  |  |     for (size_t i = 0; i < this->measured_.size(); | 
					
						
							|  |  |  |          i++) {  // for each measurement
 | 
					
						
							|  |  |  |       const Pose3& w_P_body1 = | 
					
						
							|  |  |  |           values.at<Pose3>(world_P_body_key_pairs_[i].first); | 
					
						
							|  |  |  |       const Pose3& w_P_body2 = | 
					
						
							|  |  |  |           values.at<Pose3>(world_P_body_key_pairs_[i].second); | 
					
						
							|  |  |  |       double interpolationFactor = alphas_[i]; | 
					
						
							|  |  |  |       const Pose3& w_P_body = | 
					
						
							|  |  |  |           interpolate<Pose3>(w_P_body1, w_P_body2, interpolationFactor); | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |       const typename Base::Camera& camera_i = (*cameraRig_)[cameraIds_[i]]; | 
					
						
							| 
									
										
										
										
											2021-11-08 03:56:06 +08:00
										 |  |  |       const Pose3& body_P_cam = camera_i.pose(); | 
					
						
							| 
									
										
										
										
											2021-11-08 03:50:56 +08:00
										 |  |  |       const Pose3& w_P_cam = w_P_body.compose(body_P_cam); | 
					
						
							|  |  |  |       cameras.emplace_back(w_P_cam, | 
					
						
							|  |  |  |                            make_shared<typename CAMERA::CalibrationType>( | 
					
						
							| 
									
										
										
										
											2021-11-08 03:56:06 +08:00
										 |  |  |                                camera_i.calibration())); | 
					
						
							| 
									
										
										
										
											2021-11-08 03:50:56 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     return cameras; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * error calculates the error of the factor. | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   double error(const Values& values) const override { | 
					
						
							|  |  |  |     if (this->active(values)) { | 
					
						
							|  |  |  |       return this->totalReprojectionError(this->cameras(values)); | 
					
						
							|  |  |  |     } else {  // else of active flag
 | 
					
						
							|  |  |  |       return 0.0; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +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 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |    * @return Return arguments are the camera jacobians Fs (including the | 
					
						
							|  |  |  |    * jacobian with respect to both body poses we interpolate from), the point | 
					
						
							|  |  |  |    * Jacobian E, and the error vector b. Note that the jacobians are computed | 
					
						
							|  |  |  |    * for a given point. | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |   void computeJacobiansWithTriangulatedPoint(FBlocks& Fs, Matrix& E, Vector& b, | 
					
						
							| 
									
										
										
										
											2021-07-22 01:58:47 +08:00
										 |  |  |                                              const Values& values) const { | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |     if (!this->result_) { | 
					
						
							|  |  |  |       throw("computeJacobiansWithTriangulatedPoint"); | 
					
						
							|  |  |  |     } else {  // valid result: compute jacobians
 | 
					
						
							|  |  |  |       size_t numViews = this->measured_.size(); | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |       E = Matrix::Zero(2 * numViews, | 
					
						
							|  |  |  |                        3);  // a Point2 for each view (point jacobian)
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |       b = Vector::Zero(2 * numViews);  // a Point2 for each view
 | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |       // intermediate Jacobians
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |       Eigen::Matrix<double, ZDim, DimPose> dProject_dPoseCam; | 
					
						
							|  |  |  |       Eigen::Matrix<double, DimPose, DimPose> dInterpPose_dPoseBody1, | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |           dInterpPose_dPoseBody2, dPoseCam_dInterpPose; | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |       Eigen::Matrix<double, ZDim, 3> Ei; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       for (size_t i = 0; i < numViews; i++) {  // for each camera/measurement
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         auto w_P_body1 = values.at<Pose3>(world_P_body_key_pairs_[i].first); | 
					
						
							|  |  |  |         auto w_P_body2 = values.at<Pose3>(world_P_body_key_pairs_[i].second); | 
					
						
							| 
									
										
										
										
											2021-08-14 09:42:09 +08:00
										 |  |  |         double interpolationFactor = alphas_[i]; | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |         // get interpolated pose:
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         auto w_P_body = | 
					
						
							|  |  |  |             interpolate<Pose3>(w_P_body1, w_P_body2, interpolationFactor, | 
					
						
							|  |  |  |                                dInterpPose_dPoseBody1, dInterpPose_dPoseBody2); | 
					
						
							| 
									
										
										
										
											2021-11-08 07:32:43 +08:00
										 |  |  |         const typename Base::Camera& camera_i = (*cameraRig_)[cameraIds_[i]]; | 
					
						
							| 
									
										
										
										
											2021-11-08 03:23:14 +08:00
										 |  |  |         auto body_P_cam = camera_i.pose(); | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         auto w_P_cam = w_P_body.compose(body_P_cam, dPoseCam_dInterpPose); | 
					
						
							| 
									
										
										
										
											2021-11-08 03:23:14 +08:00
										 |  |  |         typename Base::Camera camera( | 
					
						
							|  |  |  |             w_P_cam, make_shared<typename CAMERA::CalibrationType>( | 
					
						
							|  |  |  |                          camera_i.calibration())); | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // get jacobians and error vector for current measurement
 | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |         Point2 reprojectionError_i = camera.reprojectionError( | 
					
						
							|  |  |  |             *this->result_, this->measured_.at(i), dProject_dPoseCam, Ei); | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |         Eigen::Matrix<double, ZDim, DimBlock> J;  // 2 x 12
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         J.block(0, 0, ZDim, 6) = | 
					
						
							|  |  |  |             dProject_dPoseCam * dPoseCam_dInterpPose * | 
					
						
							|  |  |  |             dInterpPose_dPoseBody1;  // (2x6) * (6x6) * (6x6)
 | 
					
						
							|  |  |  |         J.block(0, 6, ZDim, 6) = | 
					
						
							|  |  |  |             dProject_dPoseCam * dPoseCam_dInterpPose * | 
					
						
							|  |  |  |             dInterpPose_dPoseBody2;  // (2x6) * (6x6) * (6x6)
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // fit into the output structures
 | 
					
						
							|  |  |  |         Fs.push_back(J); | 
					
						
							|  |  |  |         size_t row = 2 * i; | 
					
						
							|  |  |  |         b.segment<ZDim>(row) = -reprojectionError_i; | 
					
						
							| 
									
										
										
										
											2021-07-22 04:19:44 +08:00
										 |  |  |         E.block<ZDim, 3>(row, 0) = Ei; | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   /// linearize and return a Hessianfactor that is an approximation of error(p)
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   std::shared_ptr<RegularHessianFactor<DimPose>> createHessianFactor( | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |       const Values& values, const double& lambda = 0.0, | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |       bool diagonalDamping = false) const { | 
					
						
							|  |  |  |     // we may have multiple observation sharing the same keys (due to the
 | 
					
						
							|  |  |  |     // rolling shutter interpolation), hence the number of unique keys may be
 | 
					
						
							|  |  |  |     // smaller than 2 * nrMeasurements
 | 
					
						
							|  |  |  |     size_t nrUniqueKeys = | 
					
						
							|  |  |  |         this->keys_ | 
					
						
							|  |  |  |             .size();  // note: by construction, keys_ only contains unique keys
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-10-03 11:10:05 +08:00
										 |  |  |     typename Base::Cameras cameras = this->cameras(values); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |     // Create structures for Hessian Factors
 | 
					
						
							|  |  |  |     KeyVector js; | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     std::vector<Matrix> Gs(nrUniqueKeys * (nrUniqueKeys + 1) / 2); | 
					
						
							|  |  |  |     std::vector<Vector> gs(nrUniqueKeys); | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     if (this->measured_.size() != | 
					
						
							| 
									
										
										
										
											2021-10-03 11:10:05 +08:00
										 |  |  |         cameras.size())  // 1 observation per interpolated camera
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |       throw std::runtime_error( | 
					
						
							|  |  |  |           "SmartProjectionPoseFactorRollingShutter: " | 
					
						
							|  |  |  |           "measured_.size() inconsistent with input"); | 
					
						
							| 
									
										
										
										
											2021-07-22 03:10:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-22 11:33:42 +08:00
										 |  |  |     // triangulate 3D point at given linearization point
 | 
					
						
							| 
									
										
										
										
											2021-10-03 11:10:05 +08:00
										 |  |  |     this->triangulateSafe(cameras); | 
					
						
							| 
									
										
										
										
											2021-07-22 11:33:42 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-23 10:31:33 +08:00
										 |  |  |     if (!this->result_) {  // failed: return "empty/zero" Hessian
 | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |       if (this->params_.degeneracyMode == ZERO_ON_DEGENERACY) { | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         for (Matrix& m : Gs) m = Matrix::Zero(DimPose, DimPose); | 
					
						
							|  |  |  |         for (Vector& v : gs) v = Vector::Zero(DimPose); | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |         return std::make_shared<RegularHessianFactor<DimPose>>(this->keys_, | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |                                                                  Gs, gs, 0.0); | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |       } else { | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         throw std::runtime_error( | 
					
						
							|  |  |  |             "SmartProjectionPoseFactorRollingShutter: " | 
					
						
							|  |  |  |             "only supported degeneracy mode is ZERO_ON_DEGENERACY"); | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-07-22 11:33:42 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     // compute Jacobian given triangulated 3D Point
 | 
					
						
							|  |  |  |     FBlocks Fs; | 
					
						
							| 
									
										
										
										
											2021-07-24 03:39:13 +08:00
										 |  |  |     Matrix E; | 
					
						
							| 
									
										
										
										
											2021-07-22 11:33:42 +08:00
										 |  |  |     Vector b; | 
					
						
							|  |  |  |     this->computeJacobiansWithTriangulatedPoint(Fs, E, b, values); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Whiten using noise model
 | 
					
						
							|  |  |  |     this->noiseModel_->WhitenSystem(E, b); | 
					
						
							|  |  |  |     for (size_t i = 0; i < Fs.size(); i++) | 
					
						
							|  |  |  |       Fs[i] = this->noiseModel_->Whiten(Fs[i]); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-08-28 13:31:50 +08:00
										 |  |  |     Matrix3 P = Cameras::PointCov(E, lambda, diagonalDamping); | 
					
						
							| 
									
										
										
										
											2021-07-23 09:45:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     // Collect all the key pairs: these are the keys that correspond to the
 | 
					
						
							|  |  |  |     // blocks in Fs (on which we apply the Schur Complement)
 | 
					
						
							| 
									
										
										
										
											2021-07-23 10:31:33 +08:00
										 |  |  |     KeyVector nonuniqueKeys; | 
					
						
							|  |  |  |     for (size_t i = 0; i < world_P_body_key_pairs_.size(); i++) { | 
					
						
							|  |  |  |       nonuniqueKeys.push_back(world_P_body_key_pairs_.at(i).first); | 
					
						
							|  |  |  |       nonuniqueKeys.push_back(world_P_body_key_pairs_.at(i).second); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2021-07-24 10:23:01 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     // Build augmented Hessian (with last row/column being the information
 | 
					
						
							|  |  |  |     // vector) Note: we need to get the augumented hessian wrt the unique keys
 | 
					
						
							|  |  |  |     // in key_
 | 
					
						
							| 
									
										
										
										
											2021-07-23 10:31:33 +08:00
										 |  |  |     SymmetricBlockMatrix augmentedHessianUniqueKeys = | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         Base::Cameras::template SchurComplementAndRearrangeBlocks<3, 12, 6>( | 
					
						
							| 
									
										
										
										
											2021-07-23 10:31:33 +08:00
										 |  |  |             Fs, E, P, b, nonuniqueKeys, this->keys_); | 
					
						
							| 
									
										
										
										
											2021-07-23 09:45:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |     return std::make_shared<RegularHessianFactor<DimPose>>( | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |         this->keys_, augmentedHessianUniqueKeys); | 
					
						
							| 
									
										
										
										
											2021-07-22 03:10:10 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2021-08-29 08:09:24 +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 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |    * @return a Gaussian factor | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   std::shared_ptr<GaussianFactor> linearizeDamped( | 
					
						
							| 
									
										
										
										
											2021-11-07 06:11:46 +08:00
										 |  |  |       const Values& values, const double& lambda = 0.0) const { | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     // depending on flag set on construction we may linearize to different
 | 
					
						
							|  |  |  |     // linear factors
 | 
					
						
							| 
									
										
										
										
											2021-07-20 03:30:53 +08:00
										 |  |  |     switch (this->params_.linearizationMode) { | 
					
						
							| 
									
										
										
										
											2021-07-20 05:01:27 +08:00
										 |  |  |       case HESSIAN: | 
					
						
							| 
									
										
										
										
											2021-07-23 09:45:26 +08:00
										 |  |  |         return this->createHessianFactor(values, lambda); | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |       default: | 
					
						
							|  |  |  |         throw std::runtime_error( | 
					
						
							| 
									
										
										
										
											2021-11-08 03:50:56 +08:00
										 |  |  |             "SmartProjectionPoseFactorRollingShutter: " | 
					
						
							|  |  |  |             "unknown linearization mode"); | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// linearize
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   std::shared_ptr<GaussianFactor> linearize( | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |       const Values& values) const override { | 
					
						
							| 
									
										
										
										
											2021-07-23 09:45:26 +08:00
										 |  |  |     return this->linearizeDamped(values); | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  private: | 
					
						
							| 
									
										
										
										
											2023-01-19 04:03:30 +08:00
										 |  |  | #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION  ///
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   /// Serialization function
 | 
					
						
							|  |  |  |   friend class boost::serialization::access; | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |   template <class ARCHIVE> | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   void serialize(ARCHIVE& ar, const unsigned int /*version*/) { | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  |     ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2023-01-19 04:03:30 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | // end of class declaration
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /// traits
 | 
					
						
							| 
									
										
										
										
											2021-11-08 01:02:33 +08:00
										 |  |  | template <class CAMERA> | 
					
						
							|  |  |  | struct traits<SmartProjectionPoseFactorRollingShutter<CAMERA>> | 
					
						
							|  |  |  |     : public Testable<SmartProjectionPoseFactorRollingShutter<CAMERA>> {}; | 
					
						
							| 
									
										
										
										
											2021-07-20 02:38:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | }  // namespace gtsam
 |