25 #define BETWEENFACTOR_VISIBILITY 29 #define BETWEENFACTOR_VISIBILITY GTSAM_EXPORT 63 typedef typename std::shared_ptr<BetweenFactor> shared_ptr;
74 Base(model, key1, key2), measured_(measured) {
82 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
84 gtsam::NonlinearFactor::shared_ptr(
new This(*
this))); }
91 const std::string& s =
"",
92 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
93 std::cout << s <<
"BetweenFactor(" 94 << keyFormatter(this->key1()) <<
"," 95 << keyFormatter(this->key2()) <<
")\n";
97 this->noiseModel_->print(
" noise model: ");
102 const This *e =
dynamic_cast<const This*
> (&expected);
115 #ifdef GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR 118 if (H1) *H1 = Hlocal * (*H1);
119 if (H2) *H2 = Hlocal * (*H2);
138 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 140 friend class boost::serialization::access;
141 template<
class ARCHIVE>
142 void serialize(ARCHIVE & ar,
const unsigned int ) {
144 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
145 boost::serialization::base_object<Base>(*
this));
146 ar & BOOST_SERIALIZATION_NVP(measured_);
151 enum { NeedsToAlign = (
sizeof(VALUE) % 16) == 0 };
157 template<
class VALUE>
165 template<
class VALUE>
168 typedef std::shared_ptr<BetweenConstraint<VALUE> > shared_ptr;
179 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 180 friend class boost::serialization::access;
181 template<
class ARCHIVE>
182 void serialize(ARCHIVE & ar,
const unsigned int ) {
183 ar & boost::serialization::make_nvp(
"BetweenFactor",
190 template<
class VALUE>
Definition: BetweenFactor.h:166
Definition: NonlinearFactor.h:431
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Concept check for values that can be used in unit tests.
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: BetweenFactor.h:90
Definition: Testable.h:152
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
Definition: NonlinearFactor.h:68
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: BetweenFactor.h:82
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Definition: types.h:293
#define OptionalNone
Definition: NonlinearFactor.h:49
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:245
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
Vector evaluateError(const T &p1, const T &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
evaluate error, returns vector of errors size of tangent space
Definition: BetweenFactor.h:111
BetweenFactor()
Definition: BetweenFactor.h:69
BetweenConstraint(const VALUE &measured, Key key1, Key key2, double mu=1000.0)
Definition: BetweenFactor.h:171
Definition: Testable.h:59
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
Base class and basic functions for Lie types.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition: BetweenFactor.h:101
Definition: BetweenFactor.h:40
Definition: chartTesting.h:28
Non-linear factor base classes.
const VALUE & measured() const
return the measurement
Definition: BetweenFactor.h:131
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
BetweenFactor(Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr)
Definition: BetweenFactor.h:72