You are on page 1of 17

An Autonomous Carrier Landing System for Unmannned

Aerial Vehicles ∗
Jovan D. Bošković† and Joshua Redding‡
Scientific Systems Company, Inc.

One of the important problems related to naval Unmanned Aerial Vehicles (UAV), is the design
of an automatic landing system that would enable autonomous landing of a UAV on an aircraft
carrier. When landing needs to be accomplished safely in the high sea states and during the carrier
turns, the problem becomes highly complex.
In this paper we present an innovative autonomous carrier landing system for UAVs, referred to
as the Carrier Motion Prediction & Autonomous Landing (CM-PAL) system. The system is based
on real-time estimation of magnitudes and frequencies of waves encountered by the carrier, and on-
line prediction of the carrier motion. This prediction generates information regarding the carrier
states at touchdown; this information is in turn used to generate corrections in the UAV’s heading
and flight path angle commands to achieve minimum dispersion around the desired touchdown
point and heading. We also present performance evaluation results of the CM-PAL system on a
high-fidelity simulation of typical aircraft carrier dynamics.

I. Introduction

To address the automatic landing concept, the U.S. Department of Defense is developing Joint Preci-
sion Approach and Landing System (JPALS) program. Under this program, the Navy is responsible for its
shipboard component termed Shipboard Relative Global Positioning System (SRGPS).1 The SRGPS will
support all Air Traffic Control (ATC) functions, including takeoff, departure, taxi, holding, approach, land-
ing, bolter, missed approach, and long range navigation. In addition to supporting manned aircraft, SRGPS
will fully support automatic takeoff, approach, landing and ATC automation required by future unmanned
systems such as the Naval Unmanned Combat Aerial Vehicle. Recently, Northrop Grumman Corporation
was awarded a six-year, $636 million UCAS-D contract after its X-47B was selected over Boeing’s X-45N.
The first of two demonstrators is scheduled to fly in November 2009, and the first carrier landing is planned
for 2011.
The problem of autonomous landing of Unmanned Aerial Vehicles (UAV) and Unmanned Combat Aerial
Vehicles (UCAV) on a ship is highly challenging due to stringent constraints with respect to dispersion
around the desired touchdown point, approach speed, approach heading and pitch attitude. When accurate
landing under these constraints needs to be achieved under wind gust disturbances, communication dropouts
and in the presence of ship motion under high sea states, the problem becomes truly formidable. An addi-
tional complexity in the context of UAVs is that of bolter recovery. Bolter is a term for a failed attempt to
capture the arresting cable when landing, and is a highly dangerous situation from a safety perspective. This
problem needs to be specifically addressed in the case of UAVs. Hence, the control strategy for UAV carrier
landing needs to have the following capabilities:

This research was supported by Boeing Phantom Works under a contract to Scientific Systems Company.

Principal Research Engineer & Intelligent & Autonomous Control Systems Group Leader, 500 W. Cummings Park, Suite 3000,
Woburn, MA, AIAA Senior Member, jovan@ssci.com

Ph.D. Candidate, MIT Aerospace Controls Laboratory, on leave from SSCI, AIAA Member, jredding@mit.edu

1 of 17

American Institute of Aeronautics and Astronautics


• Efficient prediction and compensation of the carrier motion under communication blackouts
• Capability to autonomously recover from bolter
• Flexibility to readily incorporate changes in the landing parameters due to heave, sway and surge
motion of the touchdown point to achieve effective Deck Motion Compensation
• Effective rejection of atmospheric disturbances such as wind gust.

To address these issues, we developed a Carrier Motion Prediction & Autonomous Landing (CM-PAL)
system that consists of a Ship Motion Predictor (SMP), and an algorithm for the determination of optimal
UAV heading for ship-relative course line following during landing on a turning aircraft carrier. The main
objective was to develop an algorithm for course-line following, and the SMP module to allow for UAV
heading and flight path angle corrections at the carrier landing stage based on predicted carrier states ten
seconds before touchdown. We show in Section VIII that the SMP system accurately predicts all the states
of the ship 10 seconds ahead of touchdown with errors well below the stated specifications.
The proposed CM-PAL system consists of the following modules:

1. A signal conditioning module that extracts the actual wave disturbance signal from the
measurements
2. A frequency estimation module that employs a modified Fast Fourier Transform (FFT)
algorithm and generates an accurate wave frequency estimate.
3. A parameter estimation module that uses Batch Least Squares algorithm to estimate am-
plitudes and phases of the wave disturbance signal, as well as the signal itself.
4. A prediction module that uses a Kalman Filter to predict the behavior of ship’s states due
to wave disturbances.
5. A confidence measure calculation module that calculates a wave-off criterion.

