quadrotor_dynamics_solver_quaternion.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019, Wolfgang Merkt
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 // NOTE: Unused
32 
34 
35 namespace exotica
36 {
37 QuadrotorDynamicsSolver::QuadrotorDynamicsSolver()
38 {
39  num_positions_ = 7;
40  num_velocities_ = 6;
41  num_controls_ = 4;
42 
43  J_.setZero();
44  J_.diagonal() = Eigen::Vector3d(0.0023, 0.0023, 0.004);
45 
46  J_inv_.setZero();
47  J_inv_.diagonal() = Eigen::Vector3d(1. / 0.0023, 1. / 0.0023, 1. / 0.0040);
48 }
49 
50 void QuadrotorDynamicsSolver::AssignScene(ScenePtr scene_in)
51 {
52  const int num_positions_in = scene_in->GetKinematicTree().GetNumControlledJoints();
53  // TODO: This is a terrible check (not against name etc.), but can stop _some_ mismatches between URDF/model and dynamics
54  if ((num_positions_in) != 6 || scene_in->GetKinematicTree().GetControlledBaseType() != BaseType::FLOATING)
55  ThrowPretty("Robot model may not be a quadrotor.");
56 }
57 
58 Eigen::VectorXd QuadrotorDynamicsSolver::f(const StateVector& x, const ControlVector& u)
59 {
60  Eigen::Quaterniond quaternion;
61 
62  // If input quaternion is (0,0,0,0) set to (1,0,0,0)
63  if (x.segment<4>(3).isApprox(Eigen::Vector4d::Zero()))
64  quaternion = Eigen::Quaterniond(1, 0, 0, 0);
65  else
66  quaternion = Eigen::Quaterniond(x.segment<4>(3)).normalized();
67 
68  const Eigen::Vector3d v = x.segment<3>(6);
69  const Eigen::Vector3d omega = x.tail<3>();
70 
71  const double F_1 = k_f_ * u(0);
72  const double F_2 = k_f_ * u(1);
73  const double F_3 = k_f_ * u(2);
74  const double F_4 = k_f_ * u(3);
75  const Eigen::Vector3d F(0, 0, F_1 + F_2 + F_3 + F_4); // total rotor force in body frame
76 
77  const double M_1 = k_m_ * u(0);
78  const double M_2 = k_m_ * u(1);
79  const double M_3 = k_m_ * u(2);
80  const double M_4 = k_m_ * u(3);
81  const Eigen::Vector3d tau(L_ * (F_2 - F_4), L_ * (F_3 - F_1), (M_1 - M_2 + M_3 - M_4)); // total rotor torque in body frame
82 
83  StateVector x_dot(13);
84  x_dot.head<3>() = v; // velocity in world frame
85  x_dot.segment<4>(3) = 0.5 * (quaternion * Eigen::Quaterniond(0, omega(0), omega(1), omega(2))).coeffs(); // via quaternion derivative (cf. https://math.stackexchange.com/a/2099673)
86  x_dot.segment<3>(7) = Eigen::Vector3d(0, 0, -g_) + (1. / mass_) * (quaternion * F); // acceleration in world frame
87  x_dot.segment<3>(10) = J_inv_ * (tau - omega.cross(J_ * omega)); // Euler's equation : I*ω + ω x I*ω
88 
89  return x_dot;
90 }
91 
92 Eigen::MatrixXd QuadrotorDynamicsSolver::fx(const StateVector& x, const ControlVector& u)
93 {
94  // TODO
95  ThrowPretty("NotYetImplemented");
96 }
97 
98 Eigen::MatrixXd QuadrotorDynamicsSolver::fu(const StateVector& x, const ControlVector& u)
99 {
100  // TODO
101  ThrowPretty("NotYetImplemented");
102 }
103 
104 Eigen::VectorXd QuadrotorDynamicsSolver::GetPosition(Eigen::VectorXdRefConst x_in)
105 {
106  // Convert quaternion to Euler angles.
107  Eigen::Matrix<double, 6, 1> xyz_rpy;
108  xyz_rpy.head<3>() = x_in.head<3>();
109  xyz_rpy.tail<3>() = Eigen::Quaterniond(x_in.segment<4>(3)).toRotationMatrix().eulerAngles(0, 1, 2);
110  return xyz_rpy;
111 }
112 } // namespace exotica
#define REGISTER_DYNAMICS_SOLVER_TYPE(TYPE, DERIV)
#define ThrowPretty(m)
std::shared_ptr< Scene > ScenePtr
Quadrotor dynamics with quaternion representation Based on D. Mellinger, N. Michael, and V. Kumar, "Trajectory generation and control for precise aggressive maneuvers with quadrotors", Proceedings of the 12th International Symposium on Experimental Robotics (ISER 2010), 2010. Cf. https://journals.sagepub.com/doi/abs/10.1177/0278364911434236.
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst


exotica_quadrotor_dynamics_solver
Author(s):
autogenerated on Sat Apr 10 2021 02:36:44