gtsam  4.0.0
gtsam
BetweenFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
16 #pragma once
17 
18 #include <ostream>
19 
20 #include <gtsam/base/Testable.h>
21 #include <gtsam/base/Lie.h>
23 
24 namespace gtsam {
25 
31  template<class VALUE>
32  class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {
33 
34  // Check that VALUE type is a testable Lie group
35  BOOST_CONCEPT_ASSERT((IsTestable<VALUE>));
36  BOOST_CONCEPT_ASSERT((IsLieGroup<VALUE>));
37 
38  public:
39 
40  typedef VALUE T;
41 
42  private:
43 
44  typedef BetweenFactor<VALUE> This;
46 
47  VALUE measured_;
49  public:
50 
51  // shorthand for a smart pointer to a factor
52  typedef typename boost::shared_ptr<BetweenFactor> shared_ptr;
53 
56 
58  BetweenFactor(Key key1, Key key2, const VALUE& measured,
59  const SharedNoiseModel& model = nullptr) :
60  Base(model, key1, key2), measured_(measured) {
61  }
62 
63  virtual ~BetweenFactor() {}
64 
66  virtual gtsam::NonlinearFactor::shared_ptr clone() const {
67  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
68  gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
69 
73  virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
74  std::cout << s << "BetweenFactor("
75  << keyFormatter(this->key1()) << ","
76  << keyFormatter(this->key2()) << ")\n";
77  traits<T>::Print(measured_, " measured: ");
78  this->noiseModel_->print(" noise model: ");
79  }
80 
82  virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const {
83  const This *e = dynamic_cast<const This*> (&expected);
84  return e != NULL && Base::equals(*e, tol) && traits<T>::Equals(this->measured_, e->measured_, tol);
85  }
86 
90  Vector evaluateError(const T& p1, const T& p2, boost::optional<Matrix&> H1 =
91  boost::none, boost::optional<Matrix&> H2 = boost::none) const {
92  T hx = traits<T>::Between(p1, p2, H1, H2); // h(x)
93  // manifold equivalent of h(x)-z -> log(z,h(x))
94 #ifdef SLOW_BUT_CORRECT_BETWEENFACTOR
95  typename traits<T>::ChartJacobian::Jacobian Hlocal;
96  Vector rval = traits<T>::Local(measured_, hx, boost::none, (H1 || H2) ? &Hlocal : 0);
97  if (H1) *H1 = Hlocal * (*H1);
98  if (H2) *H2 = Hlocal * (*H2);
99  return rval;
100 #else
101  return traits<T>::Local(measured_, hx);
102 #endif
103  }
104 
106  const VALUE& measured() const {
107  return measured_;
108  }
109 
111  std::size_t size() const {
112  return 2;
113  }
114 
115  private:
116 
119  template<class ARCHIVE>
120  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
121  ar & boost::serialization::make_nvp("NoiseModelFactor2",
122  boost::serialization::base_object<Base>(*this));
123  ar & BOOST_SERIALIZATION_NVP(measured_);
124  }
125 
126  // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
127  enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 };
128  public:
129  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
130  }; // \class BetweenFactor
131 
133  template<class VALUE>
134  struct traits<BetweenFactor<VALUE> > : public Testable<BetweenFactor<VALUE> > {};
135 
141  template<class VALUE>
142  class BetweenConstraint : public BetweenFactor<VALUE> {
143  public:
144  typedef boost::shared_ptr<BetweenConstraint<VALUE> > shared_ptr;
145 
147  BetweenConstraint(const VALUE& measured, Key key1, Key key2, double mu = 1000.0) :
148  BetweenFactor<VALUE>(key1, key2, measured,
149  noiseModel::Constrained::All(traits<VALUE>::GetDimension(measured), fabs(mu)))
150  {}
151 
152  private:
153 
156  template<class ARCHIVE>
157  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
158  ar & boost::serialization::make_nvp("BetweenFactor",
159  boost::serialization::base_object<BetweenFactor<VALUE> >(*this));
160  }
161  }; // \class BetweenConstraint
162 
164  template<class VALUE>
165  struct traits<BetweenConstraint<VALUE> > : public Testable<BetweenConstraint<VALUE> > {};
166 
167 }
This is the base class for all factor types.
Definition: Factor.h:54
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
virtual bool equals(const NonlinearFactor &expected, double tol=1e-9) const
equals
Definition: BetweenFactor.h:82
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
boost::shared_ptr< BetweenFactor > shared_ptr
The measurement.
Definition: BetweenFactor.h:52
Definition: BetweenFactor.h:32
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
BetweenFactor()
default constructor - only use for serialization
Definition: BetweenFactor.h:55
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: BetweenFactor.h:66
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
Binary between constraint - forces between to a given value This constraint requires the underlying t...
Definition: BetweenFactor.h:142
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:210
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
friend class boost::serialization::access
Serialization function.
Definition: BetweenFactor.h:155
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
const VALUE & measured() const
return the measured
Definition: BetweenFactor.h:106
Definition: Testable.h:57
Non-linear factor base classes.
BetweenFactor(Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: BetweenFactor.h:58
friend class boost::serialization::access
Serialization function.
Definition: BetweenFactor.h:118
Lie Group Concept.
Definition: Lie.h:268
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
virtual void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
implement functions needed for Testable
Definition: BetweenFactor.h:73
Concept check for values that can be used in unit tests.
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
std::size_t size() const
number of variables attached to this factor
Definition: BetweenFactor.h:111
Vector evaluateError(const T &p1, const T &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const
implement functions needed to derive from Factor
Definition: BetweenFactor.h:90
BetweenConstraint(const VALUE &measured, Key key1, Key key2, double mu=1000.0)
Syntactic sugar for constrained version.
Definition: BetweenFactor.h:147
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
Base class and basic functions for Lie types.