/* ---------------------------------------------------------------------------- * 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 BiasedGPSFactor.h * @author Luca Carlone **/ #pragma once #include #include #include namespace gtsam { /** * A class to model GPS measurements, including a bias term which models * common-mode errors and that can be partially corrected if other sensors are used * @addtogroup SLAM */ class BiasedGPSFactor: public NoiseModelFactor2 { private: typedef BiasedGPSFactor This; typedef NoiseModelFactor2 Base; Point3 measured_; /** The measurement */ public: // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; /** default constructor - only use for serialization */ BiasedGPSFactor() {} /** Constructor */ BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured, const SharedNoiseModel& model) : Base(model, posekey, biaskey), measured_(measured) { } virtual ~BiasedGPSFactor() {} /** implement functions needed for Testable */ /** print */ virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "BiasedGPSFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; measured_.print(" 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) && this->measured_.equals(e->measured_, tol); } /** implement functions needed to derive from Factor */ /** vector of errors */ Vector evaluateError(const Pose3& pose, const Point3& bias, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { if (H1 || H2){ H1->resize(3,6); // jacobian wrt pose (*H1) << Matrix3::Zero(), pose.rotation().matrix(); H2->resize(3,3); // jacobian wrt bias (*H2) << Matrix3::Identity(); } return pose.translation().vector() + bias.vector() - measured_.vector(); } /** return the measured */ const Point3 measured() const { return measured_; } 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 BiasedGPSFactor } /// namespace gtsam