The diagram of the SMP system is shown in Figure 1. Since the position and velocity measurements
are given in geodetic coordinates, these are first converted to Earth-Centered, Earth-Fixed (ECEF) Cartesian
coordinates, and then to North-East-Down (NED) coordinates which are attached to the body of the carrier.
The measurements contain the information about both the carrier dynamics and the effect of waves. Based
on the known carrier dynamics and these measurements, the dynamics of waves can be extracted. The
next step is to run the Fast Fourier Transform (FFT) on the waves data to estimate wave frequencies from
noisy signals. Once the wave frequencies have been estimated, a Least-Squares Estimator is run to estimate
the magnitudes and phases of the wave signals. After attaining accurate estimates wave frequencies and
propagating the effect of the waves, these estimates are integrated with the model of carrier dynamics to
generate predicted carrier motion. A confidence measure for the estimates is also calculated such that, if
above a threshold, the UAV is waved-off.
The specifications under which the algorithms were developed are described in Section II below.

II. Specifications

During the design, the following specifications were assumed:

• The algorithm should be valid for sea states up to and including level 5.

• The algorithm should be valid for turning motion of the carrier of up to 0.5deg/s.

• It is assumed that the UAV control system has a wind disturbance rejection capability, and that the
effect of the wind of the carrier can be neglected.

2 of 17

American Institute of Aeronautics and Astronautics


Figure 1. Structure of the Carrier Motion Prediction & Autonomous Landing (CM-PAL) System

• The algorithm shall utilize the broadcast messages from the carrier containing its current attitudes,
rates and accelerations in the keel axis. These messages will be available within 10 nautical miles
from the ship and received at 20Hz.

• The ship motion prediction model shall be robust to momentary dropouts of these periodic messages.

• The ship motion prediction algorithm shall output a minimum of four values: predicted roll, pitch
and heading angles of the carrier vehicle (CV) keel axis at the specified time, along with a confidence
factor of these predicted values. The confidence factor will be used to determine an autonomous
wave-off criterion.

• The attitude outputs of ship motion prediction for constant carrier turn rates shall have accuracies
specified in Table 1.

Specified Prediction Time (seconds) Error Tolerance at Prediction Time


5.0 ≤ T ≤ 10.00 ±0.25 deg
T ≤ 5.0 ±0.1 deg
Table 1. Attitude Error Tolerances

• Additional outputs shall include the ship reference center of motion position (lat, lon, altitude), veloc-
ities (NED), and accelerations (NED). These values will be needed to to complete the approach after
loss of data link within 5 seconds from the touchdown.

3 of 17

American Institute of Aeronautics and Astronautics


III. Ship Dynamics Model

This section outlines the dynamics model assumed for the ship Center of Motion. We use this model in
the design of the desired UAV dynamics to achieve accurate following of the carrier course line.

 
Ṅ = Γ̇ x + Vnom cos (ψt ) − Γ̇y sin (ψt )
 
Ė = Γ̇ x + Vnom sin (ψt ) + Γ̇y cos (ψt ) (1)
Ḋ = Γ̇z ,

where north-east-down coordinate frame is assumed for the center-of-motion coordinates (Keel Axis), Γ̇∗
denote the ship’s body accelerations, Vnom is the nominal ship velocity (e.g. 20 knots), and ψt is the ship’s
heading track, which is a lag-filtered heading with time constant τ as a function of Vnom .
Ship rotation is assumed to be due to the waves modeled by the sum of sinusoids:
n
X  
φ̇ = aφi sin ωφi t + νφi
i=1
n
X 
θ̇ = aθi sin ωθi t + νθi (2)
i=1
Xn  
ψ̇ = aψi sin ωψi t + νψi + ψcmd ,
i=1

where a∗ , ω∗ , and ν∗ are amplitude, frequency and phase shift inputs based on ship motion data and ψcmd is
an adequately filtered ship turn command.
The ship’s body velocities are denoted as Γ x,y,z , and refer to ship surge, sway and heave respectively.
Body accelerations are given by:
n
X  
Γ̇ x = aΓxi sin ωΓxi t + νΓxi
i=1
n
X  
Γ̇y = aΓyi sin ωΓyi t + νΓyi (3)
i=1
Xn  
Γ̇z = aΓzi sin ωΓzi t + νΓzi ,
i=1

and body-axis rotational rates are:

p = φ̇ − sin (θ)ψ̇
q = sin (φ) cos (θ)ψ̇ + cos (φ)θ̇ (4)
r = cos (φ) cos (θ)ψ̇ − sin (φ)θ̇,

where p, q and r denote respectively the roll, pitch and yaw rate.

A. Cant Axes System


