15 #include <gtsam/nonlinear/NonlinearFactor.h> 16 #include <gtsam/base/Matrix.h> 17 #include <gtsam/base/Vector.h> 18 #include <gtsam/geometry/Pose3.h> 24 class XYZFactor:
public gtsam::NoiseModelFactor1<VALUE> {
38 XYZFactor(gtsam::Key poseKey,
const gtsam::Point3 m, gtsam::SharedNoiseModel
model) :
39 gtsam::NoiseModelFactor1<VALUE>(model, poseKey), mx_(m.
x()), my_(m.y()), mz_(m.z()) {}
44 gtsam::Vector
evaluateError(
const gtsam::Pose3& p, boost::optional<gtsam::Matrix&> H = boost::none)
const {
49 return (gtsam::Vector3() << p.x() -
mx_, p.y() -
my_, p.z() -
mz_).finished();
51 gtsam::Vector
evaluateError(
const gtsam::Point3& p, boost::optional<gtsam::Matrix&> H = boost::none)
const {
52 return (gtsam::Vector3() << p.x() -
mx_, p.y() -
my_, p.z() -
mz_).finished();
gtsam::Vector evaluateError(const gtsam::Pose3 &p, boost::optional< gtsam::Matrix &> H=boost::none) const
gtsam::Vector evaluateError(const gtsam::Point3 &p, boost::optional< gtsam::Matrix &> H=boost::none) const
XYZFactor(gtsam::Key poseKey, const gtsam::Point3 m, gtsam::SharedNoiseModel model)