52 typedef typename boost::shared_ptr<BetweenFactor>
shared_ptr;
66 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
67 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
68 gtsam::NonlinearFactor::shared_ptr(
new This(*
this))); }
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";
78 this->noiseModel_->print(
" noise model: ");
83 const This *e = dynamic_cast<const This*> (&expected);
90 Vector
evaluateError(
const T& p1,
const T& p2, boost::optional<Matrix&> H1 =
91 boost::none, boost::optional<Matrix&> H2 = boost::none)
const {
94 #ifdef SLOW_BUT_CORRECT_BETWEENFACTOR 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);
119 template<
class ARCHIVE>
120 void serialize(ARCHIVE & ar,
const unsigned int ) {
121 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
122 boost::serialization::base_object<Base>(*
this));
123 ar & BOOST_SERIALIZATION_NVP(measured_);
127 enum { NeedsToAlign = (
sizeof(VALUE) % 16) == 0 };
129 EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
133 template<
class VALUE>
141 template<
class VALUE>
144 typedef boost::shared_ptr<BetweenConstraint<VALUE> > shared_ptr;
156 template<
class ARCHIVE>
157 void serialize(ARCHIVE & ar,
const unsigned int ) {
158 ar & boost::serialization::make_nvp(
"BetweenFactor",
164 template<
class VALUE>
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.