The Cant axes system is an important coordinate frame as this is the reference associated with the desired
UAV touchdown point and corresponding course line. Figure 2 shows the locations of the Keel and Cant

4 of 17

American Institute of Aeronautics and Astronautics


Figure 2. Keel to Cant axis coordinate transformation

axes on the ship deck. The relationship between the two is given by:
     
 xca   x ∆x 
     
yca  = y + R ∆y  ,
     
zca z ∆z

where ∆(x,y,z) are defined as the Cant axis offset in the Keel reference frame, as shown in Figure 2, and the
rotation R is given by
 
 sψcθ cψcφ + sψsθsφ −cψsφ + sψsθcφ
 
R = cψcθ −sψcφ + cψsθsφ sψsφ + cψsθcφ  (5)
 
−sθ cθsφ cθcφ
where s∗, c∗ denotes sin(∗), cos(∗) respectively.
The velocity and acceleration of the Cant axes system are given by:
     
 ẋca   ẋ ∆x 
     
ẏca  = ẏ + Ṙ ∆y  (6)
     
żca ż ∆z

5 of 17

American Institute of Aeronautics and Astronautics


     
 ẍca   ẍ ∆x 
     
ÿca  = ÿ + R̈ ∆y  (7)
     
z̈ca z̈ ∆z

In Equation (6) and (7) above, the derivatives are simple since ∆∗ represents fixed distances and hence have a
zero derivative. The first and second derivative of the rotation, R, are tedious but straightforward and hence,
are not given.

IV. Coordinate transformations

In order to implement the landing algorithm, we need to define several coordinate frames and the trans-
formations between them. We have already introduced the ship’s keel, or center of motion, and Cant coor-
dinate systems. Additional frames include the following:

1. Local north, east, down (NED)


Ship information is provided to the unmanned aircraft landing system in this coordinate frame. It is
formed by a plane tangent to the Earth’s surface fixed to a specific location, hence it is sometimes
known as the local tangent, or local geodetic plane. By convention, the east axis is labeled x, the
north y and, in our case, down z.
2. Earth-centered Earth-fixed (ECEF)
This is the conventional terrestrial coordinate system and rotates with the Earth as its origin is at the
Earth’s center. The X axis passes through the equator at the prime meridian, the Z axis passes through
the north pole, and the Y axis passes through the equator at 90◦ longitude, following the right-hand
rule.
3. Geodetic
The geodetic system represents more accurately the fact that the earth is not a perfect sphere. Under
this system, the Earth’s surface is approximated by an ellipsoid and locations near the surface are
described in terms of latitude, longitude and height. The ellipsoid is completely parameterized by the
semi-major axis a, and the flattening f .

Sections A to C outline the transformations between these various coordinate frames.

A. Local to ECEF
Transforming from a local NED coordinate system to a earth-centered earth-fixed system is accomplished
by the following:
    
Xecef  − sin(lat) cos(lon) − sin(lon) − cos(lat) cos(lon) N 
     
 Yecef  =  − sin(lat) sin(lon) cos(lon) − cos(lat) sin(lon)   E  ,
    
Zecef cos(lat) 0 − sin(lat) D

where the rotation matrix is built using geodetic latitude and longitude.

6 of 17

American Institute of Aeronautics and Astronautics


B. ECEF to Geodetic
We use the direct algorithm in Ref. [12] to transform from earth-centered earth-fixed to the geodetic system.
This transformation is given by:
lon = arctan(Y, X)
e = e2 (a/b)2
p
p = X2 + Y 2
q
r = p2 + Z 2
!
bZ (1 + eb/r)
u = arctan
ap
Z + eb sin3 u
!
lat = arctan
p − e2 a cos3 u
a
v = q
1 − e2 sin2 (lat)
h = p cos(lat) + Z sin(lat) − a2 /v,
where X, Y, Z are ECEF coordinates, e2 = 6.69437999014e−3 denotes the first eccentricity squared, a =
2.092564632545929e+07 ft is the semi-major axis, and b = 2.085548659528727e+07 ft is the semi-minor
axis.

C. Geodetic to ECEF
Transforming back to earth-centered earth-fixed coordinates from geodetic is given by:
X = (Φ + alt) cos(lat) cos(lon)
Y = (Φ + alt) cos(lat) sin(lon)
 
Z = Φ(b/a)2 + alt sin(lat),
p
where Φ = a/ 1 − e2 sin(lat)2 .

V. Real-time Ship Motion Prediction

