2014-06-21 00:59:14 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file ProjectionFactorPPP.h
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief Derived from ProjectionFactor, but estimates body-camera transform
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * in addition to body pose and 3D landmark
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author Chris Beall
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#pragma once
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactor.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/PinholeCamera.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Cal3_S2.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * i.e. the main building block for visual SLAM.
							 | 
						
					
						
							
								
									
										
										
										
											2022-07-27 04:44:30 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								   * @ingroup slam
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  class ProjectionFactorPPP: public NoiseModelFactorN<POSE, POSE, LANDMARK> {
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  protected:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Keep a copy of measurement and calibration for I/O
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Point2 measured_;                    ///< 2D measurement
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::shared_ptr<CALIBRATION> K_;  ///< shared pointer to calibration object
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // verbosity handling for Cheirality Exceptions
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// shorthand for base class type
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-10 06:52:56 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef NoiseModelFactor3<POSE, POSE, LANDMARK> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-12 03:14:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-11 05:07:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Provide access to the Matrix& version of evaluateError:
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-10 06:52:56 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    using Base::evaluateError;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// shorthand for this class
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> This;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +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;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Default constructor
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 15:37:49 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  ProjectionFactorPPP() :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      measured_(0.0, 0.0), throwCheirality_(false), verboseCheirality_(false) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * Constructor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * TODO: Mark argument order standard (keys, measurement, parameters)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param measured is the 2 dimensional location of point in image (the measurement)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param model is the standard deviation
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param poseKey is the index of the camera
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param transformKey is the index of the body-camera transform
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param pointKey is the index of the landmark
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param K shared pointer to the constant calibration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     */
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    ProjectionFactorPPP(const Point2& measured, const SharedNoiseModel& model,
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        Key poseKey, Key transformKey,  Key pointKey,
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        const std::shared_ptr<CALIBRATION>& K) :
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K),
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          throwCheirality_(false), verboseCheirality_(false) {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * Constructor with exception-handling flags
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * TODO: Mark argument order standard (keys, measurement, parameters)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param measured is the 2 dimensional location of point in image (the measurement)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param model is the standard deviation
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param poseKey is the index of the camera
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param pointKey is the index of the landmark
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param K shared pointer to the constant calibration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param throwCheirality determines whether Cheirality exceptions are rethrown
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param verboseCheirality determines whether exceptions are printed for Cheirality
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     */
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    ProjectionFactorPPP(const Point2& measured, const SharedNoiseModel& model,
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        Key poseKey, Key transformKey, Key pointKey,
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        const std::shared_ptr<CALIBRATION>& K,
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        bool throwCheirality, bool verboseCheirality) :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K),
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /** Virtual destructor */
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-29 12:02:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    ~ProjectionFactorPPP() override {}
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// @return a deep copy of this factor
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    NonlinearFactor::shared_ptr clone() const override {
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:39:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return std::static_pointer_cast<NonlinearFactor>(
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 15:37:49 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          NonlinearFactor::shared_ptr(new This(*this))); }
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * print
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param s optional string naming the factor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     * @param keyFormatter optional formatter useful for printing Symbols
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								     */
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2014-08-13 03:54:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      std::cout << s << "ProjectionFactorPPP, z = ";
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-07 12:57:52 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      traits<Point2>::Print(measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Base::print("", keyFormatter);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// equals
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      const This *e = dynamic_cast<const This*>(&p);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return e
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          && Base::equals(p, tol)
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-07 12:57:52 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          && traits<Point2>::Equals(this->measured_, e->measured_, tol)
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          && this->K_->equals(*e->K_, tol);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Evaluate error h(x)-z and optionally derivatives
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point,
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-10 06:52:56 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      try {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          if(H1 || H2 || H3) {
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 15:37:49 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            Matrix H0, H02;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            PinholeCamera<CALIBRATION> camera(pose.compose(transform, H0, H02), *K_);
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-13 06:02:31 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            Point2 reprojectionError(camera.project(point, H1, H3, {}) - measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            *H2 = *H1 * H02;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            *H1 = *H1 * H0;
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 15:37:49 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            return reprojectionError;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            PinholeCamera<CALIBRATION> camera(pose.compose(transform), *K_);
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-13 06:02:31 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            return camera.project(point, H1, H3, {}) - measured_;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      } catch( CheiralityException& e) {
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (H1) *H1 = Matrix::Zero(2,6);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if (H2) *H2 = Matrix::Zero(2,6);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if (H3) *H3 = Matrix::Zero(2,3);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if (verboseCheirality_)
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            std::cout << e.what() << ": Landmark "
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-05 12:24:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								                      << DefaultKeyFormatter(this->key2())
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								                      << " moved behind camera "
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-05 12:24:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								                      << DefaultKeyFormatter(this->key1())
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								                      << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if (throwCheirality_)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          throw e;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      }
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-16 05:30:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return Vector::Ones(2) * 2.0 * K_->fx();
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /** return the measurement */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    const Point2& measured() const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return measured_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /** return the calibration object */
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    inline const std::shared_ptr<CALIBRATION> calibration() const {
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return K_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /** return verbosity */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    inline bool verboseCheirality() const { return verboseCheirality_; }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /** return flag for throwing cheirality exceptions */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    inline bool throwCheirality() const { return throwCheirality_; }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-19 04:03:30 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION    ///
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Serialization function
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    friend class boost::serialization::access;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    template<class ARCHIVE>
							 | 
						
					
						
							
								
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(measured_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(K_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-19 04:03:30 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#endif
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// traits
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  template<class POSE, class LANDMARK, class CALIBRATION>
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-26 23:47:51 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  struct traits<ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> > :
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      public Testable<ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> > {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-21 00:59:14 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								} // \ namespace gtsam
							 |