gtsam 4.1.1
gtsam
VelocityConstraint.h
Go to the documentation of this file.
1
7#pragma once
8
12
13#include <boost/bind/bind.hpp>
14
15namespace gtsam {
16
17namespace dynamics {
18
20typedef enum {
21 TRAPEZOIDAL, // Constant acceleration
22 EULER_START, // Constant velocity, using starting velocity
23 EULER_END // Constant velocity, using ending velocity
24} IntegrationMode;
25
26}
27
35class VelocityConstraint : public gtsam::NoiseModelFactor2<PoseRTV,PoseRTV> {
36public:
38
39protected:
40
41 double dt_;
43
44public:
45
50 double dt, double mu = 1000)
51 : Base(noiseModel::Constrained::All(3, mu), key1, key2), dt_(dt), integration_mode_(mode) {}
52
57 VelocityConstraint(Key key1, Key key2, double dt, double mu = 1000)
58 : Base(noiseModel::Constrained::All(3, mu), key1, key2),
59 dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {}
60
65 double dt, const gtsam::SharedNoiseModel& model)
66 : Base(model, key1, key2), dt_(dt), integration_mode_(mode) {}
67
72 VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel& model)
73 : Base(model, key1, key2), dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {}
74
75 ~VelocityConstraint() override {}
76
78 gtsam::NonlinearFactor::shared_ptr clone() const override {
79 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
80 gtsam::NonlinearFactor::shared_ptr(new VelocityConstraint(*this))); }
81
85 gtsam::Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2,
86 boost::optional<gtsam::Matrix&> H1=boost::none,
87 boost::optional<gtsam::Matrix&> H2=boost::none) const override {
88 if (H1) *H1 = gtsam::numericalDerivative21<gtsam::Vector,PoseRTV,PoseRTV>(
89 std::bind(VelocityConstraint::evaluateError_, std::placeholders::_1,
90 std::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5);
91 if (H2) *H2 = gtsam::numericalDerivative22<gtsam::Vector,PoseRTV,PoseRTV>(
92 std::bind(VelocityConstraint::evaluateError_, std::placeholders::_1,
93 std::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5);
94 return evaluateError_(x1, x2, dt_, integration_mode_);
95 }
96
97 void print(const std::string& s = "", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override {
98 std::string a = "VelocityConstraint: " + s;
99 Base::print(a, formatter);
100 switch(integration_mode_) {
101 case dynamics::TRAPEZOIDAL: std::cout << "Integration: Trapezoidal\n"; break;
102 case dynamics::EULER_START: std::cout << "Integration: Euler (start)\n"; break;
103 case dynamics::EULER_END: std::cout << "Integration: Euler (end)\n"; break;
104 default: std::cout << "Integration: Unknown\n" << std::endl; break;
105 }
106 std::cout << "dt: " << dt_ << std::endl;
107 }
108
109private:
110 static gtsam::Vector evaluateError_(const PoseRTV& x1, const PoseRTV& x2,
111 double dt, const dynamics::IntegrationMode& mode) {
112
113 const Velocity3& v1 = x1.v(), v2 = x2.v();
114 const Point3& p1 = x1.t(), p2 = x2.t();
115 Point3 hx(0,0,0);
116 switch(mode) {
117 case dynamics::TRAPEZOIDAL: hx = p1 + Point3((v1 + v2) * dt *0.5); break;
118 case dynamics::EULER_START: hx = p1 + Point3(v1 * dt); break;
119 case dynamics::EULER_END : hx = p1 + Point3(v2 * dt); break;
120 default: assert(false); break;
121 }
122 return p2 - hx;
123 }
124};
125
126} // \namespace gtsam
Some functions to compute numerical derivatives.
Non-linear factor base classes.
Pose3 with translational velocity.
IntegrationMode
controls which model to use for numerical integration to use for constraints
Definition: VelocityConstraint.h:20
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
Definition: NavState.h:28
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
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
This is the base class for all factor types.
Definition: Factor.h:56
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Print.
Definition: NonlinearFactor.cpp:63
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:211
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:369
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:401
Robot state for use with IMU measurements.
Definition: PoseRTV.h:23
Constraint to enforce dynamics between the velocities and poses, using a prediction based on a numeri...
Definition: VelocityConstraint.h:35
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: VelocityConstraint.h:78
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
Calculates the error for trapezoidal model given.
Definition: VelocityConstraint.h:85
dynamics::IntegrationMode integration_mode_
time difference between frames in seconds
Definition: VelocityConstraint.h:42
VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel &model)
Creates a constraint relating the given variables with arbitrary noise model Uses the default Trapezo...
Definition: VelocityConstraint.h:72
VelocityConstraint(Key key1, Key key2, double dt, double mu=1000)
Creates a constraint relating the given variables with fully constrained noise model Uses the default...
Definition: VelocityConstraint.h:57
VelocityConstraint(Key key1, Key key2, const dynamics::IntegrationMode &mode, double dt, double mu=1000)
Creates a constraint relating the given variables with fully constrained noise model.
Definition: VelocityConstraint.h:49
VelocityConstraint(Key key1, Key key2, const dynamics::IntegrationMode &mode, double dt, const gtsam::SharedNoiseModel &model)
Creates a constraint relating the given variables with arbitrary noise model.
Definition: VelocityConstraint.h:64
void print(const std::string &s="", const gtsam::KeyFormatter &formatter=gtsam::DefaultKeyFormatter) const override
Print.
Definition: VelocityConstraint.h:97