We now turn to our Ship Motion Prediction algorithm, as developed and tested on a high-fidelity ship
motion model. As described previously,4 there are a large number of approaches that can be used to predict
ship motion including:
• Time-series prediction techniques such as those using ARMA models and neural networks
• Prediction based on detailed modeling techniques such as those arising from the strip theory
• Parametric and non-parametric identification techniques.
These approaches differ in several aspects including the prior information regarding the environmental dis-
turbances, algorithm dependence on the ship velocity, and the sensor system.
We addressed the Ship Motion Prediction problem using a combination of Fast Fourier Transform (FFT),
nonlinear on-line parameter estimation, and state estimation and prediction using Kalman Filtering. The
main idea is the following:

1. Ship motion is described by a model of ship dynamics whose inputs are waves described
by sums of sine and cosine functions with uncertain amplitudes and frequencies.

7 of 17

American Institute of Aeronautics and Astronautics


2. Frequencies are estimated accurately in real time using Fast Fourier Transform (FFT).
3. Since attitude, rate and acceleration measurements are available, uncertain amplitudes are
estimated on-line using Batch Least Squares.
4. These estimates are input into the Kalman Filter at every instant to generate the state
estimates and associated covariances.
5. At the end of the “learning” interval T , parameter estimates are frozen and their values
at t = T are input into the Kalman Filter, when the prediction stage starts. Since during
this stage there are no measurement inputs, the covariance of the state estimates will keep
increasing.
6. The confidence in the state estimates generated during the prediction interval is calculated
based on a combination of covariances of the parameter estimates and covariances of the
state estimates.

A. Wave Frequency Estimation


To arrive at an accurate prediction model for the ship motion, it is crucial to accurately estimate the wave fre-
quencies. Since there is a relatively long time interval between the start of the approach and the touchdown,
we used the Fast Fourier Transform (FFT) to estimate wave frequencies.
The FFT is an efficient algorithm to compute the Discrete Fourier Transform (DFT). The DFT transforms
a function from the time domain into the frequency domain. The DFT requires an input function that is
discrete and whose non-zero values have a limited (finite) duration. This is achieved by sampling the time-
domain signal. The DFT only evaluates enough frequency components to reconstruct the finite segment that
is analyzed.
The FFT has been widely used in estimation of multiple frequencies from noisy signals. It is a standard
function in Matlab, and we used it to estimate wave frequencies given the ship dynamics and measurements
of the ship state variables.
After the implementation of FFT, Figure 3 shows a noisy signal (top figure) from which the wave fre-
quencies were obtained (middle figure), and a plot of the frequency estimation errors (bottom figure). It is
seen that the FFT results in accurate frequency estimates.

B. Estimation of Magnitudes
Once the frequencies are known, the wave model becomes linear in parameters, i.e. in magnitudes, and
many parameter estimation technique can be used to estimate the magnitudes. We chose a Batch least-
Squares algorithm due to its accuracy and ease of implementation. The estimation results are shown in
Figure 4.

VI. An Algorithm for Determination of Optimal Ship-Relative Course Line Commands

The main objective here was to develop an algorithm that uses the information from the Ship Motion
Prediction module and modify the desired landing parameters in response to the deck motion. Specifically,
it modifies the lineup, glide slope, and pitch angle to achieve landing within the touchdown point dispersion
limits. The objective is to determine an optimal course line command for carrier approach. The course line
is defined as a straight-line ship-relative trajectory that intersects the targeted touchdown point.
The assumptions made during the design include:

• The aerial vehicle is designed to precisely follow the commanded ship-relative course line while flying
an approach to the aircraft carrier.

8 of 17

American Institute of Aeronautics and Astronautics


Signal

Magnitude

Time

Estimated Frequencies in Signal


Magnitude

Frequency

−3 Estimation Error
x 10
1

0.8
Normalized Error

0.6

0.4

0.2

0
Frequency

Figure 3. Ship motion in a single axis, estimated frequencies in the signal, and estimation error

• Commanded rotation of the course line is constrained such that an aerial vehicle with a first-order bank
response with one second time constant will not exceed a bank angle of 20 degrees while tracking the
commanded course line.
• The commanded course line shall be optimized to be as steady as possible during the last 10 seconds
of an approach. For cases where ship is turning during the approach, a steady course line is defined
as a course line that is rotating along with the ship’s average rotation rate.
• The course line shall be optimized in order to minimize cross-track error relative to the centerline
of the angle deck, ∆x feet beyond the ideal touchdown location, assuming a constant course line
following touchdown. This ∆x shall be adjustable between 0 and 1100 ft. For a ∆x of 0 ft, the course
line should ideally line up with the centerline of the angle deck.
• It shall be assumed that average ship turn rate will be steady during the last 20 seconds of each
approach. Realistic ship turn dynamics for ship turn rate changes made prior to the last 20 seconds of
the are assumed.
• The algorithm shall be valid for the same ship motion and sea states specified in the previous section.

9 of 17

American Institute of Aeronautics and Astronautics


Signal

