XYZFactor.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 template<class VALUE>
24 class XYZFactor: public gtsam::NoiseModelFactor1<VALUE> {
25 
26 private:
27  // measurement information
28  double mx_, my_, mz_;
29 
30 public:
31 
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()) {}
40 
41  // error function
42  // @param p the pose in Pose
43  // @param H the optional Jacobian matrix, which use boost optional and has default null pointer
44  gtsam::Vector evaluateError(const gtsam::Pose3& p, boost::optional<gtsam::Matrix&> H = boost::none) const {
45  if(H)
46  {
47  p.translation(H);
48  }
49  return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished();
50  }
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();
53  }
54 };
55 
56 } // namespace gtsamexamples
57 
x
gtsam::Vector evaluateError(const gtsam::Pose3 &p, boost::optional< gtsam::Matrix &> H=boost::none) const
Definition: XYZFactor.h:44
gtsam::Vector evaluateError(const gtsam::Point3 &p, boost::optional< gtsam::Matrix &> H=boost::none) const
Definition: XYZFactor.h:51
XYZFactor(gtsam::Key poseKey, const gtsam::Point3 m, gtsam::SharedNoiseModel model)
Definition: XYZFactor.h:38
model
Definition: trace.py:4


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:38:58