SlideShare a Scribd company logo
1 of 4
Download to read offline
1
NEW ERA FOR PUBLIC TRANSPORATION: MODEL PREDICTIVE CONTROL FOR URBAN
AIR MOBILITY IN THE BAY AREA
Sonny Li (3035300139), Muireann Spain (3033516594), Shawn Marshall-Spitzbart (3035289739), David Tondreau
(3035296317), Anthony Yan (3035300282)
ABSTRACT
Using Model Predictive Control (MPC), an Unmanned
Arial Vehicle (UAV) is simulated flying in ℝ3
between set
destinations. The Constrained Finite Time Optimal Control
problem (CFTOC) is weighted to prioritize optimization of input
power, velocity and deviation from the reference trajectory.
Furthermore, the UAV is constrained to fly within an admissible
tube, limiting the UAV’s maximum displacement from the
reference trajectory. A link to the source code is provided below
in Appendix 8.1. Our project video is linked here:
https://www.youtube.com/watch?v=tJv9LQBCpm0&feature=yo
utu.be&fbclid=IwAR1J4QYwMSt9eecqPHOYh_UXFUAJWNx_
mTUNrLnsxF8mUO9pUgAc6m-Dc6Y
1. INTRODUCTION
To solve current challenges with dense traffic in the Bay
Area, our team strives to redefine public transportation by
utilizing UAVs. For this project, the optimization problem seeks
to minimize input power for a multiple passenger-sized UAV
along a reference trajectory between Berkeley, San Francisco,
and Palo Alto. The system dynamics of the UAV are defined by
a discretized linear dynamic model and holonomic constraints,
which include the displacement of the UAV to be within an
admissible tube from the reference trajectory.
2. QUADCOPTER PARAMETERS
Figure 1: Body-fixed frame UAV
The parameters of the UAV are outlined with the assumption
that the UAV is symmetric about the body-fixed 1 and 2 axes as
shown in Fig.1. Drawing inspiration from Boeing-Aurora Flight
Science’s Passenger Aerial Vehicle [11], the mass of the fully-
loaded passenger UAV was defined as 800 kg. The UAV
traverses using four motors orthogonal to one another, three
meters radially from the COM. Next, the mass moment of
inertias (𝑱𝑱) are defined as follows:
𝑱𝑱 = �
𝐽𝐽𝑥𝑥𝑥𝑥 0 0
0 𝐽𝐽𝑥𝑥𝑥𝑥 0
0 0 𝐽𝐽𝑧𝑧𝑧𝑧
� (1)
where,
𝐽𝐽𝑥𝑥𝑥𝑥 = ∑ 𝑚𝑚 𝑀𝑀[ (𝑠𝑠𝑖𝑖
2)2
+ (𝑠𝑠𝑖𝑖
3
)2]4
𝑖𝑖=1 (2)
𝐽𝐽𝑧𝑧𝑧𝑧 = ∑ 𝑚𝑚 𝑀𝑀[ (𝑠𝑠𝑖𝑖
1)2
+ (𝑠𝑠𝑖𝑖
2)2]4
𝑖𝑖=1 (3)
note that 𝐽𝐽𝑥𝑥𝑥𝑥 is equal to 𝐽𝐽𝑦𝑦𝑦𝑦 due to the symmetry of the UAV.
3. QUADCOPTER DYNAMICS
The state vector (z) defines the UAV’s position (s), velocity
(v), roll (ϕ), pitch (θ), and yaw (φ) angles, roll rate (p), pitch rate
(q), and yaw rate (r) in ℝ3
Euclidean space:
𝑧𝑧 =
⎣
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎡
𝑠𝑠1
𝑠𝑠2
𝑠𝑠3
𝑣𝑣1
𝑣𝑣2
𝑣𝑣3
𝜙𝜙
𝜃𝜃
𝜑𝜑
𝑝𝑝
𝑞𝑞
𝑟𝑟 ⎦
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎤
, 𝑧𝑧̇ =
⎣
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎢
⎡
𝑣𝑣1
𝑣𝑣2
𝑣𝑣3
𝜃𝜃 ∙ 𝑔𝑔
− 𝜙𝜙 ∙ 𝑔𝑔
𝐶𝐶Σ− 𝑚𝑚𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡∙𝑔𝑔
𝑚𝑚𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡
𝑝𝑝
𝑞𝑞
𝑟𝑟
𝑛𝑛1
𝐽𝐽𝑥𝑥𝑥𝑥
�
𝑛𝑛2
𝐽𝐽𝑥𝑥𝑥𝑥
�
𝑛𝑛3
𝐽𝐽𝑧𝑧𝑧𝑧
� ⎦
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎥
⎤
(4)
In Eqn.4, 𝑧𝑧̇ defines the linearized state derivatives, g is the
norm of the gravity tensor, C∑ is the sum of the four input forces,
and n are the input torques. To transform quadcopter propeller
forces into torques (n), a mixer matrix is introduced where l is
the perpendicular distance from each motor to the body-fixed 1
axis, and k is a proportionality constant (Eqn. 5).
2
�
𝐶𝐶Σ
𝑛𝑛1
𝑛𝑛2
𝑛𝑛3
� = �
1 1 1 1
𝑙𝑙 −𝑙𝑙 −𝑙𝑙 𝑙𝑙
−𝑙𝑙 −𝑙𝑙 𝑙𝑙 𝑙𝑙
𝜅𝜅 −𝜅𝜅 𝜅𝜅 −𝜅𝜅
� ∙ �
𝐶𝐶P1
𝐶𝐶P2
𝐶𝐶P3
𝐶𝐶P4
� (5)
Thus, using the mixer matrix, the four motor forces are utilized
as inputs to the system. Finally, the system propagation was
performed using the Forward Euler method:
𝑧𝑧𝑘𝑘+1 = 𝑧𝑧𝑘𝑘 + 𝑇𝑇𝑠𝑠 ∙ 𝑧𝑧𝑘𝑘̇ (6)
where Ts is the simulation time step and 𝑧𝑧̇ is the state derivative
vector.
To calculate the state derivative vector, 𝑧𝑧̇, the dynamics of
the UAV were linearized about a hover state following the
approach in [9]; in doing so, small angles, velocities, and angular
accelerations were assumed. To analyze this assumption, a
CFTOC was formulated using the linearized dynamics, and the
resultant optimal inputs were simulated with both the linear and
nonlinear dynamics as similarly completed in [1]. For roll and
pitch angles less than 30 degrees, the error between the linear
and nonlinear dynamics was found to be small (Fig.2). However,
when small angles were added as a constraint to the main
CFTOC described in Section 5, the solution was found to be
infeasible. Thus, creating a dynamically feasible trajectory,
given small angles, velocities, and angular accelerations, has
been left for future work.
Figure 2: Analysis of linearized dynamics vs nonlinear dynamics
where the y axes of the x and y position graphs is in meters, the y axes
of the roll and pitch graphs is in radians, and the x axes are in seconds
4. QUADCOPTER TRAJECTORY
The reference trajectory shown in Fig.3 was defined in ℝ3
.
The “drop-off locations” illustrated were derived by importing
geographical data of the Bay Area into MATLAB and manually
selecting the X and Y coordinates of our three destinations.
Terminal waypoints were discretized from the reference
trajectory to be implemented into our MPC algorithm. These
waypoints were propagated forward along the trajectory at
constant intervals of 5 m by utilizing a reference velocity of 50
m/s along with a time step of 0.1 s. This reference velocity
ensures that the UAV continues moving forward along the
trajectory at a constant rate. However, the implementation of
such a reference velocity disables the maximization of UAV
velocity.
Figure 3: Map of the Bay Area with the tube constraint shown in red
and the drop off locations labeled with triangles
In anticipation of a multitude of UAVs flying various
trajectories across the Bay area, a holonomic constraint was
designed to ensure that the radial displacement of the UAV from
the reference trajectory is within a virtual tube. To define this
constraint, a cubic interpolation is performed along the reference
trajectory for each iteration of the CFTOC function, with the
number of interpolated values equal to the prediction horizon, N.
Next, the position of the UAV is constrained to be within the
radius of the tube minus half of the width of the UAV at each of
the aforementioned interpolated steps along the trajectory. The
tube constraints are therefore manifested as cubes constraining
the X, Y, and Z positions of the UAV in the inertial frame to the
waypoints calculated along the reference trajectory at each step
from zero to the prediction horizon, N.
5. MODEL PREDICTIVE CONTROL FORMULATION
(7)
3
The MPC function utilizes four input propeller forces and
the 12 UAV states as decision variables. First, a CFTOC problem
is solved using the discretized linear dynamics described in
Section 3, the tube constraints described in Section 4, and a
quadratic objective function. Abstractly, the objective function
was weighted to minimize fuel consumption by primarily
minimizing the UAV’s propeller forces, while still penalizing
lateral and vertical deviation from the reference trajectory at each
discrete time step. The weights for P, Q, W, and R are given in
Appendix 8.3.
After solving each CFTOC iteration, the optimal inputs for
the initial time step are applied to the system. The system is then
simulated using the discretized linear dynamics for one time
step. The state of the system at the end of one sample time is
retrieved, then applied as the initial state for the next CFTOC
formulation. This procedure is repeated in a loop for the duration
of the MPC simulation horizon, M. In our case, the MPC
algorithm terminates when the UAV reaches within a defined
tolerance of the final waypoint.
6. RESULTS AND DISCUSSION
The UAV successfully lifted off from Berkeley and
followed a user-defined flight path, landing on various
destinations without violating the radial tube constraint of 50
m. Fig.4 illustrates the UAV, depicted as a ‘*’, with the
reference trajectory depicted in red and the MPC path traveled
in black. It was necessary to set the prediction horizon value, N,
to the sufficiently high value of 35 to guarantee feasibility of
the MPC function with constraints. The simulation horizon was
defined to terminate the MPC loop once the UAV reached
sufficiently close to the final waypoint at 6100 steps. Fig.5
illustrates an example of the UAV following the reference
trajectory while obeying the virtual tube constraints.
The tube radius was initially defined at 10 m, but the MPC
formulation was infeasible as the rather sharp ascension/
descension portions of the ℝ3
curve were unsolvable to solve
given the UAV system dynamics and the tight constraints. A
tube radius of 50 meters enabled the desired path to be feasible
and therefore solvable.
Figure 4: The UAV makes three stops – Berkeley, San Francisco, and
Palo Alto – flying at height of 100m in-between stops
Figure 5: A sample trajectory of the UAV following part of the desired
trajectory within the tube constraint with axes in meters.
7. FUTURE WORK AND IMPROVEMENTS
The initial approach taken to formulate this problem was to
employ the Serret-Frenet frame attached to the reference
trajectory. Specifically, this frame would allow the UAV state
to be described by a curvilinear abscissa and displacement from
the abscissa to the UAV as done in [6] [7] [10] [12] [13] [14].
This frame greatly simplifies the formulation of vertical and
lateral position constraints along the reference trajectory by
creating an admissible tube where the UAV is permitted to
traverse. This approach was taken by [12] with great success
where a constant radius tube formed the width of the race track.
By using the Serret-Frenet frame, the constrained finite-time
optimal control problem effectively transforms a reference-
tracking problem to a reference-free trajectory-optimization
problem. The authors believe future work entails utilizing a
curvilinear abscissa in ℝ3
to formulate the MPC and solve for
the optimal trajectory between Berkeley, San Francisco, and
Palo Alto in real-time. Next, the authors believe that leveraging
Learning MPC to train for time-optimality [13], given
passenger-comfort constraints and an admissible tube radius,
could greatly reduce commute times between the three cities.
4
8. APPENDIX
8.1 Github: https://github.com/smarshall-
spitzbart/Advanced-Control-Design-Final-Project
8.2 Table 1: Numerical Values of UAV Parameters
Variable Numerical Value
R 3 m
α 45°
l 3/√2 m
k 0.01
mB 600 kg
mM 50 kg
𝐽𝐽𝑥𝑥𝑥𝑥 1.44E+04 kg-m2
𝐽𝐽𝑧𝑧𝑧𝑧 2.88E+04 kg-m2
8.3 Table 2: Numerical Values of Cost Function Weights
Variable Numerical Value
P I3
Q I3
W I3
R 10*I4
ACKNOWLEDGEMENTS
Special thanks to Francesco Borrelli and Mark Mueller for their
consultation during this project and their instruction over the
course of the semester.
REFERENCES
[1] Anand, Raghav. “MPC Control of Multiple Quadcopters
Cooperatively Lifting an Object,” 2018
[2] Brown, Matthew, “Safe Driving Envelopes for Path
Tracking in Autonomous Vehicles,” 2016
[3] Gray, Andrew, “Predictive Control for Agile Semi-
Autonomous Ground Vehicles using Motion Primitives,”
2012
[4] Hehn, Markus, “Quadcopter Trajectory Generation and
Control,” 2011
[5] Islam, Maidul, “Dynamics and Control of Quadcopter
Using Linear Model Predictive Control Approach,” 2017
[6] Lorenzetti, Joseph, “A Simple and Efficient Tube-based
Robust Output Feedback Model Predictive Control
Scheme,” 2019
[7] Lot, Robert, “A Curvilinear Abscissa Approach for the Lap
Time Optimization of Racing Vehicles,” 2014
[8] Micaelli, Alain, “Trajectory tracking for two-steering-
wheels mobile robots,” 1994
[9] Mueller, Mark. “Quadcopter Dynamics,” 2019
[10]Oulmas, Ali. “Closed-loop 3D path following of scaled-up
helical microswimmers,” 2016
[11]“PAV – Passenger Air Vehicle,” accessed 10th
December
2019, https://www.aurora.aero/pav-evtol-passenger-air-
vehicle/
[12]Rosollia, Ugo, “Autonomous Vehicle Control: A Nonconvex
Approach for Obstacle Avoidance,” 2016
[13]Samson, Claude, “Path Following And Time-Varying
Feedback Stabilization of a Wheeled Mobile Robot,” 1992
[14]Wang, Ye. “Nonlinear Model Predictive Control with
Constraint Satisfaction for a Quadcopter,” 2016
[15]Zhang, Xiaojing, “Optimization-Based Collision
Avoidance,” 2018