Magnitude

Time

Estimated Magnitudes in Signal


a cosν, a sinν

Magnitude

Estimation Error
0.4
Normalized Error

0.3

0.2

0.1

0
Magnitude

Figure 4. Estimated wave magnitudes, and estimation error

• The algorithm shall be robust enough to allow for the aircraft to continue approach and bolter after
loss of ship data link five seconds prior to touchdown.

Figure 5 shows the modifications in the glide slope and lineup in response to deck sway, surge and heave.
(Please note that the sizes in the figure are slightly exaggerated to illustrate the command modification
concept). In the case of bolter, the command generator will generate the desired speed (full throttle) and
lineup to achieve safe take-off.
We next describe the design of an optimal trajectory for the course-line following, along with the outer-
loop control law designed to follow accurately the optimal trajectory.

10 of 17

American Institute of Aeronautics and Astronautics


Original glide slope Original touchdown point

Modified glide slope

Original touchdown point


Predicted touchdown point

Original lineup

Modified lineup
Figure 5. Modification of commands in response to the deck motion

A. UAV Equations of Motion


In the case of carrier landing, a reasonable assumption is that the UAV dynamics is of the form of a con-
strained point-mass model. The assumed equations are of the form:

ẋv = V · cos(ψ) · cos(γ)


ẏv = V · sin(ψ) · cos(γ)
żv = V · sin(γ)
V̇ = −λV · (V − Vc ), V̇ ≤ V̄
ψ̇ = −λψ · (ψ − ψc ), ψ̇ ≤ ψ̄
γ̇ = −λγ · (γ − γc ) γ̇ ≤ γ̄

where ψ is the heading angle, γ is the flight-path angle, V is the total velocity of the helicopter, xv , yv , and zv
are the positions of the UAV in the inertial frame, λV , λψ , and λγ are the positive constants, and ψc , Vc , and
γc are the control inputs.
Let p = [xv yv zv ]T . We now write the UAV equations of motion as:
   
 ẍ   Vc 
   
 ÿ  = p̈ = f (V, ψ, γ) + g(V, ψ, γ) ·  ψc  , (8)
   
z̈ γc

where
 
 −λV · V · cos(ψ) · cos(γ) + λψ · ψ · V · sin(ψ) · cos(γ) + λγ · γ · V · cos(ψ) · sin(γ) 
 
f (V, ψ, γ) =  −λV · V · sin(ψ) · cos(γ) − λψ · ψ · V · cos(ψ) · cos(γ) + λγ · γ · V · sin(ψ) · sin(γ) 
 
−λV · V · sin(γ) − λγ · γ · V · cos(γ)

and  
 λV · cos(ψ) · cos(γ) −λψ · V · sin(ψ) · cos(γ) −λγ · V · cos(ψ) · sin(γ) 
 
g(V, ψ, γ) =  λV · sin(ψ) · cos(γ) λψ · V · cos(ψ) · cos(γ) −λγ · V · sin(ψ) · sin(γ)  .
 
λV · sin(γ) 0 λγ · V · cos(γ)

11 of 17

American Institute of Aeronautics and Astronautics


   
 Vc   V + Vcc 
   
It is seen that by choosing  ψc  =  ψ + ψcc , the expression (8) simplifies to:
   
γc γ + γcc
 
 Vcc 
 
p̈ = g(V, ψ, γ) ·  ψcc  . (9)
 
γcc

Let p∗ (t) be a twice differentiable function describing the desired trajectory that the vehicles is to follow.
One possible control law that assures tracking of the desired trajectory p∗ (t) is that based on nonlinear
inverse dynamics and is of the form:
 
 Vcc 
h i
 ψcc  = g−1 (V, ψ, γ) −k1 (p − p∗ ) − k2 ( ṗ − ṗ∗ ) + p̈∗ ,
 
(10)
 
γcc

where k1 , k2 > 0.
The resulting closed-loop control system consists of three decoupled second-order error equations of the
form:
ë + k2 ė + k1 e = 0,
where e = p − p∗ , so that limt→∞ e(t) = limt→∞ ė(t) = 0.

B. Desired UAV Location, Velocity, Acceleration


Desired UAV Location: The remaining task is to define the vector p∗ . Let p∗ = [x∗v y∗v z∗v ]T . The desired
UAV location is defined with respect to the cant axis under an assumption that the UAV approaches the
carrier with constant ship-relative velocity V ∗ . The resulting UAV position is defined as:

x∗v = xca − (d − V ∗ (t − to )) cos(ψo + ψ) cos(γ∗ ) (11)


y∗v ∗
= yca − (d − V (t − to )) sin(ψo + ψ) cos(γ ) ∗
(12)
z∗v = d sin(γ ),∗
(13)

