PosePriorFactor.h 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file PosePriorFactor.h
  10. * @author Frank Dellaert
  11. **/
  12. #pragma once
  13. #include <gtsam/nonlinear/NonlinearFactor.h>
  14. #include <gtsam/geometry/concepts.h>
  15. #include <gtsam/base/Testable.h>
  16. namespace gtsam {
  17. /**
  18. * A class for a soft prior on any Value type
  19. * @addtogroup SLAM
  20. */
  21. template<class POSE>
  22. class PosePriorFactor: public NoiseModelFactor1<POSE> {
  23. private:
  24. typedef PosePriorFactor<POSE> This;
  25. typedef NoiseModelFactor1<POSE> Base;
  26. POSE prior_; /** The measurement */
  27. boost::optional<POSE> body_P_sensor_; ///< The pose of the sensor in the body frame
  28. /** concept check by type */
  29. GTSAM_CONCEPT_TESTABLE_TYPE(POSE)
  30. GTSAM_CONCEPT_POSE_TYPE(POSE)
  31. public:
  32. /// shorthand for a smart pointer to a factor
  33. typedef typename boost::shared_ptr<PosePriorFactor<POSE> > shared_ptr;
  34. /** default constructor - only use for serialization */
  35. PosePriorFactor() {}
  36. ~PosePriorFactor() override {}
  37. /** Constructor */
  38. PosePriorFactor(Key key, const POSE& prior, const SharedNoiseModel& model,
  39. boost::optional<POSE> body_P_sensor = boost::none) :
  40. Base(model, key), prior_(prior), body_P_sensor_(body_P_sensor) {
  41. }
  42. /// @return a deep copy of this factor
  43. gtsam::NonlinearFactor::shared_ptr clone() const override {
  44. return boost::static_pointer_cast<gtsam::NonlinearFactor>(
  45. gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
  46. /** implement functions needed for Testable */
  47. /** print */
  48. void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
  49. std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n";
  50. prior_.print(" prior mean: ");
  51. if(this->body_P_sensor_)
  52. this->body_P_sensor_->print(" sensor pose in body frame: ");
  53. this->noiseModel_->print(" noise model: ");
  54. }
  55. /** equals */
  56. bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
  57. const This* e = dynamic_cast<const This*> (&expected);
  58. return e != nullptr
  59. && Base::equals(*e, tol)
  60. && this->prior_.equals(e->prior_, tol)
  61. && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
  62. }
  63. /** implement functions needed to derive from Factor */
  64. /** vector of errors */
  65. Vector evaluateError(const POSE& p, boost::optional<Matrix&> H = boost::none) const override {
  66. if(body_P_sensor_) {
  67. // manifold equivalent of h(x)-z -> log(z,h(x))
  68. return prior_.localCoordinates(p.compose(*body_P_sensor_, H));
  69. } else {
  70. if(H) (*H) = I_6x6;
  71. // manifold equivalent of h(x)-z -> log(z,h(x))
  72. return prior_.localCoordinates(p);
  73. }
  74. }
  75. const POSE& prior() const { return prior_; }
  76. private:
  77. /** Serialization function */
  78. friend class boost::serialization::access;
  79. template<class ARCHIVE>
  80. void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
  81. ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
  82. ar & BOOST_SERIALIZATION_NVP(prior_);
  83. ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
  84. }
  85. };
  86. } /// namespace gtsam