/** * @file Pose3Factor.h * @brief A Nonlinear Factor, specialized for Urban application * @author Frank Dellaert * @author Viorela Ila */ #pragma once #include #include "NonlinearFactor.h" #include "GaussianFactor.h" #include "VectorConfig.h" #include "Pose3.h" #include "Matrix.h" #include "ostream" namespace gtsam { template class Pose3Factor : public NonlinearFactor { private: std::string key1_, key2_; /** The keys of the two poses, order matters */ Pose3 measured_; Matrix square_root_inverse_covariance_; /** sqrt(inv(measurement_covariance)) */ public: typedef boost::shared_ptr shared_ptr; // shorthand for a smart pointer to a factor Pose3Factor(const std::string& key1, const std::string& key2, const Pose3& measured, const Matrix& measurement_covariance): key1_(key1),key2_(key2),measured_(measured) { square_root_inverse_covariance_ = inverse_square_root(measurement_covariance); } /** implement functions needed for Testable */ void print(const std::string& name) const { std::cout << name << std::endl; std::cout << "Factor "<< std::endl; std::cout << "key1 "<< key1_<& expected, double tol) const {return false;} /** implement functions needed to derive from Factor */ Vector error_vector(const Config& config) const { //z-h Pose3 p1 = config.get(key1_), p2 = config.get(key2_); return (measured_ - between(p1,p2)).vector(); } std::list keys() const { std::list l; return l; } std::size_t size() const { return 2;} /** linearize */ boost::shared_ptr linearize(const Config& config) const { Pose3 p1 = config.get(key1_), p2 = config.get(key2_); Vector b = (measured_ - between(p1,p2)).vector(); Matrix H1 = Dbetween1(p1,p2); Matrix H2 = Dbetween2(p1,p2); boost::shared_ptr linearized(new GaussianFactor( key1_, square_root_inverse_covariance_ * H1, key2_, square_root_inverse_covariance_ * H2, b, 1.0)); return linearized; } }; } /// namespace gtsam