where d is the initial UAV distance from the ship, and V ∗ is the desired relative velocity of UAV with respect
to the ship.
Desired UAV Velocity: Upon differentiation of the above equations one obtains:

ẋ∗v = ẋca + (d − V ∗ (t − to )) sin(ψo + ψ) cos(γ∗ )ψ̇ + V ∗ cos(ψo + ψ) cos(γ∗ ) (14)


ẏ∗v ∗ ∗ ∗
= ẏca − (d − V (t − to )) cos(ψo + ψ) cos(γ )ψ̇ + V sin(ψo + ψ) cos(γ ) ∗
(15)
ż∗v ∗
= V sin(γ ) ∗
(16)

Desired UAV Acceleration: Similarly, upon differentiation of the above equations one obtains:

ẍ∗v = ẍca + (d − V ∗ (t − to )) cos(ψo + ψ) cos(γ∗ )ψ̇2


−2V ∗ sin(ψo + ψ) cos(γ∗ )ψ̇ + (d − V ∗ (t − to )) sin(ψo + ψ) cos(γ∗ )ψ̈
ÿ∗v = ÿca + (d − V ∗ (t − to )) sin(ψo + ψ) cos(γ∗ )ψ̇2
+2V ∗ cos(ψo + ψ) cos(γ∗ )ψ̇ − (d − V ∗ (t − to )) cos(ψo + ψ) cos(γ∗ )ψ̈,
z̈∗v = 0.

The above equations define p∗ , ṗ∗ and p̈∗ needed to implement the outer-loop control law (10).

12 of 17

American Institute of Aeronautics and Astronautics


VII. Angle corrections to compensate for carrier motion

We now address UAV control system compensation for carrier motion in altitude and heading.

A. Carrier Motion Compensation in z


Due to the ship heave, pitch and roll, the actual location of the touchdown point may be different from the
nominal one. The ship motion predictor will generate the actual touchdown point xca , yca , zca . The problem
of compensating for this difference can be divided into problems of correction of the flight path angle, and
the problem of modification of the UAV heading angle in the final landing stage.
The correction is implemented 10 seconds before touchdown. The equations in the z axis are of the
form:
z∗ (t) = z∗t=tF −10 − V ∗ sin(γ∗ )(t − tF + 10),
where tF is the nominal touchdown time. The nominal touchdown value for z is zN = z∗t=tF −10 − 10V ∗ sin(γ∗ ).
Let the composite perturbation in the z-coordinate of the touchdown point due to ship heave, roll and pitch
be denoted by ∆zN .

Figure 6. Variables of interest in the γ compensation analysis

Then the dN from Figure 6 is calculated as dN = 10V ∗ . Based on this we have:


z′ = dN sin(γ∗ )
z′′ = z′ − ∆zN = dN sin(γ∗ ) − ∆zN
d′N cos(γ∗ − ∆γ) = dN cos(γ∗ )
q
d′N = d2N + ∆z2N − 2dN ∆zN cos(γ∗ )
from where it follows that the correction in γ is:
dN
∆γ = γ∗ − arccos γ∗ .
d′N
The above equations neglect the difference between the actual and nominal touchdown times. If the dif-
ference between the nominal and actual touchdown time is large, an iterative procedure can be implemented
to calculate the actual touchdown point at the touchdown time tF .

B. Heading Angle Compensation


In this case the heading angle correction is applied at t = tF − 10. The correction takes into account not only
the heading of the cant axis, but also the heading of a point where the UAV would be after a prespecified
time on deck. This assures that the UAV will be aligned with the cant axis when on deck even when landing
on a turning ship.

13 of 17

American Institute of Aeronautics and Astronautics


VIII. Simulation Results

A typical simulation result is shown in Figure 7. The simulation consist of the high-fidelity aircraft
carrier dynamics, and wave dynamics described by a sum of sines with eight distinct frequencies. The wave
dynamics affects surge, heave and sway and their rates, and roll, pitch and yaw, and their rates. The SMP

7000 2
5000
6000
0
4000
5000
−2

Lon (ft)
Lat (ft)

Alt (ft)
3000 4000
−4
3000
2000
−6
2000
1000
1000 −8

0 0
0 50 100 150 200 0 50 100 150 200 0 50 100 150 200

30 42 3
40 2
25
38 1
VN (ft/s)

VD (ft/s)
VE (ft/s)

20 36 0

15 34 −1
32 −2
10
30 −3
5 28 −4

0 50 100 150 200 0 50 100 150 200 0 50 100 150 200

90
1.5 1.5

1 1 80

0.5 0.5
ψ (deg)
φ (deg)

θ (deg)

