23 template<
typename POSE = Pose3,
typename POINT = Po
int3>
45 : Base(model, key1, key2), measured_(measured) {}
54 std::cout << s <<
"PoseToPointFactor(" 55 << keyFormatter(this->
key1()) <<
"," 56 << keyFormatter(this->
key2()) <<
")\n" 57 <<
" measured: " << measured_.transpose() << std::endl;
63 double tol = 1
e-9)
const override {
64 const This*
e =
dynamic_cast<const This*
>(&
expected);
85 const POSE& w_T_b,
const POINT& w_P,
88 return w_T_b.transformTo(w_P, H1, H2) -
measured_;
95 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 97 friend class boost::serialization::access;
98 template <
class ARCHIVE>
99 void serialize(ARCHIVE& ar,
const unsigned int ) {
101 ar& boost::serialization::make_nvp(
103 boost::serialization::base_object<Base>(*
this));
104 ar& BOOST_SERIALIZATION_NVP(measured_);
virtual ~PoseToPointFactor()
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector evaluateError(const POSE &w_T_b, const POINT &w_P, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error = w_T_b.inverse()*w_P - measured_.
std::shared_ptr< PoseToPointFactor > shared_ptr
NoiseModelFactorN< POSE, POINT > Base
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
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
Matrix * OptionalMatrixType
Array< double, 1, 3 > e(1./3., 0.5, 2.)
PoseToPointFactor(Key key1, Key key2, const POINT &measured, const SharedNoiseModel &model)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
SharedNoiseModel noiseModel_
const POINT & measured() const
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
gtsam::NonlinearFactor::shared_ptr clone() const override
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel