The physics of multicopter drones [In Progress]
This article summarizes the physics governing flight of a drone. It also provides convenient python code for these calculations. This work was adapted from my publication at AIAA DASC 2023 about multirotor
, a python simulation framework for drones. The notation here borrows heavily from the excellent work by Charles Tytler.
The following topics are covered, in order:
- The state variables used to describe the vehicle. Accounting for the effects of different reference frames.
- The forces and moments acting on the vehicle in its local reference frame.
- Using the forces/moments to calculate the change in state variables.
- How propellers and motors are able to generate the forces and torques.
- Determining exactly how much force and torque to generate to control the vehicle.
Describing the vehicle
A multi-rotor UAV is modeled with six degrees of freedom: the three spatial coordinates for position: $x, y, z$, and the three Euler angles for orientation: $\phi, \theta, \psi$.
Two reference frames are used for representing the state of the body:
- Inertial, nominal reference frame $n$ is the static frame of reference where the axes are aligned with arbitrary, global directions. They are represented as $\hat{n} = [\hat{x}, \hat{y}, \hat{z}]$.
- Body-fixed reference frame $b$ has the axes aligned with respect to the center of gravity of the rigid body in motion. They are represented as $\hat{b} = [\hat{b}_1, \hat{b}_2, \hat{b}_3]$. The body frame moves and rotates with the vehicle. Consider the origin of the body frame attached to the center of mass of the drone.
Position representation
Orientation representation
Orientation of a body in the inertial reference frame follows the Tait-Bryan angles convention. That is, orientation can be described by three sequential rotations: yaw ($\psi$), pitch ($\theta$), and roll ($\phi$) - in that order. The order of rotations matters. Starting from the inertial frame, yaw $\psi$ is rotation $R(\psi)$ of the body frame about the inertial $z$ axis. Pitch $\theta$ is rotation about the $y$ axis after the first rotation of the inertial frame: $R(\theta)\cdot R(\psi)$. And roll $\phi$ is the final rotation about the $x$ axis of the frame after the prior two rotations. The final product is the body reference frame.
By convention, the right handed coordinate system is followed. The direction of the positive $x$ axis in the body frame ($b_1$) is considered “forward”/North orientation. The positive $y$ axis ($b_2$) is “right”/East and the positive $z$ axis ($b_3$) is “down”. For rotations about each axis, positive rotation is counter-clockwise, looking at the positive rotation axis coming out of the page.
Reconciling inertial and body frames
A body frame may be different from the intertial frame due to (1) displacement and (2) rotation. The body frame’s origin is fixed to the origin of the UAV. Therefore, the displacement of the body frame from the inertial frame is the inertial position of the UAV: $\hat{r}^n=[x,y,z]^T$.
A vector relative to the origin of the body frame will appear rotated if displaced to the origin of the inertial frame. Given a vector in the inertial frame $\hat{\mathcal{V}}^n=[x,y,z]^T$ and the same vector displaced to the body frame $\hat{\mathcal{V}}^b=[b_1,b_2,b_3]^T$, the rotation matrix from the inertial to body reference frames $R_n^b$ is defined as:
$$ \begin{align} \hat{\mathcal{V}}^b &= R(\phi)\cdot R(\theta) \cdot R(\psi) \cdot \hat{\mathcal{V}}^n \\ \hat{\mathcal{V}}^b &= R_n^b \hat{\mathcal{V}}^n \\ \begin{bmatrix} b_1 \\ b_2 \\ b_3 \end{bmatrix} &= \begin{bmatrix} c\theta c\psi & c\theta s\psi & -s\theta \\ -c\phi s\psi + s\phi s\theta c\psi & c\phi c\psi + s\phi s\theta s\psi & s\psi c\theta \\ s\phi s\psi + c\phi s\theta c\psi & -s\phi c\psi + c\phi s\theta s\psi & c\psi c\theta \end{bmatrix} \begin{bmatrix} x \\ y \\ z \end{bmatrix} \end{align} $$
Here $c | s$ of $\phi | \theta | \psi$ refer to the cosine and sin respectively. This rotation is useful when looking at forces acting in the body frame from an inertial viewpoint. The above transforms a vector instantaneously between rotated reference frames.
Reconciling derivatives in rotating frames
If, however, the vector is changing while the reference frame is rotating, then the rate of change is not as simple. The rate of change of a vector is due to (1) the changing vector in its own frame itself, and (2) the rate of change of the rotating frame.
That is, in a body frame rotating with instantaneous angular velocity $\hat{\omega}=[\omega_x,\omega_y,\omega_z]$ about its axes, the time-derivative of a vector in a rotating body frame $\hat{\mathcal{V}}^b = \hat{\mathcal{V}} \cdot \hat{b}$ as measured in the body frame is given by the Transport theorem:
$$ \begin{align} \frac{d \hat{\mathcal{V}}^b}{d t} &= \frac{d \hat{\mathcal{V}}}{d t} \cdot \hat{b} + \frac{d \hat{b}}{d t} \cdot \hat{\mathcal{V}} \\ &= \frac{d \hat{\mathcal{V}}}{d t} \cdot \hat{b} + \hat{\omega} \times \hat{\mathcal{V}}^b \\ &= \frac{d \hat{\mathcal{V}}}{d t} \cdot \hat{b} + \begin{bmatrix} 0 & -\omega_z & \omega_y \\ \omega_z & 0 & -\omega_x \\ -\omega_y & \omega_x & 0 \end{bmatrix} \hat{\mathcal{V}} \end{align} $$
This can be used to integrate accelerations in the body frame to find body-frame velocity.
The state of the vehicle
Tracking the motion of the vehicle requires tracking multiple variables. The variables can be divided into translational and their rotational analogues.
- $\hat{r}^n=[x,y,z]$ are the navigation coordinates in the inertial frame.
- $\hat{v^b}=[\dot{\hat{v^b}_1}, \dot{\hat{v^b}_2}, \dot{\hat{v^b}_3}]$ is the velocity of the vehicle along the body frame axes.
- $\hat{\Phi}=[\phi, \theta, \psi] $ is the orientation of the body reference frame $b$ in Euler angles (roll, pitch, yaw) with reference to the inertial reference frame.
- $\hat{\omega}=[\omega_x, \omega_y, \omega_z]$ is the roll rate of the three body frame axes.
Dynamics of multi-rotor UAVs
The state variables above are affected by the forces and torques acting on the body.
- $\hat{F}^b=[F_{b_1},F_{b_2},F_{b_3}]$ are the net forces along the three body frame axes, where $\hat{F}^b=R_n^b \hat{F}^n$.
- $\hat{M}^b=[M_{b_1},M_{b_2},M_{b_3}]$ are the moments along the three body axes, where $\hat{M}^b=R_n^b \hat{M}^n$.
The multirotor is modeled as a rigid body. A rigid body has a constant mass distribution relative to its center of gravity. Fundamental to the dynamics is Newton’s second law of motion:
$$ \begin{align} F = m \cdot a \end{align} $$
And its rotational analogue:
$$ \begin{align} r \times F &= r \times (m \cdot a) \\ M &= I \cdot \frac{d\omega}{dt} \end{align} $$
Where $I$ is the moment of inertia, also known as angular mass. These two relationships can be used to calculate how the state variables change over time.
Equations of motion
The equations of motion relate the state variables to the dynamics of the system. In this case, the equations are solved in the body frame.
The above relationship can be re-written as using the abstraction provided by the Transport Theorem. This will give the force acting on the body according to the inertial frame:
$$ \begin{align} \hat{F}^b &= m(\hat{\dot{v}}^b + \hat{\omega} \times \hat{v}^b) \end{align} $$
For rotational variables a similar analogue exists. Given $M^b$ is the rotating body-frame moment, $\omega$ is the angular rate measured in the body frame (subject to the Coriolis effect), and $I$ is the moment of inertia:
$$ \begin{align} \hat{r}^b \times \hat{F}^b &= m \cdot \hat{r}^b \times \hat{\dot{v}}^b \\ \hat{M}^b &= \hat{I} \hat{\dot{\omega}} \\ \hat{M}^b &= \hat{I}\hat{\dot{\omega}} + \hat{\omega} \times \hat{I}\hat{\omega} \end{align} $$
Linear variables
The linear state variables ($\hat{r}^n$, $\hat{v}^b$) are determined primarily by the forces acting on the vehicle. The force of gravity $\hat{F_g}^n=[0,0,-mg]$ in the nominal reference frame. In the body frame it becomes $\hat{F_g}^b=R^b_n \hat{F}^n$. The net force of the $p$ propellers in the body frame is $\hat{F_p}^b=[0,0,\sum_i^p T_i]$. Thus, the total force acting on the center of mass is $\hat{F}^b=\hat{F_p}^b + \hat{F_g}^b$. Thus solving for acceleration $\hat{\dot{v}}^b$ and equating with the acceleration acting on the body frame $\hat{F}^b / m$ yields the rate of change of velocity $\hat{v}^b$ in the body frame.
Using $R_b^n$ and the current body frame velocity $\hat{v}^b$ gives the rate of change of position $r^n$ in the inertial frame.
Angular variables
The angular state variables ($\hat{\omega}$, $\hat{\Phi}$) are governed by the moments acting on the body. The moments due to thrust acting on the propeller arm for each propeller are $\hat{M}_T^b=\sum_i^p r_i \times T_i$. The yaw moments about $b_3$ due to the rotation of the motor are given by $\hat{M}_\tau^b=\sum_i^p \tau_i$. The total moments about the body are $\hat{M}^b=\hat{M}_T^b+\hat{M}_\tau^b$. Solving the torque equation for $\hat{\omega}$, and substituting these moments, yields the rate of change of angular rate $\hat{\omega}$ in the body frame.
The rate of change of orientation $\hat{\Phi} = [\dot{\phi}, \dot{\theta}, \dot{\psi}]$ is related to the angular rate $\hat{\omega}$. The angular rate is the instantaneous rotation rate of the body axes. Whereas each angle of orientation is defined in its own reference frame during a sequence of ordered rotations from the inertial axes to the body frame (yaw, pitch, roll). Solving this quation gives the rate of change of orientation.
$$ \begin{bmatrix} p \\ q \\ r \end{bmatrix} = R(\phi)\cdot R(\theta) \begin{bmatrix} 0 \\ 0 \\ \dot{\psi} \end{bmatrix} + R(\phi) \begin{bmatrix} 0 \\ \dot{\theta} \\ 0 \end{bmatrix} + \begin{bmatrix} \dot{\phi} \\ 0 \\ 0 \end{bmatrix} $$
The rates of changes of the 12 (linear and angular) state variables can be integrated to track the state of the vehicle.
$$ \begin{align} \begin{bmatrix} \dot{\hat{r^n}_1} \\ \dot{\hat{r^n}_2} \\ \dot{\hat{r^n}_3} \\ \\ \dot{\hat{v^b}_1} \\ \dot{\hat{v^b}_2} \\ \dot{\hat{v^b}_3} \\ \\ \dot{\phi} \\ \dot{\theta}\\ \dot{\psi} \\ \\ \dot{\hat{\omega}} \end{bmatrix} = \begin{bmatrix} c_\theta c_\psi \hat{v^b}_1 + (-c_\phi s_\psi + s_\phi s_\theta c_\psi) \hat{v^b}_2 + (s_\phi s_\psi+c_\phi s_\theta c_\psi) \hat{v^b}_3 \\ c_\theta s_\psi \hat{v^b}_1 + (c_\phi c_\psi+s_\phi s_\theta s_\psi) \hat{v^b}_2 + (-s_\phi c_\psi+c_\phi s_\theta s_\psi) \hat{v^b}_3 \\ (-s_\theta \hat{v^b}_1 + s_\phi c_\theta \hat{v^b}_2 + c_\phi c_\theta \hat{v^b}_3) \\ \\ \frac{m}{F_x} + g s_\theta + \omega_3 \hat{v^b}_2 - \omega_2 \hat{v^b}_3 \\ \frac{m}{F_y} - g s_\phi c_\theta - \omega_3 \hat{v^b}_1 + \omega_1 \hat{v^b}_3 \\ \frac{m}{F_z} - g c_\phi c_\theta + \omega_2 \hat{v^b}_1 - \omega_1 \hat{v^b}_2 \\ \\ \omega_1 + (\omega_2 s_\phi + \omega_3 c_\phi) s_\theta / c_\theta \\ \omega_2 c_\phi - \omega_3 s_\phi \\ (\omega_2 s_\phi + \omega_3 c_\phi) / c_\theta \\ \\ I^{-1} \cdot (\hat{\tau} - \hat{\omega} \times I \cdot \hat{\omega}) \end{bmatrix} \end{align} $$
|
|
Generating forces and torques
Propellers
Given the propeller geometry parameters, the thrust is modeled by numerically solving the equation for thrust and propeller induced velocity. An alternate approach, relating the thrust constant and propeller velocity can be used as well.
$$ \begin{align} T = k_{T} \cdot \Omega^2 \end{align} $$
Torque about the yaw axis is modeled as aerodynamic drag, which is equal to the net BLDC motor torque $\tau_{BLDC}$ near hover conditions. Given the drag coefficient $k_d$,
$$ \begin{align} \tau = k_{d} \cdot \Omega^2 \end{align} $$
Motors
The environment models brushless direct current (BLDC) motors independently as sub-objects. Each motor is parameterized by the back electromotive force constant, $k_e$, and the internal resistance $R_{BLDC}$. The torque constant $k_\tau$ is equal to $k_e$ for an ideal square-wave BLDC. $k_\tau$ determines the driving moment of the motor. Dissipative moments are governed by the dynamic friction constant $k_{DF}$, and the aerodynamic drag constant $k_d$. Finally, the net moments $\tau$ and the moment of inertia $J$ of the motor determine how fast the rotor spins. The state of each motor is its angular velocity $\Omega$, applied voltage $v_{BLDC}$, and drawn current $i_{BLDC}$. The dynamics are given by this equation:
$$ \begin{align} i_{BLDC} &= (v_{BLDC} - k_e \cdot \Omega ) / R_{BLDC}\\ \tau_{BLDC} &= k_\tau \cdot i_{BLDC} \\ \tau &= \tau_{BLDC} - k_{DF}\cdot\Omega - k_d\cdot\Omega^2 \\ \frac{d \Omega}{dt} &= \tau / J \end{align} $$
Control
Control mixing is the procedure of relating the net dynamics (forces and moments) about the vehicle body $D$, to the rotational speeds of the propellers $\hat{\Omega}$. Due to geometry, the lateral forces on the body from the propeller are zero, thus $F_{b_2}=F_{b_3}=0$. Moments about $b_1$ and $b_2$ are determined by the moment arm $r_{arm}$ and thrust $r_{arm} \times T$. Yaw moments about $b_3$ are determined by the torque equation. Putting these relationships together yields the control allocation matrix, and a system of equations linear in $\Omega^2$. Thus, the prescribed dynamics $D$ from the controller can be converted to the prescribed propeller speeds $\Omega$ for each motor:
$$ \begin{align} \begin{bmatrix} F_{b_1} \\ F_{b_2} \\ F_{b_3} \\ M_{b_1} \\ M_{b_2} \\ M_{b_3} \end{bmatrix} &= \underset{6 \times 1}{D} = \underset{6 \times p}{A} \cdot \underset{p \times 1}{\hat{\Omega}^2} \\ \hat{\Omega} &= \sqrt{A^{-1} \cdot D} \end{align} $$
For a propeller $p$ with a thrust coefficient $k_{th,p}$, a drag coefficient $k_{dr,p}$, at a radius $r_p$ from the center of mass and angle $\theta_p$ from the reference forward direction in the vehicle’s frame of reference, and where propellers are alternatively spinning clockwise and counter-clockwise,
$$ \begin{align} A = \begin{bmatrix} \cdots & k_{th,i} & \cdots \\ \cdots & k_{th,i} \cdot r_p \sin(\theta_i) & \cdots \\ \cdots & k_{th,i} \cdot r_p \cos(\theta_i) & \cdots \end{bmatrix} \end{align} $$
A cascaded PID controller is implemented for position and attitude tracking. A supervisory position PID controller tracks measured lateral velocities and outputs the required pitch and roll needed to reach a specified way-point. A lower-level attitude controller then tracks the pitch, roll, and yaw velocities and outputs the required torques. In parallel, a PID controller tracks vertical velocity and outputs the thrust needed. The eventual output of the cascaded PID setup is the prescribed thrust, and the roll, pitch, and yaw torques. These prescribed dynamics are then allocated via control mixing to the motors.
The standard control logic flow of UAVs is depicted in the following figure. In this standard end-to-end approach, the position reference is converted into propeller speed signals
The cascaded PID controller converts position/yaw references into the desired dynamics (forces and torques, $F_z,\tau_x,\tau_y,\tau_z$) to achieve that reference position and yaw. The control output $u_{PID}$ aims to minimize the input error $e=\texttt{reference}-\texttt{measurement}$ with respect to the reference and measured states.:
$$ \begin{align} u_{PID} = k_p e + k_d \nabla_t e + k_i \int_0^t e \partial t \end{align} $$
≡
Ibrahim Ahmed