70
0
0
−0.5 60
−0.5
−1
−1 50
−1.5
−1.5
0 50 100 150 200 0 50 100 150 200 0 50 100 150 200
Time (s) Time (s) Time (s)

Figure 7. Simulation result generated using the SMP module – Solid blue line: actual variables; Dashed red line: estimated
variables; and Dashed black line: predicted variables

module is seen to accurately estimate all the variables. To verify its prediction capabilities, the figures are
zoomed in last ten seconds before touchdown, and shown in Figure 8. It is seen that the SMP module
accurately predicts all the states 10 seconds into the future while assuring that the errors are well within
specifications. In fact, while the specifications were given for prediction over the horizon of 10 seconds
(±1 f t in (x, y, z), and ±0.25◦ for angles), we tested the SMP module over larger time horizons and found
that the prediction errors are within specifications most of the time even when the prediction horizon is
extended to 30 seconds.
Figure 9 shows the error between actual and estimated parameters during the 10 second prediction

14 of 17

American Institute of Aeronautics and Astronautics


5480 2
7200
5470 7150 0
7100
5460
7050 −2

Lon (ft)
Lat (ft)

Alt (ft)
5450 7000
6950 −4
5440
6900
5430 6850 −6
6800
5420
210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220

8 43 2

7 1
42.5

6 0
V (ft/s)

VD (ft/s)
VE (ft/s)

42
N

5 −1

41.5
4 −2

3 41 −3
210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220

2 1 90

1.5 89
0.5
1 88
ψ (deg)
φ (deg)

θ (deg)

0.5 87
0
0 86

−0.5 85
−0.5
−1 84

−1.5 −1 83
210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220
Time (s) Time (s) Time (s)

Figure 8. Prediction result generated using the SMP module – Solid blue line: actual variables; Dashed red line: estimated
variables; and Dashed black line: predicted variables

horizon under communication blackout.


Table 2 shows the 10 second prediction error to be well within the specified bounds.

Variable Error at Touchdown Specification


Lat (ft) 0.09 1.0
Lon (ft) 0.33 1.0
Alt (ft) 0.16 1.0
φ (deg) 0.02 0.25
θ (deg) 0.01 0.25
ψ (deg) 0.23 0.25
Table 2. Table of prediction errors at touchdown

15 of 17

American Institute of Aeronautics and Astronautics


0.35
0
0.25
0.3
0.2 −0.1

Lon (ft)
Lat (ft)

Alt (ft)
0.15 0.25
−0.2
0.1
−0.3 0.2
0.05

0 −0.4
210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220

0.02 0.04
0.1
0 0.02
0.05
−0.02 0
VN (ft/s)

VD (ft/s)
VE (ft/s)
0

−0.05 −0.04 −0.02


−0.1
−0.06 −0.04
−0.15

−0.2 −0.08 −0.06


210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220

0.04
0
0.03 0.2
−0.01
0.02
−0.02 0.1

ψ (deg)
φ (deg)

θ (deg)

0.01 −0.03

0 −0.04 0
−0.05
−0.01
−0.06 −0.1
−0.02
210 212 214 216 218 220 210 212 214 216 218 220 210 212 214 216 218 220
Time (s) Time (s) Time (s)

Figure 9. Estimation errors over the 10 second prediction horizon

IX. Conclusions

One of the important problems related to naval Unmanned Aerial Vehicles (UAV), is that of the design of
an automatic landing system that enables autonomous landing of a UAV on an aircraft carrier. When landing
needs to be accomplished safely in the high sea states and during the carrier turns, the problem becomes
highly complex.
In this paper we present an innovative autonomous carrier landing system for UAVs, referred to as the
Carrier Motion Prediction & Autonomous Landing (CM-PAL) system. The system is based on real-time
estimation of magnitudes and frequencies of waves encountered by the carrier, and on-line prediction of
the carrier motion. This prediction generates information regarding the carrier states at touchdown; this
information is in turn used to generate corrections in the UAV’s heading and flight path angle commands to
achieve minimum dispersion around the desired touchdown point.
In the paper we present performance evaluation results of the CM-PAL system on a high-fidelity simu-
lation of a typical aircraft carrier dynamics and show that the desired performance specifications are met.

16 of 17

American Institute of Aeronautics and Astronautics