More Related Content

What's hot

Flight Dynamics Software Presentation Part II Version 7
Flight Dynamics Software Presentation Part II Version 7Flight Dynamics Software Presentation Part II Version 7
Flight Dynamics Software Presentation Part II Version 7Antonios Arkas
 
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...Project KRIT
 
E043036045
E043036045E043036045
E043036045inventy
 
Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...
  Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...  Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...
Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...Belinda Marchand
 
14 fixed wing fighter aircraft- flight performance - ii
14 fixed wing fighter aircraft- flight performance - ii14 fixed wing fighter aircraft- flight performance - ii
14 fixed wing fighter aircraft- flight performance - iiSolo Hermelin
 
CFD Final Report-2
CFD Final Report-2CFD Final Report-2
CFD Final Report-2Dwight Nava
 
Prediction tool for preliminary design assessment of the manoeuvring characte...
Prediction tool for preliminary design assessment of the manoeuvring characte...Prediction tool for preliminary design assessment of the manoeuvring characte...
Prediction tool for preliminary design assessment of the manoeuvring characte...Enrico Della Valentina
 
Ravasi_etal_EAGESBGF2014
Ravasi_etal_EAGESBGF2014Ravasi_etal_EAGESBGF2014
Ravasi_etal_EAGESBGF2014Matteo Ravasi
 
