Reduced-order model for UAV
Robotics System Toolbox UAV Library
This block requires you to install the UAV Library for Robotics System
Toolbox™. To install add-ons, use roboticsAddons
and select the desired add-on.
The UAV Guidance Model block represents a small unmanned aerial vehicle (UAV) guidance model that estimates the UAV state based on control and environmental inputs. The model approximates the behavior of a closed-loop system consisting of an autopilot controller and a fixed-wing or multirotor kinematic model for 3-D motion. Use this block as a reduced-order guidance model to simulate your fixed-wing or multirotor UAV. Specify the ModelType to select your UAV type. Use the Initial State tab to specify the initial state of the UAV depending on the model type. The Configuration tab defines the control parameters and physical parameters of the UAV.
Control
— Control commandsControl commands sent to the UAV model, specified as a bus. The name of the input bus is specified in Input/Output Bus Names.
For multirotor UAVs, the model is approximated as separate PD controllers for each command. The elements of the bus are control command:
Roll
- Roll angle in radians.
Pitch
- Pitch angle in radians.
YawRate
- Yaw rate in radians per second. (D = 0. P only
controller)
Thrust
- Vertical thrust of the UAV in Newtons. (D = 0. P
only controller)
For fixed-wing UAVs, the model assumes the UAV is flying under the coordinated-turn condition. The guidance model equations assume zero side-slip. The elements of the bus are:
Height
- Altitude above the ground in meters.
Airspeed
- UAV speed relative to wind in meters per
second.
RollAngle
- Roll angle along body forward axis in
radians. Because of the coordinated-turn condition, the heading angular rate is
based on the roll angle.
Environment
— Environmental inputsEnvironmental inputs, specified as a bus. The model compensates for these environmental inputs when trying to achieve the commanded controls.
For fixed-wing UAVs, the elements of the bus are WindNorth
,
WindEast
,WindDown
, and
Gravity
. Wind speeds are in meters per second and negative speeds
point in the opposite direction. Gravity
is in meters per second
squared.
For multirotor UAVs, the only element of the bus is Gravity
in
meters per second squared.
Data Types: bus
State
— Simulated UAV stateSimulated UAV state, returned as a bus. The block uses the
Control
and Environment
inputs with the
guidance model equations to simulate the UAV state.
For multirotor UAVs, the state is a five-element bus:
WorldPosition - [x y z]
in
meters.
WorldVelocity - [vx vy vz]
in meters
per second.
EulerZYX - [psi phi theta]
Euler
angles in radians.
BodyAngularRateRPY - [r p q]
in
radians per second along the xyz
-axes of the UAV.
Thrust - F
in Newtons.
For fixed-wing UAVs, the state is an eight-element bus:
North - Position in north direction in meters.
East - Position in east direction in meters.
Height - Height above ground in meters.
AirSpeed - Speed relative to wind in meters per second.
HeadingAngle - Angle between ground velocity and north direction in radians.
FlightPathAngle - Angle between ground velocity and north-east plane in radians.
RollAngle - Angle of rotation along body x-axis in radians per second.
RollAngleRate - Angular velocity of rotation along body x-axis in radians per second.
Data Types: bus
ModelType
— UAV guidance model typeMultirotorGuidance
(default) | FixedWingGuidance
UAV guidance model type, specified as MultirotorGuidance
or
FixedWingGuidance
. The model type determines the elements of the
UAV State
and the required Control
and
Environment
inputs.
Tunable: No
DataType
— Input and output numeric data typesdouble
(default) | single
Input and output numeric data types, specified as either double
or single
. Choose the data type based on possible software or
hardware limitations.
Tunable: No
Simulate using
— Type of simulation to runInterpreted execution
(default) | Code generation
Code generation
— Simulate model using
generated C code. The first time you run a simulation, Simulink® generates C code for the block. The C code is reused for subsequent
simulations, as long as the model does not change. This option requires additional
startup time, but the speed of the subsequent simulations is comparable to
Interpreted execution
.
Interpreted execution
— Simulate model using
the MATLAB® interpreter. This option shortens startup time but has a slower
simulation speed than Code generation
. In this mode, you
can debug the source code of the block.
Tunable: No
Initial State
— Initial UAV state tabInitial UAV state tab, specified as multiple table entries. All entries on this tab are nontunable.
For multirotor UAVs, the initial state is:
World Position - [x y z]
in
meters.
World Velocity - [vx vy vz]
in meters
per second.
Euler Angles (ZYX) - [psi phi theta]
in radians.
Body Angular Rates - [p q r]
in
radians per second.
Thrust - F
in Newtons.
For fixed-wing UAVs, the initial state is:
North - Position in north direction in meters.
East - Position in east direction in meters.
Height - Height above ground in meters.
Air Speed - Speed relative to wind in meters per second.
Heading Angle - Angle between ground velocity and north direction in radians.
Flight Path Angle - Angle between ground velocity and north-east plane in radians.
Roll Angle - Angle of rotation along body x-axis in radians per second.
Roll Angle Rate - Angular velocity of rotation along body x-axis in radians per second.
Tunable: No
Configuration
— UAV controller configuration tabUAV controller configuration tab, specified as multiple table entries. This tab allows you to configure the parameters of the internal control behaviour of the UAV. Specify the proportional (P) and derivative (D) gains for the dynamic model and the UAV mass in kilograms (for multirotor).
For multirotor UAVs, the parameters are:
PD Roll
PD Pitch
P YawRate
P Thrust
Mass(kg)
For fixed-wing UAVs, the parameters are:
P Height
P Flight Path Angle
PD Roll
P Air Speed
Min/Max Flight Path Angle ([min max]
angle in radians)
Tunable: No
Input/Output Bus Names
— Simulink bus signal names tabSimulink bus signal names tab, specified as multiple entries of character vectors. These buses have a default name based on the UAV model and input type. To use multiple guidance models in the same Simulink model, specify different bus names that do not intersect. All entries on this tab are nontunable.
The UAV Library for Robotics System Toolbox uses the North-East-Down (NED) coordinate system convention, which is also sometimes called the local tangent plane (LTP). The UAV position vector consists of three numbers for position along the northern-axis, eastern-axis, and vertical position. The down element complies with the right-hand rule and results in negative values for altitude gain.
The ground plane, or earth frame (NE plane, D = 0), is assumed to be an inertial plane that is flat based on the operation region for small UAV control. The earth frame coordinates are [xe,ye,ze]. The body frame of the UAV is attached to the center of mass with coordinates [xb,yb,zb]. xb is the preferred forward direction of the UAV, and zb is perpendicular to the plane that points downwards when the UAV travels during perfect horizontal flight.
The orientation of the UAV (body frame) is specified in ZYX Euler angles. To convert from the earth frame to the body frame, we first rotate about the ze-axis by the yaw angle, ψ. Then, rotate about the intermediate y-axis by the pitch angle, ϕ. Then, rotate about the intermediate x-axis by the roll angle, ϴ.
The angular velocity of the UAV is represented by [p,q,r] with respect to the body axes, [xb,yb,zb].
For fixed-wing UAVs, the following equations are used to define the
guidance model of the UAV. Use the derivative
function to calculate the time-derivative of the UAV state using these governing equations.
Specify the inputs using the state
,
control
,
and environment
functions.
The UAV position in the earth frame is [xe, ye, h] with orientation as heading angle, flight path angle, and roll angle, [χ, γ, ϕ] in radians.
The model assumes that the UAV is flying under a coordinated-turn condition, with zero side-slip. The autopilot controls airspeed, altitude, and heading angle. The corresponding equations of motion are:
Va and Vg denote the UAV air and ground speeds.
The wind speed is specified as
[Vwn,Vwe,Vwd]
for the north, east, and down directions. To generate the structure for these inputs, use
the environment
function.
k* are controller gains. To specify these gains,
use the Configuration
property of the fixedwing
object.
From these governing equations, the model gives the following variables:
These variables match the output of the state
function.
For multirotors, the following equations are used to define the guidance
model of the UAV. To calculate the time-derivative of the UAV state using these governing
equations, use the derivative
function. Specify the inputs using state
,
control
,
and environment
.
The UAV position in the earth frame is [xe, ye, ze] with orientation as ZYX Euler angles, [ψ, ϴ, ϕ] in radians. Angular velocities are [p, q, r] in radians per second.
The UAV body frame uses coordinates as [xb, yb, zb].
When converting coordinates from the world (earth) frame to the body frame of the UAV, the rotation matrix is:
The cos(x) and sin(x) are abbreviated as cx and sx.
The acceleration of the UAV center of mass in earth coordinates is governed by:
m is the UAV mass, g is gravity, and Fthrust is the total force created by the propellers applied to the multirotor along the –zb axis (points upwards in a horizontal pose).
The closed-loop roll-pitch attitude controller is approximated by the behavior of 2 independent PD controllers for the two rotation angles, and 2 independent P controllers for the yaw rate and thrust. The angular velocity, angular acceleration, and thrust are governed by:
This model assumes the autopilot takes in commanded roll, pitch, yaw angles,
[ψc,
ϴc,
ϕc] and a commanded total thrust
force, Fcthrust. The
structure to specify these inputs is generated from control
.
The P and D gains for the control inputs are specified as
KPα and
KDα, where α is either
the rotation angle or thrust. These gains along with the UAV mass, m, are
specified in the Configuration
property of the multirotor
object.
From these governing equations, the model gives the following variables:
These variables match the output of the state
function.
[1] Randal W. Beard and Timothy W. McLain. "Chapter 9." Small Unmanned Aircraft Theory and Practice, NJ: Princeton University Press, 2012.
[2] Mellinger, Daniel, and Nathan Michael. "Trajectory Generation and Control for Precise Aggressive Maneuvers with Quadrotors." The International Journal of Robotics Research. 2012, pp. 664-74.
control
| derivative
| environment
| ode45
| plotTransforms
| roboticsAddons
| state