References
1
P. Sousa, L. Wellons, G. Colby, J. Waters and J. Weir, ”Test Results of an F/A-18 Automatic Carrier Landing using
Shipboard Relative Global Positioning System”, Report No. NAWCADPAX/RTR-2003/122, Naval Air Warfare Center Aircraft
Division, Patuxent River, MD, Sept. 2003.
2
J. F. Sweger, ”Design Specifications Development for Unmanned Aircraft Carrier Landings: A Simulation Approach”,
U.S.N.A. Trident Scholar Project Report No. 316, May 2003.
3
R. Heffley, ”Outer-Loop Control Factors For Carrier Aircraft”, Report number: RHE- NAV-90-TR-1, Naval Air Systems
Command, Dec. 1990.
4
Baha M. Suleiman, ”Identification of Finite-Degree-of-Freedom Models for Ship Motions”, PhD Thesis Virginia Polytech-
nic Institute and State University, Dec 2000.
5
G. C. Goodwin and K. S. Sin, Adaptive Filtering Prediction and Control, Prentice Hall, Englewood Cliffs, NJ, 1984.
6
T. I. Fossen, ”Guidance and Control of Ocean Vehicles”, John Wiley & Sons Ltd. ISBN 0-471-94113-1
7
K. S. Narendra and A. M. Annaswamy, Stable Adaptive Systems, Prentice Hall Inc., Englewood Cliffs, New Jersey, 1988.
8
J. D. Bošković, R. Prasanth and R. K. Mehra, ”Retrofit Reconfigurable Flight Control under Control Effector Damage”, to
appear in AIAA Journal of Guidance, Control & Dynamics, March 2007.
9
J. D. Bošković and R. K. Mehra, ”Robust Integrated Flight Control Design Under Failures, Damage and State-Dependent
Disturbances”, AIAA Journal of Guidance, Control & Dynamics, Vol. 28, No. 5, pp. 902-917, September-October 2005.
10
J. D. Bošković, R. Prasanth and R. K. Mehra, ”A Multi-Layer Autonomous Intelligent Control Architecture for Unmanned
Aerial Vehicles”, AIAA Journal of Aerospace Computing, Information, and Communication (JACIC), Special Issue on Intelligent
Systems, Vol. 1, pp. 605-628, Dec. 2004.
11
R. Prasanth and J. D. Bošković, “Design of stabilizing optimal one step ahead controllers”, AIAA-2005-6078, AIAA Guid-
ance, Navigation and Control Conference, San Francisco, CA, 15-18 August, 2005.
12
B.R. Bowring, “The accuracy of geodetic latitude and height equations”, Survey Review, vol28 #218, October 1985,
pp.202-206.
13
J. D. Bošković and R. K. Mehra, ”An Adaptive Reconfigurable Formation Flight Control Design”, in Proceedings of the
2003 American Control Conference, Denver, CO, June 4-6, 2003.
14
J. D. Bošković, S.-M. Li and R. K. Mehra, ”Semi-Globally Stable Formation Flight Control in Three Dimensions”, in
Proceedings of the 40th IEEE Conference on Decision and Control, Orlando, FL, December 2001.
15
S.-M. Li, J. D. Bošković and R. K. Mehra, ”A Globally Stable Formation Flight Controller in Two Dimensions”, AIAA-
2001-4046, in Proceedings of the 2001 AIAA Guidance, Navigation and Control (GNC) Conference, Montreal, Canada, August
2001.
16
J. D. Bošković, S. E. Bergstrom, R. K. Mehra, J. M. Urnes and M. Hood, ”Performance Evaluation of an Integrated Retrofit
Failure Detection, Identification and Reconfiguration (FDIR) System using High-Fidelity and Piloted Simulations”, Proc. SAE
World Aviation Congress, Reno, NV, Nov. 2004.
17
J. D. Bošković, ”Adaptive Control of a Class of Nonlinearly-Parametrized Plants”, IEEE Transaction on Automatic Control,
Vol. 43, No. 7, pp. 930-934, July 1998.
18
G. Prado, ”Optimal estimation of ship’s attitudes and attitude rates”, in IEEE Journal of Oceanic Engineering, Vol 4, Issue
2, April 1979.
19
X. Zhao, R. Xu and C. Kwan, ”Ship-motion prediction: algorithms and simulation results”, in IEEE International Confer-
ence on Acoustics, Speech, and Signal Processing (ICASSP ’04), Vol 5, May 2004.
20
A. Khan, C. Bil and K. E. Marion, ”Ship motion prediction for launch and recovery of air vehicles”, in Proceedings of
MTS/IEEE OCEANS, 2005, Vol 3, pg 2795-2801.
21
M. Ben Ghalia and A. T. Alouani, ”Robust control design of an autolanding system”, in Proceedings of the Twenty-Fifth
Southeastern Symposium on System Theory (SSST ’93), Mar 1993.
22
Li Yan, N. Sundararajan, P. Saratchandran and W. Zhifeng, ”Robust neuro-H∞ controller design for aircraft auto-landing”,
in IEEE Transactions on Aerospace and Electronic Systems, Vol 40, Jan 2004.

17 of 17

American Institute of Aeronautics and Astronautics

You might also like