gtsam 4.2.0
gtsam
Loading...
Searching...
No Matches
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#ifdef _WIN32
25#define BETWEENFACTOR_VISIBILITY
26#else
27// This will trigger a LNKxxxx on MSVC, so disable for MSVC build
28// Please refer to https://github.com/borglab/gtsam/blob/develop/Using-GTSAM-EXPORT.md
29#define BETWEENFACTOR_VISIBILITY GTSAM_EXPORT
30#endif
31
32namespace gtsam {
33
39 template<class VALUE>
40 class BetweenFactor: public NoiseModelFactorN<VALUE, VALUE> {
41
42 // Check that VALUE type is a testable Lie group
43 BOOST_CONCEPT_ASSERT((IsTestable<VALUE>));
44 BOOST_CONCEPT_ASSERT((IsLieGroup<VALUE>));
45
46 public:
47
48 typedef VALUE T;
49
50 private:
51
52 typedef BetweenFactor<VALUE> This;
54
55 VALUE measured_;
57 public:
58
59 // shorthand for a smart pointer to a factor
60 typedef typename boost::shared_ptr<BetweenFactor> shared_ptr;
61
64
67
69 BetweenFactor(Key key1, Key key2, const VALUE& measured,
70 const SharedNoiseModel& model = nullptr) :
71 Base(model, key1, key2), measured_(measured) {
72 }
73
75
76 ~BetweenFactor() override {}
77
79 gtsam::NonlinearFactor::shared_ptr clone() const override {
80 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
81 gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
82
85
87 void print(
88 const std::string& s = "",
89 const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
90 std::cout << s << "BetweenFactor("
91 << keyFormatter(this->key1()) << ","
92 << keyFormatter(this->key2()) << ")\n";
93 traits<T>::Print(measured_, " measured: ");
94 this->noiseModel_->print(" noise model: ");
95 }
96
98 bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
99 const This *e = dynamic_cast<const This*> (&expected);
100 return e != nullptr && Base::equals(*e, tol) && traits<T>::Equals(this->measured_, e->measured_, tol);
101 }
102
106
108 Vector evaluateError(const T& p1, const T& p2, boost::optional<Matrix&> H1 =
109 boost::none, boost::optional<Matrix&> H2 = boost::none) const override {
110 T hx = traits<T>::Between(p1, p2, H1, H2); // h(x)
111 // manifold equivalent of h(x)-z -> log(z,h(x))
112#ifdef GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR
114 Vector rval = traits<T>::Local(measured_, hx, boost::none, (H1 || H2) ? &Hlocal : 0);
115 if (H1) *H1 = Hlocal * (*H1);
116 if (H2) *H2 = Hlocal * (*H2);
117 return rval;
118#else
119 return traits<T>::Local(measured_, hx);
120#endif
121 }
122
126
128 const VALUE& measured() const {
129 return measured_;
130 }
132
133 private:
134
137 template<class ARCHIVE>
138 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
139 // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
140 ar & boost::serialization::make_nvp("NoiseModelFactor2",
141 boost::serialization::base_object<Base>(*this));
142 ar & BOOST_SERIALIZATION_NVP(measured_);
143 }
144
145 // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
146 enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 };
147 public:
149 }; // \class BetweenFactor
150
152 template<class VALUE>
153 struct traits<BetweenFactor<VALUE> > : public Testable<BetweenFactor<VALUE> > {};
154
160 template<class VALUE>
161 class BetweenConstraint : public BetweenFactor<VALUE> {
162 public:
163 typedef boost::shared_ptr<BetweenConstraint<VALUE> > shared_ptr;
164
166 BetweenConstraint(const VALUE& measured, Key key1, Key key2, double mu = 1000.0) :
167 BetweenFactor<VALUE>(key1, key2, measured,
168 noiseModel::Constrained::All(traits<VALUE>::GetDimension(measured), std::abs(mu)))
169 {}
170
171 private:
172
175 template<class ARCHIVE>
176 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
177 ar & boost::serialization::make_nvp("BetweenFactor",
178 boost::serialization::base_object<BetweenFactor<VALUE> >(*this));
179 }
180 }; // \class BetweenConstraint
181
183 template<class VALUE>
184 struct traits<BetweenConstraint<VALUE> > : public Testable<BetweenConstraint<VALUE> > {};
185
186}
Base class and basic functions for Lie types.
Concept check for values that can be used in unit tests.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
This marks a GTSAM object to require alignment.
Definition types.h:317
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition Key.h:35
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition concepts.h:30
Lie Group Concept.
Definition Lie.h:260
A testable concept check that should be placed in applicable unit tests and in generic algorithms.
Definition Testable.h:58
A helper that implements the traits interface for GTSAM types.
Definition Testable.h:151
bool equals(const This &other, double tol=1e-9) const
check equality
Definition Factor.cpp:42
Nonlinear factor base class.
Definition NonlinearFactor.h:42
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition NonlinearFactor.h:223
A convenient base class for creating your own NoiseModelFactor with n variables.
Definition NonlinearFactor.h:400
A class for a measurement predicted by "between(config[key1],config[key2])".
Definition BetweenFactor.h:40
BetweenFactor()
default constructor - only use for serialization
Definition BetweenFactor.h:66
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition BetweenFactor.h:98
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition BetweenFactor.h:79
boost::shared_ptr< BetweenFactor > shared_ptr
The measurement.
Definition BetweenFactor.h:60
const VALUE & measured() const
return the measurement
Definition BetweenFactor.h:128
BetweenFactor(Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr)
Constructor.
Definition BetweenFactor.h:69
friend class boost::serialization::access
Serialization function.
Definition BetweenFactor.h:136
Vector evaluateError(const T &p1, const T &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
evaluate error, returns vector of errors size of tangent space
Definition BetweenFactor.h:108
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition BetweenFactor.h:87
Binary between constraint - forces between to a given value This constraint requires the underlying t...
Definition BetweenFactor.h:161
BetweenConstraint(const VALUE &measured, Key key1, Key key2, double mu=1000.0)
Syntactic sugar for constrained version.
Definition BetweenFactor.h:166
friend class boost::serialization::access
Serialization function.
Definition BetweenFactor.h:174