15 #include <gtsam/nonlinear/NonlinearFactor.h> 16 #include <gtsam/base/Matrix.h> 17 #include <gtsam/base/Vector.h> 18 #include <gtsam/geometry/Pose3.h> 37 GPSPose3XYZFactor(gtsam::Key poseKey,
const gtsam::Point3 m, gtsam::SharedNoiseModel model) :
38 gtsam::NoiseModelFactor1<
gtsam::Pose3>(model, poseKey), mx_(m.x()), my_(m.y()), mz_(m.z()) {}
43 gtsam::Vector
evaluateError(
const gtsam::Pose3& p, boost::optional<gtsam::Matrix&> H = boost::none)
const {
48 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
GPSPose3XYZFactor(gtsam::Key poseKey, const gtsam::Point3 m, gtsam::SharedNoiseModel model)