| 
									
										
										
										
											2011-06-14 04:01:58 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-05-24 01:29:13 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file PartialPriorFactor.h | 
					
						
							|  |  |  |  * @brief A simple prior factor that allows for setting a prior only on a part of linear parameters | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactor.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-06 02:15:53 +08:00
										 |  |  | #include <gtsam/base/Lie.h>
 | 
					
						
							| 
									
										
										
										
											2011-05-24 01:29:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * A class for a soft partial prior on any Lie type, with a mask over Expmap | 
					
						
							|  |  |  |    * parameters. Note that this will use Logmap() to find a tangent space parameterization | 
					
						
							|  |  |  |    * for the variable attached, so this may fail for highly nonlinear manifolds. | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * The prior vector used in this factor is stored in compressed form, such that | 
					
						
							|  |  |  |    * it only contains values for measurements that are to be compared, and they are in | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |    * the same order as VALUE::Logmap(). The provided indices will determine which components to | 
					
						
							|  |  |  |    * extract in the error function. | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |    * | 
					
						
							|  |  |  |    * @tparam VALUE is the type of variable the prior effects | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   template<class VALUE> | 
					
						
							| 
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 |  |  |   class PartialPriorFactor: public NoiseModelFactorN<VALUE> { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  |     typedef VALUE T; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   protected: | 
					
						
							|  |  |  |     // Concept checks on the variable type - currently requires Lie
 | 
					
						
							|  |  |  |     GTSAM_CONCEPT_LIE_TYPE(VALUE) | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 |  |  |     typedef NoiseModelFactorN<VALUE> Base; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     typedef PartialPriorFactor<VALUE> This; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |     Vector prior_;                 ///< Measurement on tangent space parameters, in compressed form.
 | 
					
						
							|  |  |  |     std::vector<size_t> indices_;  ///< Indices of the measured tangent space parameters.
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** default constructor - only use for serialization */ | 
					
						
							|  |  |  |     PartialPriorFactor() {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * constructor with just minimum requirements for a factor - allows more | 
					
						
							|  |  |  |      * computation in the constructor.  This should only be used by subclasses | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     PartialPriorFactor(Key key, const SharedNoiseModel& model) | 
					
						
							|  |  |  |       : Base(model, key) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-01-29 12:02:13 +08:00
										 |  |  |     ~PartialPriorFactor() override {} | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |     /** Single Element Constructor: Prior on a single parameter at index 'idx' in the tangent vector.*/ | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |       Base(model, key), | 
					
						
							|  |  |  |       prior_((Vector(1) << prior).finished()), | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |       indices_(1, idx) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       assert(model->dim() == 1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |     /** Indices Constructor: Specify the relevant measured indices in the tangent vector.*/ | 
					
						
							|  |  |  |     PartialPriorFactor(Key key, const std::vector<size_t>& indices, const Vector& prior, | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |         const SharedNoiseModel& model) : | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |         Base(model, key), | 
					
						
							|  |  |  |         prior_(prior), | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |         indices_(indices) { | 
					
						
							|  |  |  |       assert((size_t)prior_.size() == indices_.size()); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |       assert(model->dim() == (size_t)prior.size()); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /// @return a deep copy of this factor
 | 
					
						
							| 
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 |  |  |     gtsam::NonlinearFactor::shared_ptr clone() const override { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       return boost::static_pointer_cast<gtsam::NonlinearFactor>( | 
					
						
							|  |  |  |           gtsam::NonlinearFactor::shared_ptr(new This(*this))); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** implement functions needed for Testable */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** print */ | 
					
						
							| 
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 |  |  |     void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       Base::print(s, keyFormatter); | 
					
						
							|  |  |  |       gtsam::print(prior_, "prior"); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** equals */ | 
					
						
							| 
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 |  |  |     bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       const This *e = dynamic_cast<const This*> (&expected); | 
					
						
							| 
									
										
										
										
											2020-04-07 05:31:05 +08:00
										 |  |  |       return e != nullptr && Base::equals(*e, tol) && | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |           gtsam::equal_with_abs_tol(this->prior_, e->prior_, tol) && | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |           this->indices_ == e->indices_; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** implement functions needed to derive from Factor */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |     /** Returns a vector of errors for the measured tangent parameters.  */ | 
					
						
							| 
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 |  |  |     Vector evaluateError(const T& p, boost::optional<Matrix&> H = boost::none) const override { | 
					
						
							| 
									
										
										
										
											2021-03-27 05:29:47 +08:00
										 |  |  |       Eigen::Matrix<double, T::dimension, T::dimension> H_local; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // If the Rot3 Cayley map is used, Rot3::LocalCoordinates will throw a runtime error
 | 
					
						
							|  |  |  |       // when asked to compute the Jacobian matrix (see Rot3M.cpp).
 | 
					
						
							|  |  |  |       #ifdef GTSAM_ROT3_EXPMAP
 | 
					
						
							|  |  |  |       const Vector full_tangent = T::LocalCoordinates(p, H ? &H_local : nullptr); | 
					
						
							|  |  |  |       #else
 | 
					
						
							|  |  |  |       const Vector full_tangent = T::Logmap(p, H ? &H_local : nullptr); | 
					
						
							|  |  |  |       #endif
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |       if (H) { | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |         (*H) = Matrix::Zero(indices_.size(), T::dimension); | 
					
						
							|  |  |  |         for (size_t i = 0; i < indices_.size(); ++i) { | 
					
						
							| 
									
										
										
										
											2021-03-27 02:36:43 +08:00
										 |  |  |           (*H).row(i) = H_local.row(indices_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2021-03-27 05:29:47 +08:00
										 |  |  |       // Select relevant parameters from the tangent vector.
 | 
					
						
							| 
									
										
										
										
											2021-03-27 02:36:43 +08:00
										 |  |  |       Vector partial_tangent = Vector::Zero(indices_.size()); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |       for (size_t i = 0; i < indices_.size(); ++i) { | 
					
						
							| 
									
										
										
										
											2021-03-27 02:36:43 +08:00
										 |  |  |         partial_tangent(i) = full_tangent(indices_.at(i)); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |       } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-03-27 02:36:43 +08:00
										 |  |  |       return partial_tangent - prior_; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // access
 | 
					
						
							|  |  |  |     const Vector& prior() const { return prior_; } | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |     const std::vector<size_t>& indices() const { return indices_; } | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   private: | 
					
						
							|  |  |  |     /** Serialization function */ | 
					
						
							|  |  |  |     friend class boost::serialization::access; | 
					
						
							|  |  |  |     template<class ARCHIVE> | 
					
						
							| 
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 |  |  |     void serialize(ARCHIVE & ar, const unsigned int /*version*/) { | 
					
						
							| 
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 |  |  |       // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       ar & boost::serialization::make_nvp("NoiseModelFactor1", | 
					
						
							|  |  |  |           boost::serialization::base_object<Base>(*this)); | 
					
						
							|  |  |  |       ar & BOOST_SERIALIZATION_NVP(prior_); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:20:43 +08:00
										 |  |  |       ar & BOOST_SERIALIZATION_NVP(indices_); | 
					
						
							| 
									
										
										
										
											2021-03-22 05:10:00 +08:00
										 |  |  |       // ar & BOOST_SERIALIZATION_NVP(H_);
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   }; // \class PartialPriorFactor
 | 
					
						
							| 
									
										
										
										
											2011-05-24 01:29:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } /// namespace gtsam
 |