15 #include <gtsam/nonlinear/NonlinearFactor.h> 16 #include <gtsam/base/Matrix.h> 17 #include <gtsam/base/Vector.h> 18 #include <gtsam/geometry/Pose2.h> 24 class XYFactor:
public gtsam::NoiseModelFactor1<VALUE> {
38 XYFactor(gtsam::Key poseKey,
const gtsam::Point2 m, gtsam::SharedNoiseModel
model) :
39 gtsam::NoiseModelFactor1<VALUE>(model, poseKey), mx_(m.
x()), my_(m.y()) {}
44 gtsam::Vector
evaluateError(
const VALUE& p, boost::optional<gtsam::Matrix&> H = boost::none)
const {
48 if (H) *H = (gtsam::Matrix23() << 1.0, 0.0, 0.0,
49 0.0, 1.0, 0.0).finished();
52 return (gtsam::Vector2() << p.x() -
mx_, p.y() -
my_).finished();
gtsam::Vector evaluateError(const VALUE &p, boost::optional< gtsam::Matrix &> H=boost::none) const
XYFactor(gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model)