AROSAT_updated-spacesegment_presentation_NO_loghi
AROSAT_updated-spacesegment_presentation_NO_loghiAROSAT_updated-spacesegment_presentation_NO_loghi
AROSAT_updated-spacesegment_presentation_NO_loghiStefano Coltellacci
 
IRJET- Four Propellers Submarine Drone Modelling
IRJET- Four Propellers Submarine Drone ModellingIRJET- Four Propellers Submarine Drone Modelling
IRJET- Four Propellers Submarine Drone ModellingIRJET Journal
 
Ax32739746
Ax32739746Ax32739746
Ax32739746IJMER
 
Attitude determination of multirotors using camera
Attitude determination of multirotors using cameraAttitude determination of multirotors using camera
Attitude determination of multirotors using cameraRoberto Brusnicki
 
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...ijaia
 
Field work 1 (1)
Field work 1 (1)Field work 1 (1)
Field work 1 (1)Chee Lee
 

What's hot (19)

Flight Dynamics Software Presentation Part II Version 7
Flight Dynamics Software Presentation Part II Version 7Flight Dynamics Software Presentation Part II Version 7
Flight Dynamics Software Presentation Part II Version 7
 
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...
М.Г.Гоман, А.В.Храмцовский (1998) - Использование методов непрерывного продол...
 
Rail track geometry
Rail track geometryRail track geometry
Rail track geometry
 
E043036045
E043036045E043036045
E043036045
 
Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...
  Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...  Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...
Investigation Of Alternative Return Strategies for Orion Trans-Earth Inject...
 
