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) {
91 const std::string&
s =
"",
93 std::cout <<
s <<
"BetweenFactor(" 94 << keyFormatter(this->
key1()) <<
"," 95 << keyFormatter(this->
key2()) <<
")\n";
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_);
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>
Concept check for values that can be used in unit tests.
~BetweenFactor() override
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
static const KeyFormatter DefaultKeyFormatter
NoiseModelFactorN< VALUE, VALUE > Base
gtsam::NonlinearFactor::shared_ptr clone() const override
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
const SharedNoiseModel & noiseModel() const
access to the noise model
Matrix * OptionalMatrixType
std::shared_ptr< BetweenFactor > shared_ptr
Vector evaluateError(const T &p1, const T &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
evaluate error, returns vector of errors size of tangent space
BetweenConstraint(const VALUE &measured, Key key1, Key key2, double mu=1000.0)
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< BetweenConstraint< VALUE > > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
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
GTSAM_CONCEPT_ASSERT(IsTestable< VALUE >)
SharedNoiseModel noiseModel_
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
BetweenFactor< VALUE > This
const VALUE & measured() const
return the measurement
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel
BetweenFactor(Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr)