10  Multirotor

10.1 Dynamics

  • Parameters
    • state space \(\mathcal{X}\)
    • action space \(\mathcal{U}\)
    • number of rotors \(N\)
    • mass \(m\) [kg]
    • actuation matrix \(\mathbf{B}\in \mathbb R^{4\times N}\)
    • inertia matrix \(\mathbf{J}\in \mathbb R^{3\times 3}\) [\(kg\cdot m^2\)]
    • gravity constant \(g\) [\(m/s^2\)]
  • State: \(\mathbf{x}= (\mathbf{p}, \mathbf{v}, \mathbf{R}, \boldsymbol{\omega})^\top \in \mathbb R^3 \times \mathbb R^3 \times SO(3) \times \mathbb R^3\)
    • Position \(\mathbf{p}= (x,y,z)^\top\) [m, global frame]
    • Velocity \(\mathbf{v}= (\dot x, \dot y, \dot z)^\top\) [m/s, global frame]
    • Orientation \(\mathbf{R}\) [attitude rotation matrix]
    • Angular velocity \(\boldsymbol{\omega}= (\omega_x, \omega_y, \omega_z)^\top\) [rad/s, body frame]
  • Action: \(\mathbf{u}= (\omega_1, \ldots, \omega_N)^\top \in \mathbb R^N\)
    • Angular velocity of each rotor \(\omega_i\) [rad/s]

10.1.1 Basic Rotation Matrix Formulation

\[ \begin{aligned} \dot{\mathbf{p}} &= \mathbf{v}\\ m \dot{\mathbf{v}} &= f \mathbf{R}\mathbf{e}_z - m g \mathbf{e}_z\\ \dot{\mathbf{R}} &= \mathbf{R}\hat{\boldsymbol{\omega}} \\ \mathbf{J}\dot{\boldsymbol{\omega}} &= \mathbf{J}\boldsymbol{\omega}\times \boldsymbol{\omega}+ \boldsymbol{\tau}_u\\ (f, \boldsymbol{\tau}_u)^\top &= \mathbf{B}(\omega_1^2, \ldots, \omega_N^2)^\top \end{aligned} \] where \(\mathbf{e}_z = (0,0,1)^\top\) and \(\hat{\boldsymbol{\omega}}\) is defined in Equation A.9.

Note

When integrating, \(\mathbf{R}\) has to preserve the properties of a rotation matrix.

10.1.2 Basic Quaternion Formulation

The state becomes \(\mathbf{x}= (\mathbf{p}, \mathbf{v}, \mathbf{q}, \boldsymbol{\omega})^\top \in \mathbb R^3 \times \mathbb R^3 \times SO(3) \times \mathbb R^3\)

\[ \begin{aligned} \dot{\mathbf{p}} &= \mathbf{v}\\ m \dot{\mathbf{v}} &= \mathbf{q} \odot (0, 0, f)^\top - m g \mathbf{e}_z\\ \dot{\mathbf{q}} &= \frac{1}{2} \mathbf{q}\otimes \overline{\boldsymbol{\omega}} \\ \mathbf{J}\dot{\boldsymbol{\omega}} &= \mathbf{J}\boldsymbol{\omega}\times \boldsymbol{\omega}+ \boldsymbol{\tau}_u\\ (f, \boldsymbol{\tau}_u)^\top &= \mathbf{B}(\omega_1^2, \ldots, \omega_N^2)^\top \end{aligned} \] where \(\mathbf{q}\) is a unit quaternion, \(\overline{\boldsymbol{\omega}}\) is defined in Equation A.3, \(\otimes\) is defined in Equation A.7, and \(\odot\) is defined in Equation A.8.

Note

When integrating, \(\mathbf{q}\) has to preserve the property of a unit quaternion (or an integration method that preservers this has to be used, see Section A.1.7).

10.2 Differential Flatness

Details are in (Faessler, Franchi, and Scaramuzza 2018) (Appendix A).

10.3 Invariance

The dynamics are translation-invariant.

10.4 Controllers

10.4.1 Geometric Controller

This controller was proposed in (Lee, Leok, and McClamroch (2010)).

  • Given reference trajectory tuple: \(\mathbf{r}_d = (\ddddot{\mathbf{p}}_d(t), \dddot{\mathbf{p}}_d(t), \ddot{\mathbf{p}}_d(t), \dot{\mathbf{p}}_d(t), \mathbf{p}_d(t), \psi_d(t), \dot{\psi}_d(t), \ddot{\psi}_d(t))\) (i.e, desired snap, jerk, acceleration, velocity, position, heading, angular velocity for heading, acceleration for heading)
  • \(\mathbf{K}_p, \mathbf{K}_v, \mathbf{K}_R, \mathbf{K}_\omega \in\mathbb R^{3\times 3}\) are tuning matrices (typically only positive diagonal entries, so 12 parameters)
  • Control law: \[\begin{aligned} \mathbf{e}_p &= \mathbf{p}_d - \mathbf{p}\\ \mathbf{e}_v &= \dot{\mathbf{p}}_d - \dot{\mathbf{p}}\\ \mathbf{e}_R &= \frac{1}{2} \left( \mathbf{R}^\top_d \mathbf{R}- \mathbf{R}^\top \mathbf{R}_d \right)^\vee\\ \mathbf{e}_\omega &= \boldsymbol{\omega}- \mathbf{R}^\top \mathbf{R}_d \boldsymbol{\omega}_d\\ f &= m(\ddot{\mathbf{p}}_d + \mathbf{K}_p \mathbf{e}_p + \mathbf{K}_v \mathbf{e}_v + g \mathbf{e}_z) \cdot \mathbf{R}\mathbf{e}_z\\ \boldsymbol{\tau}_u &= -\mathbf{K}_R \mathbf{e}_R - \mathbf{K}_\omega \mathbf{e}_\omega + \boldsymbol{\omega}\times \mathbf{J}\boldsymbol{\omega}- \mathbf{J}(\hat{\boldsymbol{\omega}} \mathbf{R}^\top \mathbf{R}_d \boldsymbol{\omega}_d - \mathbf{R}^\top \mathbf{R}_d \dot{\boldsymbol{\omega}}_d)\\ (\omega_1^2, \ldots, \omega_N^2)^\top &= \mathbf{B}^{-1} (f, \boldsymbol{\tau}_u)^\top \text{(or solving a QP, see also action mixing below.)} \end{aligned} \] where \((\cdot)^\vee\) is defined below Equation A.9.

The additional reference signals \(\mathbf{R}_d\), \(\boldsymbol{\omega}_d\), and \(\dot{\boldsymbol{\omega}}_d\) can be computed via differential flatness as follows:

\[ \begin{aligned} \mathbf{x}_{c_d} &= \begin{bmatrix} \cos(\psi_d) & \sin(\psi_d) & 0\end{bmatrix}^\top & \mathbf{y}_{c_d} &= \begin{bmatrix} -\sin(\psi_d) & \cos(\psi_d) & 0\end{bmatrix}^\top\\ \mathbf{x}_{b_d} &= n(\mathbf{y}_{c_d} \times \mathbf{F}_d) & \mathbf{y}_{b_d} &= n(\mathbf{F}_d \times \mathbf{x}_{b_d}) & \mathbf{z}_{b_d} &= \mathbf{x}_{b_d} \times \mathbf{y}_{b_d}\\ \mathbf{R}_d &= \begin{bmatrix} \mathbf{x}_{b_d} & \mathbf{y}_{b_d} & \mathbf{z}_{b_d} \end{bmatrix}\\ c &= \mathbf{z}_{b_d}^\top (\ddot{\mathbf{p}}_d + g \mathbf{e}_z) & d_1 &= \mathbf{x}_{b_d}^\top \dddot{\mathbf{p}}_d & d_2 &= -\mathbf{y}_{b_d}^\top \dddot{\mathbf{p}}_d \\ b_3 &= -\mathbf{y}_{c_d}^\top \mathbf{z}_{b_d} & c_3 &= \| \mathbf{y}_{c_d} \times \mathbf{z}_{b_d} \| & d_3 &= \dot \psi_d \mathbf{x}_{c_d}^\top \mathbf{x}_{b_d}\\ \omega_x &= \frac{d_2}{c} & \omega_y &= \frac{d_1}{c} & \omega_z &= \frac{c d_3 - b_3 d_1}{c c_3}\\ \boldsymbol{\omega}_d &= \begin{bmatrix} \omega_x & \omega_y & \omega_z \end{bmatrix}^\top\\ \dot{c} &= \mathbf{z}_b^\top \dddot{\mathbf{p}}\\ e_1 &= \mathbf{x}_{b_d}^\top \ddddot{\mathbf{p}}_d - 2\dot{c} \omega_y - c \omega_x \omega_z & e_2 &= -\mathbf{y}_{b_d}^\top \ddddot{\mathbf{p}}_d - 2\dot{c} \omega_x + c \omega_y \omega_z & e_3 &= \ddot{\psi}_d \mathbf{x}_{c_d}^\top \mathbf{x}_{b_d} + 2 \dot{\psi}_d \omega_z \mathbf{x}_{c_d}^\top \mathbf{y}_{b_d} \\ &&&&&- 2 \dot{\psi}_d \omega_y \mathbf{x}_{c_d}^\top \mathbf{z}_{b_d} - \omega_x \omega_y \mathbf{y}_{c_d}^\top \mathbf{y}_{b_d} \\ &&&&&- \omega_x \omega_z \mathbf{y}_{c_d}^\top \mathbf{z}_{b_d}\\ \dot{\omega}_x &= \frac{e_2}{c}& \dot{\omega}_y &= \frac{e_1}{c}& \dot{\omega}_z &= \frac{c e_3 - b_3 e_1}{c c_3}\\ \dot{\boldsymbol{\omega}}_d &= \begin{bmatrix} \dot{\omega}_x & \dot{\omega}_y & \dot{\omega}_z \end{bmatrix}^\top \end{aligned} \]

Note

Note that \(\omega_z\) is wrong in (Mellinger and Kumar 2011). Details are in (Faessler, Franchi, and Scaramuzza 2018) (Appendix A), from which we obtained the results.

10.4.2 Action Mixing

10.5 Useful Parameters

10.5.1 crazyflie-21

Commercially off-the-shelves (Cots) robot: Crazyflie 2.1

\[ \begin{aligned} \mathcal{U}&= [524, 2760]^4 rad/s\\ N &= 4\\ m &= 0.034 kg\\ \mathbf{B}&= \begin{bmatrix} \kappa_F & \kappa_F & \kappa_F & \kappa_F\\ -\kappa_F a & -\kappa_F a & \kappa_F a & \kappa_F a\\ -\kappa_F a & \kappa_F a & \kappa_F a & -\kappa_F a\\ -\kappa_\tau & \kappa_\tau & -\kappa_\tau & \kappa_\tau \end{bmatrix}\\ \kappa_F &= 2.023532265845548e-08\\ \kappa_\tau &= 1.214119359507329e-10\\ a &= \frac{1}{\sqrt 2} 0.046 m\\ \mathbf{J}&= \begin{bmatrix} 16.571710e-6 & 0 & 0\\ 0 & 16.655602e-6 & 0\\ 0 & 0 & 29.261652e-6 \end{bmatrix}\\ g &= 9.81 kg / s^2\\ \end{aligned} \]

10.5.2 quad3d_v0

Identical to “crazyflie-21”, but with additional state space bounds (Hönig, Ortiz-Haro, and Toussaint (2022); Ortiz-Haro et al. (2024)):

\[\begin{aligned} \mathbf{v}\in [-4,4]^3\\ \boldsymbol{\omega}\in [-8,8]^3 \end{aligned}\]

10.5.3 quad3d_v1

Here the action space is directly force/torque, i.e., \((f,\boldsymbol{\tau}_u)^\top \in \mathcal{U}\). This dramatically simplifies planning and is used, for example in OMPL.APP

\[ \begin{aligned} \mathcal{U}&= [5, 15] \times [-1, 1]^3\\ m &= 1\\ \mathbf{J}&= \begin{bmatrix} 1 & 0 & 0\\ 0 & 1 & 0\\ 0 & 0 & 1 \end{bmatrix}\\ g &= 9.81 kg / s^2\\ \mathbf{v}\in [-1,1]^3\\ \boldsymbol{\omega}\in [-1,1]^3 \end{aligned} \]

10.5.4 quad3d_v2

Similar to “quad3d_v2”, but with different bounds. This appeared in (Ortiz-Haro et al. (2024)) as “Quadrotor v1”.

\[ \begin{aligned} \mathcal{U}&= [0, 15] \times [-2, 2]^3\\ \mathbf{v}&\in [-4,4]^3\\ \boldsymbol{\omega}&\in [-8,8]^3 \end{aligned} \]

10.5.5 crazyflie-21plus

Commercially off-the-shelves (Cots) robot: Crazyflie 2.1+

\[ \begin{aligned} \mathcal{U}&= [1370, 3390]^4 rad/s\\ N &= 4\\ m &= 0.034 kg\\ \mathbf{B}&= \begin{bmatrix} \kappa_F & \kappa_F & \kappa_F & \kappa_F\\ -\kappa_F a & -\kappa_F a & \kappa_F a & \kappa_F a\\ -\kappa_F a & \kappa_F a & \kappa_F a & -\kappa_F a\\ -\kappa_\tau & \kappa_\tau & -\kappa_\tau & \kappa_\tau \end{bmatrix}\\ \kappa_F &= 1.4346289961914151e-08\\ \kappa_\tau &= 1.0032209789778871e-10\\ a &= \frac{1}{\sqrt 2} 0.046 m\\ \mathbf{J}&= \begin{bmatrix} 16.571710e-6 & 0 & 0\\ 0 & 16.655602e-6 & 0\\ 0 & 0 & 29.261652e-6 \end{bmatrix}\\ g &= 9.81 kg / s^2\\ \end{aligned} \]

10.5.6 crazyflie-21brushless

Commercially off-the-shelves (Cots) robot: Crazyflie 2.1 Brushless

Model see (Gräfe et al. 2026).