14 fixed wing fighter aircraft- flight performance - ii
14 fixed wing fighter aircraft- flight performance - ii14 fixed wing fighter aircraft- flight performance - ii
14 fixed wing fighter aircraft- flight performance - ii
 
Satellite communication
Satellite communicationSatellite communication
Satellite communication
 
CFD Final Report-2
CFD Final Report-2CFD Final Report-2
CFD Final Report-2
 
Prediction tool for preliminary design assessment of the manoeuvring characte...
Prediction tool for preliminary design assessment of the manoeuvring characte...Prediction tool for preliminary design assessment of the manoeuvring characte...
Prediction tool for preliminary design assessment of the manoeuvring characte...
 
D04452233
D04452233D04452233
D04452233
 
Ravasi_etal_EAGESBGF2014
Ravasi_etal_EAGESBGF2014Ravasi_etal_EAGESBGF2014
Ravasi_etal_EAGESBGF2014
 
AROSAT_updated-spacesegment_presentation_NO_loghi
AROSAT_updated-spacesegment_presentation_NO_loghiAROSAT_updated-spacesegment_presentation_NO_loghi
AROSAT_updated-spacesegment_presentation_NO_loghi
 
surveying ii
surveying iisurveying ii
surveying ii
 
IRJET- Four Propellers Submarine Drone Modelling
IRJET- Four Propellers Submarine Drone ModellingIRJET- Four Propellers Submarine Drone Modelling
IRJET- Four Propellers Submarine Drone Modelling
 
Ss report 1
Ss report 1Ss report 1
Ss report 1
 
Ax32739746
Ax32739746Ax32739746
Ax32739746
 
Attitude determination of multirotors using camera
Attitude determination of multirotors using cameraAttitude determination of multirotors using camera
Attitude determination of multirotors using camera
 
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...
COMPLEMENTARY VISION BASED DATA FUSION FOR ROBUST POSITIONING AND DIRECTED FL...
 
Field work 1 (1)
Field work 1 (1)Field work 1 (1)
Field work 1 (1)
 

Similar to Mpc final report

Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Onyebuchi nosiri
 
Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Onyebuchi nosiri
 
Synthesis of Research Project-FlappingWing
Synthesis of Research Project-FlappingWingSynthesis of Research Project-FlappingWing
Synthesis of Research Project-FlappingWingKarthik Ch
 
Research Paper (ISEEE 2019)
Research Paper (ISEEE 2019)Research Paper (ISEEE 2019)
Research Paper (ISEEE 2019)EgemenBalban
 
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...IJRES Journal
 
PID vs LQR controller for tilt rotor airplane
PID vs LQR controller for tilt rotor airplane PID vs LQR controller for tilt rotor airplane
PID vs LQR controller for tilt rotor airplane IJECEIAES
 
A highly versatile autonomous underwater vehicle
A highly versatile autonomous underwater vehicleA highly versatile autonomous underwater vehicle
A highly versatile autonomous underwater vehicleAlwin Wilken
 
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...IJPEDS-IAES
 
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...IRJET Journal
 
An Unmanned Rotorcraft System with Embedded Design
An Unmanned Rotorcraft System with Embedded DesignAn Unmanned Rotorcraft System with Embedded Design
An Unmanned Rotorcraft System with Embedded DesignIOSR Journals
 
Research Article - Automation of an excavator boom movement in 3D
Research Article - Automation of an excavator boom movement in 3DResearch Article - Automation of an excavator boom movement in 3D
Research Article - Automation of an excavator boom movement in 3DVan Tien Nguyen
 
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERijics
 
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERijcisjournal
 
IEEE Paper .venkat (1).pdf
IEEE Paper .venkat (1).pdfIEEE Paper .venkat (1).pdf
IEEE Paper .venkat (1).pdfSheronThomas4
 
Flood routing by kinematic wave model
Flood routing by kinematic wave modelFlood routing by kinematic wave model
Flood routing by kinematic wave modelIOSR Journals
 
Simulation of Deployment and Operation of an Earth Observing Satellite
Simulation of Deployment and Operation of an Earth Observing SatelliteSimulation of Deployment and Operation of an Earth Observing Satellite
Simulation of Deployment and Operation of an Earth Observing SatelliteAlber Douglawi
 
UAV Launching Trebuchet
UAV Launching TrebuchetUAV Launching Trebuchet
UAV Launching TrebuchetBalázs Gáti
 
Performance evaluation of telemetry stations based on site selection
Performance evaluation of telemetry stations based on site selectionPerformance evaluation of telemetry stations based on site selection
Performance evaluation of telemetry stations based on site selectionPriyasloka Arya
 

Similar to Mpc final report (20)

Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery
 
Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery Quadcopter Design for Payload Delivery
Quadcopter Design for Payload Delivery
 
B045012015
B045012015B045012015
B045012015
 
Synthesis of Research Project-FlappingWing
Synthesis of Research Project-FlappingWingSynthesis of Research Project-FlappingWing
Synthesis of Research Project-FlappingWing
 
Research Paper (ISEEE 2019)
Research Paper (ISEEE 2019)Research Paper (ISEEE 2019)
Research Paper (ISEEE 2019)
 
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...
Development and Implementation of a Washout Algorithm for a 6-dof Motion Plat...
 
PID vs LQR controller for tilt rotor airplane
PID vs LQR controller for tilt rotor airplane PID vs LQR controller for tilt rotor airplane
PID vs LQR controller for tilt rotor airplane
 
A highly versatile autonomous underwater vehicle
A highly versatile autonomous underwater vehicleA highly versatile autonomous underwater vehicle
A highly versatile autonomous underwater vehicle
 
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...
An Implementation Mechanisms of SVM Control Strategies Applied to Five Levels...
 
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...
Determination of Flutter Angle by Resolving Effective Gyroscope Couple to Ret...
 
An Unmanned Rotorcraft System with Embedded Design
An Unmanned Rotorcraft System with Embedded DesignAn Unmanned Rotorcraft System with Embedded Design
An Unmanned Rotorcraft System with Embedded Design
 
Research Article - Automation of an excavator boom movement in 3D
Research Article - Automation of an excavator boom movement in 3DResearch Article - Automation of an excavator boom movement in 3D
Research Article - Automation of an excavator boom movement in 3D
 
T130403141145
T130403141145T130403141145
T130403141145
 
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
 
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTERENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
ENHANCED DATA DRIVEN MODE-FREE ADAPTIVE YAW CONTROL OF UAV HELICOPTER
 
IEEE Paper .venkat (1).pdf
IEEE Paper .venkat (1).pdfIEEE Paper .venkat (1).pdf
IEEE Paper .venkat (1).pdf
 
Flood routing by kinematic wave model
Flood routing by kinematic wave modelFlood routing by kinematic wave model
Flood routing by kinematic wave model
 
Simulation of Deployment and Operation of an Earth Observing Satellite
Simulation of Deployment and Operation of an Earth Observing SatelliteSimulation of Deployment and Operation of an Earth Observing Satellite
Simulation of Deployment and Operation of an Earth Observing Satellite
 
UAV Launching Trebuchet
UAV Launching TrebuchetUAV Launching Trebuchet
UAV Launching Trebuchet
 
Performance evaluation of telemetry stations based on site selection
Performance evaluation of telemetry stations based on site selectionPerformance evaluation of telemetry stations based on site selection
Performance evaluation of telemetry stations based on site selection
 

Recently uploaded

