/* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) * See LICENSE for the license information * -------------------------------------------------------------------------- */ /** * @file BetweenFactor.h * @author Frank Dellaert, Viorela Ila **/ #pragma once #include #include #include #include namespace gtsam { /** * A class for a measurement predicted by "between(config[key1],config[key2])" * @tparam VALUE the Value type * @addtogroup SLAM */ template class BetweenFactor: public NoiseModelFactor2 { public: typedef VALUE T; private: typedef BetweenFactor This; typedef NoiseModelFactor2 Base; VALUE measured_; /** The measurement */ /** concept check by type */ GTSAM_CONCEPT_LIE_TYPE(T) GTSAM_CONCEPT_TESTABLE_TYPE(T) public: // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; /** default constructor - only use for serialization */ BetweenFactor() {} /** Constructor */ BetweenFactor(Key key1, Key key2, const VALUE& measured, const SharedNoiseModel& model) : Base(model, key1, key2), measured_(measured) { } virtual ~BetweenFactor() {} /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; traits::print()(measured_, " measured: "); this->noiseModel_->print(" noise model: "); } /** equals */ virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { const This *e = dynamic_cast (&expected); return e != NULL && Base::equals(*e, tol) && traits::equals()(this->measured_, e->measured_, tol); } /** implement functions needed to derive from Factor */ /** vector of errors */ Vector evaluateError(const T& p1, const T& p2, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { T hx = p1.between(p2, H1, H2); // h(x) // manifold equivalent of h(x)-z -> log(z,h(x)) DefaultChart chart; return chart.local(measured_, hx); } /** return the measured */ const VALUE& measured() const { return measured_; } /** number of variables attached to this factor */ std::size_t size() const { return 2; } private: /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { ar & boost::serialization::make_nvp("NoiseModelFactor2", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } }; // \class BetweenFactor /** * Binary between constraint - forces between to a given value * This constraint requires the underlying type to a Lie type * */ template class BetweenConstraint : public BetweenFactor { public: typedef boost::shared_ptr > shared_ptr; /** Syntactic sugar for constrained version */ BetweenConstraint(const VALUE& measured, Key key1, Key key2, double mu = 1000.0) : BetweenFactor(key1, key2, measured, noiseModel::Constrained::All(traits::dimension(), fabs(mu))) {} private: /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { ar & boost::serialization::make_nvp("BetweenFactor", boost::serialization::base_object >(*this)); } }; // \class BetweenConstraint } /// namespace gtsam