VelocityConstraint.h
Go to the documentation of this file.
1 
7 #pragma once
8 
12 
13 namespace gtsam {
14 
15 namespace dynamics {
16 
18 typedef enum {
19  TRAPEZOIDAL, // Constant acceleration
20  EULER_START, // Constant velocity, using starting velocity
21  EULER_END // Constant velocity, using ending velocity
23 
24 }
25 
33 class VelocityConstraint : public gtsam::NoiseModelFactor2<PoseRTV,PoseRTV> {
34 public:
36 
37 protected:
38 
39  double dt_;
41 
42 public:
43 
48  double dt, double mu = 1000)
49  : Base(noiseModel::Constrained::All(3, mu), key1, key2), dt_(dt), integration_mode_(mode) {}
50 
55  VelocityConstraint(Key key1, Key key2, double dt, double mu = 1000)
56  : Base(noiseModel::Constrained::All(3, mu), key1, key2),
57  dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {}
58 
63  double dt, const gtsam::SharedNoiseModel& model)
64  : Base(model, key1, key2), dt_(dt), integration_mode_(mode) {}
65 
71  : Base(model, key1, key2), dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {}
72 
73  ~VelocityConstraint() override {}
74 
77  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
79 
84  boost::optional<gtsam::Matrix&> H1=boost::none,
85  boost::optional<gtsam::Matrix&> H2=boost::none) const override {
86  if (H1) *H1 = gtsam::numericalDerivative21<gtsam::Vector,PoseRTV,PoseRTV>(
87  boost::bind(VelocityConstraint::evaluateError_, _1, _2, dt_, integration_mode_), x1, x2, 1e-5);
88  if (H2) *H2 = gtsam::numericalDerivative22<gtsam::Vector,PoseRTV,PoseRTV>(
89  boost::bind(VelocityConstraint::evaluateError_, _1, _2, dt_, integration_mode_), x1, x2, 1e-5);
90  return evaluateError_(x1, x2, dt_, integration_mode_);
91  }
92 
93  void print(const std::string& s = "", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override {
94  std::string a = "VelocityConstraint: " + s;
96  switch(integration_mode_) {
97  case dynamics::TRAPEZOIDAL: std::cout << "Integration: Trapezoidal\n"; break;
98  case dynamics::EULER_START: std::cout << "Integration: Euler (start)\n"; break;
99  case dynamics::EULER_END: std::cout << "Integration: Euler (end)\n"; break;
100  default: std::cout << "Integration: Unknown\n" << std::endl; break;
101  }
102  std::cout << "dt: " << dt_ << std::endl;
103  }
104 
105 private:
107  double dt, const dynamics::IntegrationMode& mode) {
108 
109  const Velocity3& v1 = x1.v(), v2 = x2.v();
110  const Point3& p1 = x1.t(), p2 = x2.t();
111  Point3 hx(0,0,0);
112  switch(mode) {
113  case dynamics::TRAPEZOIDAL: hx = p1 + Point3((v1 + v2) * dt *0.5); break;
114  case dynamics::EULER_START: hx = p1 + Point3(v1 * dt); break;
115  case dynamics::EULER_END : hx = p1 + Point3(v2 * dt); break;
116  default: assert(false); break;
117  }
118  return p2 - hx;
119  }
120 };
121 
122 } // \namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Vector v2
VelocityConstraint(Key key1, Key key2, double dt, double mu=1000)
Vector v1
Vector3f p1
noiseModel::Diagonal::shared_ptr model
VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel &model)
Vector3 Velocity3
Velocity is currently typedef&#39;d to Vector3.
Definition: NavState.h:28
double mu
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
gtsam::NoiseModelFactor2< PoseRTV, PoseRTV > Base
static gtsam::Vector evaluateError_(const PoseRTV &x1, const PoseRTV &x2, double dt, const dynamics::IntegrationMode &mode)
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const KeyFormatter & formatter
Array33i a
const double dt
VelocityConstraint(Key key1, Key key2, const dynamics::IntegrationMode &mode, double dt, const gtsam::SharedNoiseModel &model)
const Symbol key1('v', 1)
Eigen::VectorXd Vector
Definition: Vector.h:38
const Velocity3 & v() const
Definition: PoseRTV.h:57
const Point3 & t() const
Definition: PoseRTV.h:58
boost::shared_ptr< This > shared_ptr
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Pose3 with translational velocity.
traits
Definition: chartTesting.h:28
gtsam::Vector evaluateError(const PoseRTV &x1, const PoseRTV &x2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const override
Non-linear factor base classes.
Pose3 x1
Definition: testPose3.cpp:588
const Symbol key2('v', 2)
Vector evaluateError_(const PointReferenceFrameFactor &c, const Point2 &global, const Pose2 &trans, const Point2 &local)
VelocityConstraint(Key key1, Key key2, const dynamics::IntegrationMode &mode, double dt, double mu=1000)
static Point3 p2
Vector3 Point3
Definition: Point3.h:35
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void print(const std::string &s="", const gtsam::KeyFormatter &formatter=gtsam::DefaultKeyFormatter) const override
dynamics::IntegrationMode integration_mode_
time difference between frames in seconds
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
gtsam::NonlinearFactor::shared_ptr clone() const override


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:24