(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...ranjana rawat
 
Introduction to IEEE STANDARDS and its different types.pptx
Introduction to IEEE STANDARDS and its different types.pptxIntroduction to IEEE STANDARDS and its different types.pptx
Introduction to IEEE STANDARDS and its different types.pptxupamatechverse
 
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝soniya singh
 
Porous Ceramics seminar and technical writing
Porous Ceramics seminar and technical writingPorous Ceramics seminar and technical writing
Porous Ceramics seminar and technical writingrakeshbaidya232001
 
Introduction and different types of Ethernet.pptx
Introduction and different types of Ethernet.pptxIntroduction and different types of Ethernet.pptx
Introduction and different types of Ethernet.pptxupamatechverse
 
Extrusion Processes and Their Limitations
Extrusion Processes and Their LimitationsExtrusion Processes and Their Limitations
Extrusion Processes and Their Limitations120cr0395
 
SPICE PARK APR2024 ( 6,793 SPICE Models )
SPICE PARK APR2024 ( 6,793 SPICE Models )SPICE PARK APR2024 ( 6,793 SPICE Models )
SPICE PARK APR2024 ( 6,793 SPICE Models )Tsuyoshi Horigome
 
main PPT.pptx of girls hostel security using rfid
main PPT.pptx of girls hostel security using rfidmain PPT.pptx of girls hostel security using rfid
main PPT.pptx of girls hostel security using rfidNikhilNagaraju
 
Processing & Properties of Floor and Wall Tiles.pptx
Processing & Properties of Floor and Wall Tiles.pptxProcessing & Properties of Floor and Wall Tiles.pptx
Processing & Properties of Floor and Wall Tiles.pptxpranjaldaimarysona
 
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur Escorts
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur EscortsHigh Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur Escorts
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur EscortsCall Girls in Nagpur High Profile
 
Software Development Life Cycle By Team Orange (Dept. of Pharmacy)
Software Development Life Cycle By  Team Orange (Dept. of Pharmacy)Software Development Life Cycle By  Team Orange (Dept. of Pharmacy)
Software Development Life Cycle By Team Orange (Dept. of Pharmacy)Suman Mia
 
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130Suhani Kapoor
 
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptx
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptxthe ladakh protest in leh ladakh 2024 sonam wangchuk.pptx
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptxhumanexperienceaaa
 
Introduction to Multiple Access Protocol.pptx
Introduction to Multiple Access Protocol.pptxIntroduction to Multiple Access Protocol.pptx
Introduction to Multiple Access Protocol.pptxupamatechverse
 
Call Girls Delhi {Jodhpur} 9711199012 high profile service
Call Girls Delhi {Jodhpur} 9711199012 high profile serviceCall Girls Delhi {Jodhpur} 9711199012 high profile service
Call Girls Delhi {Jodhpur} 9711199012 high profile servicerehmti665
 
What are the advantages and disadvantages of membrane structures.pptx
What are the advantages and disadvantages of membrane structures.pptxWhat are the advantages and disadvantages of membrane structures.pptx
What are the advantages and disadvantages of membrane structures.pptxwendy cai
 
GDSC ASEB Gen AI study jams presentation
GDSC ASEB Gen AI study jams presentationGDSC ASEB Gen AI study jams presentation
GDSC ASEB Gen AI study jams presentationGDSCAESB
 
Microscopic Analysis of Ceramic Materials.pptx
Microscopic Analysis of Ceramic Materials.pptxMicroscopic Analysis of Ceramic Materials.pptx
Microscopic Analysis of Ceramic Materials.pptxpurnimasatapathy1234
 
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...Dr.Costas Sachpazis
 
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...ranjana rawat
 

Recently uploaded (20)

(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANJALI) Dange Chowk Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
 
Introduction to IEEE STANDARDS and its different types.pptx
Introduction to IEEE STANDARDS and its different types.pptxIntroduction to IEEE STANDARDS and its different types.pptx
Introduction to IEEE STANDARDS and its different types.pptx
 
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝
Model Call Girl in Narela Delhi reach out to us at 🔝8264348440🔝
 
Porous Ceramics seminar and technical writing
Porous Ceramics seminar and technical writingPorous Ceramics seminar and technical writing
Porous Ceramics seminar and technical writing
 
Introduction and different types of Ethernet.pptx
Introduction and different types of Ethernet.pptxIntroduction and different types of Ethernet.pptx
Introduction and different types of Ethernet.pptx
 
Extrusion Processes and Their Limitations
Extrusion Processes and Their LimitationsExtrusion Processes and Their Limitations
Extrusion Processes and Their Limitations
 
SPICE PARK APR2024 ( 6,793 SPICE Models )
SPICE PARK APR2024 ( 6,793 SPICE Models )SPICE PARK APR2024 ( 6,793 SPICE Models )
SPICE PARK APR2024 ( 6,793 SPICE Models )
 
main PPT.pptx of girls hostel security using rfid
main PPT.pptx of girls hostel security using rfidmain PPT.pptx of girls hostel security using rfid
main PPT.pptx of girls hostel security using rfid
 
Processing & Properties of Floor and Wall Tiles.pptx
Processing & Properties of Floor and Wall Tiles.pptxProcessing & Properties of Floor and Wall Tiles.pptx
Processing & Properties of Floor and Wall Tiles.pptx
 
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur Escorts
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur EscortsHigh Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur Escorts
High Profile Call Girls Nagpur Meera Call 7001035870 Meet With Nagpur Escorts
 
Software Development Life Cycle By Team Orange (Dept. of Pharmacy)
Software Development Life Cycle By  Team Orange (Dept. of Pharmacy)Software Development Life Cycle By  Team Orange (Dept. of Pharmacy)
Software Development Life Cycle By Team Orange (Dept. of Pharmacy)
 
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130
VIP Call Girls Service Kondapur Hyderabad Call +91-8250192130
 
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptx
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptxthe ladakh protest in leh ladakh 2024 sonam wangchuk.pptx
the ladakh protest in leh ladakh 2024 sonam wangchuk.pptx
 
Introduction to Multiple Access Protocol.pptx
Introduction to Multiple Access Protocol.pptxIntroduction to Multiple Access Protocol.pptx
Introduction to Multiple Access Protocol.pptx
 
Call Girls Delhi {Jodhpur} 9711199012 high profile service
Call Girls Delhi {Jodhpur} 9711199012 high profile serviceCall Girls Delhi {Jodhpur} 9711199012 high profile service
Call Girls Delhi {Jodhpur} 9711199012 high profile service
 
What are the advantages and disadvantages of membrane structures.pptx
What are the advantages and disadvantages of membrane structures.pptxWhat are the advantages and disadvantages of membrane structures.pptx
What are the advantages and disadvantages of membrane structures.pptx
 
GDSC ASEB Gen AI study jams presentation
GDSC ASEB Gen AI study jams presentationGDSC ASEB Gen AI study jams presentation
GDSC ASEB Gen AI study jams presentation
 
Microscopic Analysis of Ceramic Materials.pptx
Microscopic Analysis of Ceramic Materials.pptxMicroscopic Analysis of Ceramic Materials.pptx
Microscopic Analysis of Ceramic Materials.pptx
 
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...
Structural Analysis and Design of Foundations: A Comprehensive Handbook for S...
 
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
(ANVI) Koregaon Park Call Girls Just Call 7001035870 [ Cash on Delivery ] Pun...
 

Mpc final report

  • 1. 1 NEW ERA FOR PUBLIC TRANSPORATION: MODEL PREDICTIVE CONTROL FOR URBAN AIR MOBILITY IN THE BAY AREA Sonny Li (3035300139), Muireann Spain (3033516594), Shawn Marshall-Spitzbart (3035289739), David Tondreau (3035296317), Anthony Yan (3035300282) ABSTRACT Using Model Predictive Control (MPC), an Unmanned Arial Vehicle (UAV) is simulated flying in ℝ3 between set destinations. The Constrained Finite Time Optimal Control problem (CFTOC) is weighted to prioritize optimization of input power, velocity and deviation from the reference trajectory. Furthermore, the UAV is constrained to fly within an admissible tube, limiting the UAV’s maximum displacement from the reference trajectory. A link to the source code is provided below in Appendix 8.1. Our project video is linked here: https://www.youtube.com/watch?v=tJv9LQBCpm0&feature=yo utu.be&fbclid=IwAR1J4QYwMSt9eecqPHOYh_UXFUAJWNx_ mTUNrLnsxF8mUO9pUgAc6m-Dc6Y 1. INTRODUCTION To solve current challenges with dense traffic in the Bay Area, our team strives to redefine public transportation by utilizing UAVs. For this project, the optimization problem seeks to minimize input power for a multiple passenger-sized UAV along a reference trajectory between Berkeley, San Francisco, and Palo Alto. The system dynamics of the UAV are defined by a discretized linear dynamic model and holonomic constraints, which include the displacement of the UAV to be within an admissible tube from the reference trajectory. 2. QUADCOPTER PARAMETERS Figure 1: Body-fixed frame UAV The parameters of the UAV are outlined with the assumption that the UAV is symmetric about the body-fixed 1 and 2 axes as shown in Fig.1. Drawing inspiration from Boeing-Aurora Flight Science’s Passenger Aerial Vehicle [11], the mass of the fully- loaded passenger UAV was defined as 800 kg. The UAV traverses using four motors orthogonal to one another, three meters radially from the COM. Next, the mass moment of inertias (𝑱𝑱) are defined as follows: 𝑱𝑱 = � 𝐽𝐽𝑥𝑥𝑥𝑥 0 0 0 𝐽𝐽𝑥𝑥𝑥𝑥 0 0 0 𝐽𝐽𝑧𝑧𝑧𝑧 � (1) where, 𝐽𝐽𝑥𝑥𝑥𝑥 = ∑ 𝑚𝑚 𝑀𝑀[ (𝑠𝑠𝑖𝑖 2)2 + (𝑠𝑠𝑖𝑖 3 )2]4 𝑖𝑖=1 (2) 𝐽𝐽𝑧𝑧𝑧𝑧 = ∑ 𝑚𝑚 𝑀𝑀[ (𝑠𝑠𝑖𝑖 1)2 + (𝑠𝑠𝑖𝑖 2)2]4 𝑖𝑖=1 (3) note that 𝐽𝐽𝑥𝑥𝑥𝑥 is equal to 𝐽𝐽𝑦𝑦𝑦𝑦 due to the symmetry of the UAV. 3. QUADCOPTER DYNAMICS The state vector (z) defines the UAV’s position (s), velocity (v), roll (ϕ), pitch (θ), and yaw (φ) angles, roll rate (p), pitch rate (q), and yaw rate (r) in ℝ3 Euclidean space: 𝑧𝑧 = ⎣ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎡ 𝑠𝑠1 𝑠𝑠2 𝑠𝑠3 𝑣𝑣1 𝑣𝑣2 𝑣𝑣3 𝜙𝜙 𝜃𝜃 𝜑𝜑 𝑝𝑝 𝑞𝑞 𝑟𝑟 ⎦ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎤ , 𝑧𝑧̇ = ⎣ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎢ ⎡ 𝑣𝑣1 𝑣𝑣2 𝑣𝑣3 𝜃𝜃 ∙ 𝑔𝑔 − 𝜙𝜙 ∙ 𝑔𝑔 𝐶𝐶Σ− 𝑚𝑚𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡∙𝑔𝑔 𝑚𝑚𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡𝑡 𝑝𝑝 𝑞𝑞 𝑟𝑟 𝑛𝑛1 𝐽𝐽𝑥𝑥𝑥𝑥 � 𝑛𝑛2 𝐽𝐽𝑥𝑥𝑥𝑥 � 𝑛𝑛3 𝐽𝐽𝑧𝑧𝑧𝑧 � ⎦ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎥ ⎤ (4) In Eqn.4, 𝑧𝑧̇ defines the linearized state derivatives, g is the norm of the gravity tensor, C∑ is the sum of the four input forces, and n are the input torques. To transform quadcopter propeller forces into torques (n), a mixer matrix is introduced where l is the perpendicular distance from each motor to the body-fixed 1 axis, and k is a proportionality constant (Eqn. 5).
  • 2. 2 � 𝐶𝐶Σ 𝑛𝑛1 𝑛𝑛2 𝑛𝑛3 � = � 1 1 1 1 𝑙𝑙 −𝑙𝑙 −𝑙𝑙 𝑙𝑙 −𝑙𝑙 −𝑙𝑙 𝑙𝑙 𝑙𝑙 𝜅𝜅 −𝜅𝜅 𝜅𝜅 −𝜅𝜅 � ∙ � 𝐶𝐶P1 𝐶𝐶P2 𝐶𝐶P3 𝐶𝐶P4 � (5) Thus, using the mixer matrix, the four motor forces are utilized as inputs to the system. Finally, the system propagation was performed using the Forward Euler method: 𝑧𝑧𝑘𝑘+1 = 𝑧𝑧𝑘𝑘 + 𝑇𝑇𝑠𝑠 ∙ 𝑧𝑧𝑘𝑘̇ (6) where Ts is the simulation time step and 𝑧𝑧̇ is the state derivative vector. To calculate the state derivative vector, 𝑧𝑧̇, the dynamics of the UAV were linearized about a hover state following the approach in [9]; in doing so, small angles, velocities, and angular accelerations were assumed. To analyze this assumption, a CFTOC was formulated using the linearized dynamics, and the resultant optimal inputs were simulated with both the linear and nonlinear dynamics as similarly completed in [1]. For roll and pitch angles less than 30 degrees, the error between the linear and nonlinear dynamics was found to be small (Fig.2). However, when small angles were added as a constraint to the main CFTOC described in Section 5, the solution was found to be infeasible. Thus, creating a dynamically feasible trajectory, given small angles, velocities, and angular accelerations, has been left for future work. Figure 2: Analysis of linearized dynamics vs nonlinear dynamics where the y axes of the x and y position graphs is in meters, the y axes of the roll and pitch graphs is in radians, and the x axes are in seconds 4. QUADCOPTER TRAJECTORY The reference trajectory shown in Fig.3 was defined in ℝ3 . The “drop-off locations” illustrated were derived by importing geographical data of the Bay Area into MATLAB and manually selecting the X and Y coordinates of our three destinations. Terminal waypoints were discretized from the reference trajectory to be implemented into our MPC algorithm. These waypoints were propagated forward along the trajectory at constant intervals of 5 m by utilizing a reference velocity of 50 m/s along with a time step of 0.1 s. This reference velocity ensures that the UAV continues moving forward along the trajectory at a constant rate. However, the implementation of such a reference velocity disables the maximization of UAV velocity. Figure 3: Map of the Bay Area with the tube constraint shown in red and the drop off locations labeled with triangles In anticipation of a multitude of UAVs flying various trajectories across the Bay area, a holonomic constraint was designed to ensure that the radial displacement of the UAV from the reference trajectory is within a virtual tube. To define this constraint, a cubic interpolation is performed along the reference trajectory for each iteration of the CFTOC function, with the number of interpolated values equal to the prediction horizon, N. Next, the position of the UAV is constrained to be within the radius of the tube minus half of the width of the UAV at each of the aforementioned interpolated steps along the trajectory. The tube constraints are therefore manifested as cubes constraining the X, Y, and Z positions of the UAV in the inertial frame to the waypoints calculated along the reference trajectory at each step from zero to the prediction horizon, N. 5. MODEL PREDICTIVE CONTROL FORMULATION (7)
  • 3. 3 The MPC function utilizes four input propeller forces and the 12 UAV states as decision variables. First, a CFTOC problem is solved using the discretized linear dynamics described in Section 3, the tube constraints described in Section 4, and a quadratic objective function. Abstractly, the objective function was weighted to minimize fuel consumption by primarily minimizing the UAV’s propeller forces, while still penalizing lateral and vertical deviation from the reference trajectory at each discrete time step. The weights for P, Q, W, and R are given in Appendix 8.3. After solving each CFTOC iteration, the optimal inputs for the initial time step are applied to the system. The system is then simulated using the discretized linear dynamics for one time step. The state of the system at the end of one sample time is retrieved, then applied as the initial state for the next CFTOC formulation. This procedure is repeated in a loop for the duration of the MPC simulation horizon, M. In our case, the MPC algorithm terminates when the UAV reaches within a defined tolerance of the final waypoint. 6. RESULTS AND DISCUSSION The UAV successfully lifted off from Berkeley and followed a user-defined flight path, landing on various destinations without violating the radial tube constraint of 50 m. Fig.4 illustrates the UAV, depicted as a ‘*’, with the reference trajectory depicted in red and the MPC path traveled in black. It was necessary to set the prediction horizon value, N, to the sufficiently high value of 35 to guarantee feasibility of the MPC function with constraints. The simulation horizon was defined to terminate the MPC loop once the UAV reached sufficiently close to the final waypoint at 6100 steps. Fig.5 illustrates an example of the UAV following the reference trajectory while obeying the virtual tube constraints. The tube radius was initially defined at 10 m, but the MPC formulation was infeasible as the rather sharp ascension/ descension portions of the ℝ3 curve were unsolvable to solve given the UAV system dynamics and the tight constraints. A tube radius of 50 meters enabled the desired path to be feasible and therefore solvable. Figure 4: The UAV makes three stops – Berkeley, San Francisco, and Palo Alto – flying at height of 100m in-between stops Figure 5: A sample trajectory of the UAV following part of the desired trajectory within the tube constraint with axes in meters. 7. FUTURE WORK AND IMPROVEMENTS The initial approach taken to formulate this problem was to employ the Serret-Frenet frame attached to the reference trajectory. Specifically, this frame would allow the UAV state to be described by a curvilinear abscissa and displacement from the abscissa to the UAV as done in [6] [7] [10] [12] [13] [14]. This frame greatly simplifies the formulation of vertical and lateral position constraints along the reference trajectory by creating an admissible tube where the UAV is permitted to traverse. This approach was taken by [12] with great success where a constant radius tube formed the width of the race track. By using the Serret-Frenet frame, the constrained finite-time optimal control problem effectively transforms a reference- tracking problem to a reference-free trajectory-optimization problem. The authors believe future work entails utilizing a curvilinear abscissa in ℝ3 to formulate the MPC and solve for the optimal trajectory between Berkeley, San Francisco, and Palo Alto in real-time. Next, the authors believe that leveraging Learning MPC to train for time-optimality [13], given passenger-comfort constraints and an admissible tube radius, could greatly reduce commute times between the three cities.
  • 4. 4 8. APPENDIX 8.1 Github: https://github.com/smarshall- spitzbart/Advanced-Control-Design-Final-Project 8.2 Table 1: Numerical Values of UAV Parameters Variable Numerical Value R 3 m α 45° l 3/√2 m k 0.01 mB 600 kg mM 50 kg 𝐽𝐽𝑥𝑥𝑥𝑥 1.44E+04 kg-m2 𝐽𝐽𝑧𝑧𝑧𝑧 2.88E+04 kg-m2 8.3 Table 2: Numerical Values of Cost Function Weights Variable Numerical Value P I3 Q I3 W I3 R 10*I4 ACKNOWLEDGEMENTS Special thanks to Francesco Borrelli and Mark Mueller for their consultation during this project and their instruction over the course of the semester. REFERENCES [1] Anand, Raghav. “MPC Control of Multiple Quadcopters Cooperatively Lifting an Object,” 2018 [2] Brown, Matthew, “Safe Driving Envelopes for Path Tracking in Autonomous Vehicles,” 2016 [3] Gray, Andrew, “Predictive Control for Agile Semi- Autonomous Ground Vehicles using Motion Primitives,” 2012 [4] Hehn, Markus, “Quadcopter Trajectory Generation and Control,” 2011 [5] Islam, Maidul, “Dynamics and Control of Quadcopter Using Linear Model Predictive Control Approach,” 2017 [6] Lorenzetti, Joseph, “A Simple and Efficient Tube-based Robust Output Feedback Model Predictive Control Scheme,” 2019 [7] Lot, Robert, “A Curvilinear Abscissa Approach for the Lap Time Optimization of Racing Vehicles,” 2014 [8] Micaelli, Alain, “Trajectory tracking for two-steering- wheels mobile robots,” 1994 [9] Mueller, Mark. “Quadcopter Dynamics,” 2019 [10]Oulmas, Ali. “Closed-loop 3D path following of scaled-up helical microswimmers,” 2016 [11]“PAV – Passenger Air Vehicle,” accessed 10th December 2019, https://www.aurora.aero/pav-evtol-passenger-air- vehicle/ [12]Rosollia, Ugo, “Autonomous Vehicle Control: A Nonconvex Approach for Obstacle Avoidance,” 2016 [13]Samson, Claude, “Path Following And Time-Varying Feedback Stabilization of a Wheeled Mobile Robot,” 1992 [14]Wang, Ye. “Nonlinear Model Predictive Control with Constraint Satisfaction for a Quadcopter,” 2016 [15]Zhang, Xiaojing, “Optimization-Based Collision Avoidance,” 2018