GPSPose3XYZFactor.h
Go to the documentation of this file.
1 
13 #pragma once
14 
15 #include <gtsam/nonlinear/NonlinearFactor.h>
16 #include <gtsam/base/Matrix.h>
17 #include <gtsam/base/Vector.h>
18 #include <gtsam/geometry/Pose3.h>
19 
20 
21 namespace rtabmap {
22 
23 class GPSPose3XYZFactor: public gtsam::NoiseModelFactor1<gtsam::Pose3> {
24 
25 private:
26  // measurement information
27  double mx_, my_, mz_;
28 
29 public:
30 
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()) {}
39 
40  // error function
41  // @param p the pose in Pose
42  // @param H the optional Jacobian matrix, which use boost optional and has default null pointer
43  gtsam::Vector evaluateError(const gtsam::Pose3& p, boost::optional<gtsam::Matrix&> H = boost::none) const {
44  if(H)
45  {
46  p.translation(H);
47  }
48  return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished();
49  }
50 };
51 
52 } // namespace gtsamexamples
53 
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)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58