XYFactor.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/Pose2.h>
19 
20 
21 namespace rtabmap {
22 
23 template<class VALUE>
24 class XYFactor: public gtsam::NoiseModelFactor1<VALUE> {
25 
26 private:
27  // measurement information
28  double mx_, my_;
29 
30 public:
31 
38  XYFactor(gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model) :
39  gtsam::NoiseModelFactor1<VALUE>(model, poseKey), mx_(m.x()), my_(m.y()) {}
40 
41  // error function
42  // @param p the pose in Pose2
43  // @param H the optional Jacobian matrix, which use boost optional and has default null pointer
44  gtsam::Vector evaluateError(const VALUE& p, boost::optional<gtsam::Matrix&> H = boost::none) const {
45 
46  // note that use boost optional like a pointer
47  // only calculate jacobian matrix when non-null pointer exists
48  if (H) *H = (gtsam::Matrix23() << 1.0, 0.0, 0.0,
49  0.0, 1.0, 0.0).finished();
50 
51  // return error vector
52  return (gtsam::Vector2() << p.x() - mx_, p.y() - my_).finished();
53  }
54 
55 };
56 
57 } // namespace gtsamexamples
58 
x
gtsam::Vector evaluateError(const VALUE &p, boost::optional< gtsam::Matrix &> H=boost::none) const
Definition: XYFactor.h:44
XYFactor(gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model)
Definition: XYFactor.h:38
model
Definition: trace.py:4


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