testSimpleHelicopter.cpp
Go to the documentation of this file.
1 
10 
11 /* ************************************************************************* */
12 using namespace gtsam;
13 using namespace gtsam::symbol_shorthand;
14 
15 const double tol=1e-5;
16 const double h = 0.01;
17 
18 //const double deg2rad = M_PI/180.0;
19 //Pose3 g1(Rot3::Ypr(deg2rad*10.0, deg2rad*20.0, deg2rad*30.0), Point3(100.0, 200.0, 300.0));
20 Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0));
21 //Vector6 v1((Vector(6) << 0.1, 0.05, 0.02, 10.0, 20.0, 30.0).finished());
22 Vector6 V1_w((Vector(6) << 0.0, 0.0, M_PI/3, 0.0, 0.0, 30.0).finished());
23 Vector6 V1_g1 = g1.inverse().Adjoint(V1_w);
24 Pose3 g2(g1.expmap(h*V1_g1));
25 //Vector6 v2 = Pose3::Logmap(g1.between(g2));
26 
27 double mass = 100.0;
28 Vector gamma2 = Vector2(0.0, 0.0); // no shape
29 Vector u2 = Vector2(0.0, 0.0); // no control at time 2
30 double distT = 1.0; // distance from the body-centered x axis to the big top motor
31 double distR = 5.0; // distance from the body-centered z axis to the small motor
32 Matrix Mass = ((Vector(3) << mass, mass, mass).finished()).asDiagonal();
33 Matrix Inertia = (Vector(6) << 2.0/5.0*mass*distR*distR, 2.0/5.0*mass*distR*distR, 2.0/5.0*mass*distR*distR, mass, mass, mass).finished().asDiagonal();
34 
35 Vector computeFu(const Vector& gamma, const Vector& control) {
36  double gamma_r = gamma(0), gamma_p = gamma(1);
37 
38  Matrix F = (Matrix(6, 2) << distT*sin(gamma_r), 0.0,
39  distT*sin(gamma_p*cos(gamma_r)), 0.0,
40  0.0, distR,
41  sin(gamma_p)*cos(gamma_r), 0.0,
42  -sin(gamma_r), -1.0,
43  cos(gamma_p)*sin(gamma_r), 0.0
44  ).finished();
45  return F*control;
46 }
47 
48 /* ************************************************************************* */
49 TEST( Reconstruction, evaluateError) {
50  // hard constraints don't need a noise model
51  Reconstruction constraint(G(2), G(1), V(1), h);
52 
53  // verify error function
54  Matrix H1, H2, H3;
55  EXPECT(
56  assert_equal(Z_6x1, constraint.evaluateError(g2, g1, V1_g1, H1, H2, H3), tol));
57 
58  Matrix numericalH1 = numericalDerivative31(
59  boost::function<Vector(const Pose3&, const Pose3&, const Vector6&)>(
60  boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3,
61  boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5);
62 
63  Matrix numericalH2 = numericalDerivative32(
64  boost::function<Vector(const Pose3&, const Pose3&, const Vector6&)>(
65  boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3,
66  boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5);
67 
68  Matrix numericalH3 = numericalDerivative33(
69  boost::function<Vector(const Pose3&, const Pose3&, const Vector6&)>(
70  boost::bind(&Reconstruction::evaluateError, constraint, _1, _2, _3,
71  boost::none, boost::none, boost::none)), g2, g1, V1_g1, 1e-5);
72 
73  EXPECT(assert_equal(numericalH1,H1,1e-5));
74  EXPECT(assert_equal(numericalH2,H2,1e-5));
75 #ifdef GTSAM_USE_QUATERNIONS // TODO: why is the quaternion version much less accurate??
76  EXPECT(assert_equal(numericalH3,H3,1e-3));
77 #else
78  EXPECT(assert_equal(numericalH3,H3,1e-3));
79 #endif
80 }
81 
82 /* ************************************************************************* */
83 // Implement Newton-Euler equation for rigid body dynamics
84 Vector newtonEuler(const Vector& Vb, const Vector& Fb, const Matrix& Inertia) {
85  Matrix W = Pose3::adjointMap((Vector(6) << Vb(0), Vb(1), Vb(2), 0., 0., 0.).finished());
86  Vector dV = Inertia.inverse()*(Fb - W*Inertia*Vb);
87  return dV;
88 }
89 
91  Vector Fu = computeFu(gamma2, u2);
92  Vector fGravity_g1 = Z_6x1;
93  fGravity_g1.segment<3>(3) = g1.rotation().unrotate(Vector3(0, 0, -mass*9.81)); // gravity force in g1 frame
94  Vector Fb = Fu+fGravity_g1;
95 
96  Vector dV = newtonEuler(V1_g1, Fb, Inertia);
97  Vector V2_g1 = dV*h + V1_g1;
98  Pose3 g21 = g2.between(g1);
99  Vector V2_g2 = g21.Adjoint(V2_g1); // convert the new velocity to g2's frame
100 
101  Vector6 expectedv2(V2_g2);
102 
103  // hard constraints don't need a noise model
104  DiscreteEulerPoincareHelicopter constraint(V(2), V(1), G(2), h,
105  Inertia, Fu, mass);
106 
107  // verify error function
108  Matrix H1, H2, H3;
109  EXPECT(assert_equal(Z_6x1, constraint.evaluateError(expectedv2, V1_g1, g2, H1, H2, H3), 1e0));
110 
111  Matrix numericalH1 = numericalDerivative31(
112  boost::function<Vector(const Vector6&, const Vector6&, const Pose3&)>(
113  boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none)
114  ),
115  expectedv2, V1_g1, g2, 1e-5
116  );
117 
118  Matrix numericalH2 = numericalDerivative32(
119  boost::function<Vector(const Vector6&, const Vector6&, const Pose3&)>(
120  boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none)
121  ),
122  expectedv2, V1_g1, g2, 1e-5
123  );
124 
125  Matrix numericalH3 = numericalDerivative33(
126  boost::function<Vector(const Vector6&, const Vector6&, const Pose3&)>(
127  boost::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, _1, _2, _3, boost::none, boost::none, boost::none)
128  ),
129  expectedv2, V1_g1, g2, 1e-5
130  );
131 
132  EXPECT(assert_equal(numericalH1,H1,1e-5));
133  EXPECT(assert_equal(numericalH2,H2,1e-5));
134  EXPECT(assert_equal(numericalH3,H3,5e-5));
135 }
136 
137 /* ************************************************************************* */
138 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
139 /* ************************************************************************* */
Vector6 V1_w((Vector(6)<< 0.0, 0.0, M_PI/3, 0.0, 0.0, 30.0).finished())
Key G(std::uint64_t j)
double distR
static Matrix6 adjointMap(const Vector6 &xi)
FIXME Not tested - marked as incorrect.
Definition: Pose3.cpp:67
Key F(std::uint64_t j)
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
Definition: Pose3.h:154
Matrix Inertia
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Key W(std::uint64_t j)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Vector u2
Vector6 V1_g1
EIGEN_DEVICE_FUNC const CosReturnType cos() const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
int main()
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:50
Eigen::VectorXd Vector
Definition: Vector.h:38
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2262
double mass
Vector evaluateError(const Vector6 &xik, const Vector6 &xik_1, const Pose3 &gk, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
Class expmap(const TangentVector &v) const
Definition: Lie.h:77
#define EXPECT(condition)
Definition: Test.h:151
Vector gamma2
Vector newtonEuler(const Vector &Vb, const Vector &Fb, const Matrix &Inertia)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector computeFu(const Vector &gamma, const Vector &control)
Matrix Mass
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
const double h
Eigen::Vector2d Vector2
Definition: Vector.h:42
Key V(std::uint64_t j)
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Class between(const Class &g) const
Definition: Lie.h:51
TEST(LPInitSolver, InfiniteLoopSingleVar)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
double distT
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
virtual Vector evaluateError(const X1 &, const X2 &, const X3 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const =0
Pose3 g2(g1.expmap(h *V1_g1))
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:32