ConstantVelocityFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 namespace gtsam {
22 
27 class ConstantVelocityFactor : public NoiseModelFactor2<NavState, NavState> {
28  double dt_;
29 
30  public:
32 
33  public:
35  : NoiseModelFactor2<NavState, NavState>(model, i, j), dt_(dt) {}
37 
49  boost::optional<gtsam::Matrix &> H1 = boost::none,
50  boost::optional<gtsam::Matrix &> H2 = boost::none) const override {
51  // only used to use update() below
52  static const Vector3 b_accel{0.0, 0.0, 0.0};
53  static const Vector3 b_omega{0.0, 0.0, 0.0};
54 
55  Matrix99 predicted_H_x1;
56  NavState predicted = x1.update(b_accel, b_omega, dt_, H1 ? &predicted_H_x1 : nullptr, {}, {});
57 
58  Matrix99 error_H_predicted;
59  Vector9 error = predicted.localCoordinates(x2, H1 ? &error_H_predicted : nullptr, H2);
60 
61  if (H1) {
62  *H1 = error_H_predicted * predicted_H_x1;
63  }
64  return error;
65  }
66 };
67 
68 } // namespace gtsam
gtsam::Vector evaluateError(const NavState &x1, const NavState &x2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const override
Caclulate error: (x2 - x1.update(dt))) where X1 and X1 are NavStates and dt is the time difference in...
double error(const Values &c) const override
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none) const
localCoordinates with optional derivatives
Definition: NavState.cpp:135
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
const double dt
Eigen::VectorXd Vector
Definition: Vector.h:38
NavState update(const Vector3 &b_acceleration, const Vector3 &b_omega, const double dt, OptionalJacobian< 9, 9 > F, OptionalJacobian< 9, 3 > G1, OptionalJacobian< 9, 3 > G2) const
Definition: NavState.cpp:171
ConstantVelocityFactor(Key i, Key j, double dt, const SharedNoiseModel &model)
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
Pose3 x1
Definition: testPose3.cpp:588
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:50