IMUFactor.h
Go to the documentation of this file.
1 
7 #pragma once
8 
12 
13 namespace gtsam {
14 
20 template<class POSE>
21 class IMUFactor : public NoiseModelFactorN<POSE, POSE> {
22 public:
25 
26 protected:
27 
30  double dt_;
31 
32 public:
33 
34  // Provide access to the Matrix& version of evaluateError:
35  using Base::evaluateError;
36 
39  double dt, const Key& key1, const Key& key2, const SharedNoiseModel& model)
40  : Base(model, key1, key2), accel_(accel), gyro_(gyro), dt_(dt) {}
41 
43  IMUFactor(const Vector6& imu_vector,
44  double dt, const Key& key1, const Key& key2, const SharedNoiseModel& model)
45  : Base(model, key1, key2), accel_(imu_vector.head(3)), gyro_(imu_vector.tail(3)), dt_(dt) {}
46 
47  ~IMUFactor() override {}
48 
51  return std::static_pointer_cast<gtsam::NonlinearFactor>(
53 
55  bool equals(const NonlinearFactor& e, double tol = 1e-9) const override {
56  const This* const f = dynamic_cast<const This*>(&e);
57  return f && Base::equals(e) &&
58  equal_with_abs_tol(accel_, f->accel_, tol) &&
59  equal_with_abs_tol(gyro_, f->gyro_, tol) &&
60  std::abs(dt_ - f->dt_) < tol;
61  }
62 
63  void print(const std::string& s="", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override {
64  std::string a = "IMUFactor: " + s;
66  gtsam::print((Vector)accel_, "accel");
67  gtsam::print((Vector)gyro_, "gyro");
68  std::cout << "dt: " << dt_ << std::endl;
69  }
70 
71  // access
72  const Vector3& gyro() const { return gyro_; }
73  const Vector3& accel() const { return accel_; }
74  Vector6 z() const { return (Vector6() << accel_, gyro_).finished(); }
75 
81  OptionalMatrixType H1, OptionalMatrixType H2) const override {
82  const Vector6 meas = z();
83  if (H1) *H1 = numericalDerivative21<Vector6, PoseRTV, PoseRTV>(
84  std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_, meas), x1, x2, 1e-5);
85  if (H2) *H2 = numericalDerivative22<Vector6, PoseRTV, PoseRTV>(
86  std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_, meas), x1, x2, 1e-5);
87  return predict_proxy(x1, x2, dt_, meas);
88  }
89 
91  virtual Vector evaluateError(const Pose3& x1, const Pose3& x2,
93  assert(false); // no corresponding factor here
94  return Vector6::Zero();
95  }
96 
97 private:
99  static Vector6 predict_proxy(const PoseRTV& x1, const PoseRTV& x2,
100  double dt, const Vector6& meas) {
101  Vector6 hx = x1.imuPrediction(x2, dt);
102  return meas - hx;
103  }
104 };
105 
106 } // \namespace gtsam
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::IMUFactor::gyro_
Vector3 gyro_
Definition: IMUFactor.h:29
tail
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type tail(NType n)
Definition: BlockMethods.h:1257
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::IMUFactor::gyro
const Vector3 & gyro() const
Definition: IMUFactor.h:72
gtsam::IMUFactor::equals
bool equals(const NonlinearFactor &e, double tol=1e-9) const override
Definition: IMUFactor.h:55
gtsam::NoiseModelFactorN< POSE, POSE >::evaluateError
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
dt
const double dt
Definition: testVelocityConstraint.cpp:15
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
gtsam::Factor
Definition: Factor.h:69
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::IMUFactor::z
Vector6 z() const
Definition: IMUFactor.h:74
gtsam::IMUFactor::accel_
Vector3 accel_
Definition: IMUFactor.h:29
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::IMUFactor::predict_proxy
static Vector6 predict_proxy(const PoseRTV &x1, const PoseRTV &x2, double dt, const Vector6 &meas)
Definition: IMUFactor.h:99
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::IMUFactor::evaluateError
Vector evaluateError(const PoseRTV &x1, const PoseRTV &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Definition: IMUFactor.h:80
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::Pose3
Definition: Pose3.h:37
gtsam::IMUFactor::evaluateError
virtual Vector evaluateError(const Pose3 &x1, const Pose3 &x2, OptionalMatrixType H1, OptionalMatrixType H2) const
Definition: IMUFactor.h:91
gtsam::IMUFactor::IMUFactor
IMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
Definition: IMUFactor.h:38
gtsam::IMUFactor::~IMUFactor
~IMUFactor() override
Definition: IMUFactor.h:47
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::NoiseModelFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactor.cpp:72
PoseRTV.h
Pose3 with translational velocity.
gtsam::IMUFactor::IMUFactor
IMUFactor(const Vector6 &imu_vector, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
Definition: IMUFactor.h:43
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:80
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
gtsam::IMUFactor::Base
NoiseModelFactorN< POSE, POSE > Base
Definition: IMUFactor.h:23
gtsam::NoiseModelFactorN< POSE, POSE >::key1
Key key1() const
Definition: NonlinearFactor.h:731
head
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
Definition: BlockMethods.h:1208
gtsam::IMUFactor::print
void print(const std::string &s="", const gtsam::KeyFormatter &formatter=gtsam::DefaultKeyFormatter) const override
Definition: IMUFactor.h:63
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::IMUFactor::dt_
double dt_
Definition: IMUFactor.h:30
gtsam::IMUFactor
Definition: IMUFactor.h:21
gtsam::IMUFactor::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: IMUFactor.h:50
gtsam::PoseRTV
Definition: PoseRTV.h:23
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
NonlinearFactor.h
Non-linear factor base classes.
gtsam::IMUFactor::This
IMUFactor< POSE > This
Definition: IMUFactor.h:24
gtsam::NoiseModelFactorN< POSE, POSE >::key2
Key key2() const
Definition: NonlinearFactor.h:735
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: chartTesting.h:28
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::IMUFactor::accel
const Vector3 & accel() const
Definition: IMUFactor.h:73
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:01:01