Conference PaperPDF Available

Implementation of a Rotor Simulation with a Coupled Panel and Vortex Particle Method in State-Space Form

Authors:

Abstract

This paper describes the implementation of a coupled panel and vortex particle method in state-variable form for rotary wings. More specifically, the coupled panel and vortex particle dynamics are formulated as a nonlinear system of time-periodic, ordinary differential equations in first-order form with the specific objective for it to be self-contained and inherently linearizable. The proposed simulation model is a mesh-free aerodynamic method based on panel and vortex particle methods. Panels are used to model the wing surface as well as the near wake, whereas vortex particles are used to model the far wake. The code is implemented in MATLAB® and demonstrated through an example involving a UH-60-like rotor at hover.
Implementation of a Rotor Simulation with a Coupled Panel and Vortex
Particle Method in State-Space Form
Hussien Hafez
Graduate Research Assistant
Alessandro Cocco
Postdoctoral Researcher
Umberto Saetti
Assistant Professor
Department of Aerospace Engineering
University of Maryland
College Park, MD 20740
ABSTRACT
This paper describes the implementation of a coupled panel and vortex particle method in state-variable form for rotary
wings. More specifically, the coupled panel and vortex particle dynamics are formulated as a nonlinear system of time-
periodic, ordinary differential equations in first-order form with the specific objective for it to be self-contained and
inherently linearizable. The proposed simulation model is a mesh-free aerodynamic method based on panel and vortex
particle methods. Panels are used to model the wing surface as well as the near wake, whereas vortex particles are
used to model the far wake. The code is implemented in MATLAB®and demonstrated through an example involving
a UH-60-like rotor at hover.
INTRODUCTION
High-fidelity aeromechanics models are increasingly
making their way into rotorcraft flight dynamics simu-
lations for generalized maneuvering flight, flight control
design, and even real-time piloted simulations. Real-
time time-accurate free wake modeling was implemented
in the General Helicopter (GenHel) (Ref. 1) simula-
tion using the CHARM Wake Module (Ref. 2). The
model was used to compute the main rotor’s induced in-
flow, and real-time simulation was demonstrated. The
CHARM Wake Module was subsequently implemented
in Navy training simulators coupled with ship airwake
effects (Ref. 3). Recently, the CHARM Rotor Module
was incorporated into simulations of eVTOL configu-
rations (Ref. 4). The commercial simulation software
FLIGHTLAB can use Viscous Vortex Particle Models
(VVPM) (Ref. 5) to represent rotor inflow and wake in-
teractions between rotors and lifting surfaces. It has been
used for both conventional helicopters and electric verti-
cal take-off and landing (eVTOL) configurations.
Future Vertical Lift (FVL) and Urban Air Mobility
(UAM) configurations feature multiple rotors, high lev-
els of aerodynamic interactions, and, in the case of UAM,
high revolutions-per-minute (RPM) / variable speed ro-
tors. These features drive the need for advanced aerome-
Presented at the 6th Decennial VFS Aeromechanics Special-
ists’ Conference, Santa Clara, CA, Feb 6–8, 2024. Copy-
right © 2024 by the Vertical Flight Society. All rights reserved.
Distribution Statement A. Approved for public release; distri-
bution is unlimited.
chanics models while simultaneously making real-time
speeds (or even sufficiently fast execution speeds for
routine design) significantly more difficult. Higher ro-
tor RPM requires smaller time steps, modeling of aero-
dynamic interactions needs more significant amounts of
wake to be computed, and rigid rotor systems require
more costly structural dynamics models of the blades.
Thus, while more advanced aeromechanics models are
feasible, it is likely that, in many cases, execution speeds
required for real-time simulations or routine design ap-
plications will remain elusive. Therefore, high-fidelity
aeromechanics models must be formulated to be readily
linearized and simplified to extract more tractable and
less expensive models. Linearized state-space models
are particularly attractive from the control designer’s per-
spective. Not only are linearized models used in most
practical control design methodologies, but linear model
analysis provides many physical insights into system dy-
namics. To this end, a highly desirable feature for fu-
ture advanced simulations is a first-order state-variable
implementation of the aeromechanics (or state-space im-
plementation) that can be efficiently linear.
In Ref. 6, a state-space free-wake model was introduced
by Celi. The basis of the model is the University of
Maryland Free Wake (MFW) (Refs. 7, 8), which is ex-
pressed in partial differential equation (PDE) form. Celi
converted this model into first-order state-variable form
using the method of lines. The formulation of the MFW
model is well-suited for state-space implementation due
to the introduction of the wake age parameter. A sim-
ple kinematic equation for a vortex node subjected to the
1
Biot-Savart law is in a first-order state-space form. How-
ever, in the kinematic implementation, the nodes propa-
gate downstream and must be discarded when they reach
the end of each filament. Thus, the equations are not in
proper state-variable form, and there is no tractable state
equilibrium to linearize about (Ref. 9). In the state-space
formulation, a particular wake state represents the posi-
tion of a wake node of a given age.
In Celi’s state-space implementation, the underlying
PDEs are spatially discretized in the wake age using a
fourth-order 5-point biased upwind (5PBU4) scheme fol-
lowing the approach of Ref. 9. The system then be-
comes a set of first-order ordinary differential equations
(ODEs) in time (i.e., a state-space system), which can
be accurately integrated forward in time. More critically,
while the system states do not have a constant equilibrium
due to the time-periodic dynamics associated with a ro-
tor wake, they have a periodic equilibrium. It is worth
noting that if the same approach is applied to a fixed
wing, the wake dynamics will be time-invariant and have
an equilibrium consisting of a fixed point in the region
of attraction. Recently, a state-space free-vortex model
was implemented in the rotor model of the PSUHeloSim
flight simulation code (Ref. 10) for a rotor representative
of the UH-60. The model was linearized using the time-
periodic systems methods described above (Refs. 1113).
To improve the fidelity of this simulation, a near-wake
model was implemented to model the distribution of cir-
culation along the blade, and shed vortices were used to
model unsteady aerodynamics. A vortex lattice model of
the near wake, as described in Ref. 14, has been imple-
mented in the state-space wake model of Ref. 15. How-
ever, all of these models have three significant limitations
in that they are: (i) formulated in such a way to be suit-
able for rotating wings only (singularities arise if the ro-
tor angular speed is set to zero), (ii) limited to blade load
spanwise predictions as they do not incorporate a chord-
wise discretization of the wing, (iii) limited in modeling
rotor-on-rotor and rotor-on-wing interactions due to in-
herent instabilities in these instances.
These limitations are generally relaxed by mid-fidelity
aerodynamic solvers developed in recent years that make
use of the vortex particle method (VPM) (Refs. 1619).
This numerical methodology showed a reasonably ac-
curate representation of the aerodynamic interactions
among several bodies typical of complex rotorcraft con-
figurations and an enhanced computational time with
respect to unsteady Reynolds-averaged Navier-Stokes
(URANS) computational fluid dynamics (CFD) simula-
tions and, in general, with respect to grid-based meth-
ods. To cite a few examples, Lu et al. (Ref. 20) de-
veloped an optimization methodology for a helicopter
design based on a viscous VPM model combined with
an unsteady panel hybrid method. Alvarez and Ning
developed a VPM-based code (Ref. 21) to investigate
multirotor configurations. Tan et al. (Ref. 22) used a
vortex-based approach coupled with a viscous boundary
model to study rotor-rotor interactional problems during
shipboard operations. Recently, Politecnico di Milano
developed a novel, flexible mid-fidelity computational
tool called DUST (Refs. 2326) 1for the simulation of
the aerodynamics of complex rotorcraft configurations.
However, all said codes are not developed using a state-
variable formulation and, as such, cannot be linearized to
extract simplified models for real-time simulation, stabil-
ity analysis, and controller design. Moreover, the time-
marching nature of these codes does not allow for the
solution of unstable equilibria. The solution of unstable
equilibria becomes particularly important when the ro-
tor wake is coupled with the rotorcraft flight dynamics,
which are unstable at hover and across most of the flight
envelope. Moreover, the solution of unstable equilibria is
also relevant to aeroelastic problems (Refs. 19,27).
Outside of the rotorcraft community, Palacios and Mu-
rua (Ref. 28) developed a discrete state-space formula-
tion of the unsteady vortex lattice method coupled with a
non-linear beam model, and a similar approach was used
in (Ref. 29) validating it against the Pazy wing aeroelastic
testbed 2. Other efforts also focused on state-pace, lin-
earized, and reduced-order formulations (Refs. 3033).
These examples are, however, limited by the modeling of
a single lifting component. By the presence of a panel
wake that is inherently prone to numerical instabilities
when used to model the interaction between aerodynamic
bodies, such as rotor-wing or rotor-rotor interaction.
Most recently, a coupled panel and vortex particle method
in state-space form was proposed by the authors for
fixed wings and relax all aforementioned limitations
of aeromechanics models (Ref. 34). Along with this
method, an analytical linearization algorithm was de-
veloped to abate the cost of linearization over perturba-
tion methods by O(n2), where nis the total number of
states of the system. This reduction in linearization cost
has the potential to enable the linearization of high-order
aeromechanics models of rotary-wings which, in compar-
ison to fixed-wings, require being linearized at incremen-
tal time steps over one rotor revolution to yield a linear
time-periodic (LTP) representation of the rotor wake dy-
namics.
As such, the objective of this paper is to extend the state-
space, coupled panel and vortex particle method pro-
posed in Ref. (Ref. 34) from fixed to rotary wings. As
part of this objective, the coupled vortex and particle dy-
namics will be demonstrated for a UH-60-like main rotor
blade. This requires formulating the coupled vortex and
particle dynamics as a nonlinear time-periodic (NLTP)
system in first-order form for it to be suitable to lineariza-
tion and periodic systems lifting methods. These are nec-
essary steps to transform the NLTP dynamics to the de-
sired linear time-invariant (LTI) form.
The paper begins with a mathematical description of the
coupled panel and vortex particle dynamics in PDE form.
This is followed by a discussion on how these partial dif-
ferential equations are discretized to obtain an equivalent
1https://public.gitlab.polimi.it/DAER/dust
2https://nescacademy.nasa.gov/workshops/
AePW3/public/
2
system of nonlinear time-periodic (NLTP) ordinary dif-
ferential equations in first-order form. Next, the coupled
panel and vortex particle dynamics is implemented and
demonstrated for a UH-60-like main rotor blade. Final
remarks summarize the study’s overall findings and iden-
tify future developments.
COUPLED PANEL AND VORTEX
PARTICLE METHOD
Overview
The coupled panel and vortex particle method is an adap-
tation to that proposed in Ref. 34. This simulation model
is a mesh-free aerodynamic method based on panel and
vortex particle methods. Panels are used to model the
wing surface as well as the near wake, whereas vortex
particles are used to model the far wake. This setup is
shown in Fig. 1. This section provides an overview of
the mathematical background behind this method.
wing panels
µb,σb
wake panels
µw,rw
wake particles
rp,αp
Fig. 1: Simulation model schematic.
PDE Formulation
The mathematical formulation of the present method re-
lies on a vorticity-velocity formulation of the aerody-
namic problem based on Helmholtz’s decomposition of
the velocity field and a Lagrangian description of the vor-
ticity field. The Helmholtz decomposition of the velocity
field states that the velocity field u
u
u(r
r
r,t)can be written as
the sum of an irrotational field characterized by the po-
tential velocity u
u
uϕ=
ϕ(i.e., the velocity induced by
lifting bodies such as the wing, and by near-wake panels)
and a solenoidal field described by the rotational velocity
u
u
uψ
ψ
ψ=
×ψ
ψ
ψ(i.e., the velocity induced by vortex parti-
cles):
u
u
u(r
r
r,t) = u
u
uϕ(r
r
r,t) + u
u
uψ
ψ
ψ(r
r
r,t)(1)
Since the rotational velocity is a solenoidal vector field,
the incompressibility constraint reduces to the Laplace
equation for the kinetic potential ϕ
ϕ
ϕ(r
r
r,t)in the fluid do-
main :
0=
·u
u
u=
·u
u
uϕ+
·u
u
uψ
ψ
ψ
|{z}
·(
×ψ
ψ
ψ)0
ϕ
ϕ
ϕ=0 (2)
The Laplace equation is solved using Morino’s method
(Ref. 35) to retrieve the pressure distribution on the lifting
bodies.
Because the potential velocity is an irrotational velocity
field, the vorticity field ω
ω
ω(r
r
r,t)acts as a volume forcing
of the Poisson equation for the vector potential ψ
ψ
ψ(r
r
r,t):
ω
ω
ω=
×u
u
uφ
|{z }
×
ϕ0
+
×u
u
uψ
ψ
ψ ψ
ψ
ψ=ω
ω
ω(3)
given the vector identity ψ
ψ
ψ=
(
·ψ
ψ
ψ)
×
×ψ
ψ
ψand
the gauge condition
·ψ
ψ
ψ=0. Then, the Lagrangian de-
scription of the dynamical equation governing the vortic-
ity field ω
ω
ω(r
r
r,t)of an incompressible flow is:
Dω
ω
ω
Dt = (ω
ω
ω·
)u
u
u+νω
ω
ω(4)
where νis the flow kinematic viscosity and Dω
ω
ω/Dt rep-
resents the material derivative of the vorticity associated
with a material particle.
Differential problems defined in the fluid domain are
manipulated using Green’s function method to obtain a
grid-free volume formulation of the aerodynamic prob-
lem. Note that, in the current formulation, viscosity is
omitted.
Wing and Wake Panel Intensity With regards to the
potential portion of Eq. 1, Morino’s method (Ref. 35)
is adopted to solve the Laplace equation using Green’s
functions. Morino’s method discretizes the surface of the
solid bodies binto panels of uniform source (σ
σ
σb) and
doublet intensities (µ
µ
µb). The sources term is defined as
σ
σ
σb=ˆ
n
n
n·(u
u
ubU
U
Uu
u
uψ
ψ
ψ), where u
u
ubis the body velocity,
U
U
Uis the free-stream velocity, and u
u
uψ
ψ
ψis the velocity in-
duced by the vortex particles. The potential part of the
wake wis discretized into panels of uniform doublet
intensity µ
µ
µw. The rotational part is discretized into a se-
ries of particles of intensities α
α
αp. A discrete formulation
of the problem is given by:
K
K
K1µ
µ
µb+K
K
K2µ
µ
µTE
w+K
K
K3µ
µ
µw+K
K
K4α
α
αp=B
B
Bw
w
w(5)
where K
K
K1RNb×Nb,B
B
BRNb×Nb, and Nbis the total num-
ber of wing panels. Additionally, K
K
K2RNb×Nsis a rect-
angular matrix where Nsis the number of panels in span-
wise direction. Moreover, K
K
K3RNb×Nwis a rectangular
matrix where Nwis the total number of near-wake pan-
els excluding the trailing edge (TE) wake panels. Finally,
K
K
K4RNb×Npis a rectangular matrix where Npis the total
number of vortex particles.
Equation (5) is enhanced with three additional algebraic
equations: (i) Kutta’s condition, which provides a link
between the intensity of the trailing edge wake panel and
the first implicit wake panel, (ii) an equation to link the
intensity and direction of the first line of wake particles
with the last row of potential wake panels, as shown in
Ref. 34, and (iii) the transfer of a panel wake intensity
3
from one step to the other. These three equations are pro-
vided below:
K
K
K5µ
µ
µb=µ
µ
µTE
w(6a)
K
K
K6µ
µ
µw=α
α
αp(6b)
K
K
K7µ
µ
µw+K
K
K8µ
µ
µTE
w=µ
µ
µt+1
w(6c)
For more detail on this derivation and on the definition
of the various terms, the interested reader is invited to
consult Ref. 34.
Vortex Particle Intensity The vorticity field can be dis-
cretized with Npvortex particle (Ref. 16):
ω
ω
ω(r
r
r,t) =
Np
i=1
α
α
αpi(t)δr
r
rr
r
rpi(t)(7)
where r
r
ris the evaluation point position, r
r
rpiis the position
of the ith particle, and α
α
αpiis the intensity of the ith par-
ticle. By applying Green’s method to the Poisson equa-
tion 3, the rotational portion of this velocity field is found:
u
u
uψ(r
r
r,t) = 1
4π
Np
i=1
r
r
rr
r
rpi
|r
r
rr
r
rpi|3×α
α
αpi(t)(8)
=K
K
Kψ(r
r
r,r
r
rp)×α
α
αp(t)(9)
In this work, similarly to Ref. 23, the matrix K
K
Kψ(i.e.,
the Rosenhead kernel) is implemented as the regularised
version of the Biot-Savart kernel:
K
K
Kψ(x
x
x,y
y
y) = 1
4π
x
x
xy
y
y
(|x
x
xy
y
y|2+δ2)3/2(10)
In this equation, the regularization parameter δis propor-
tional to the radius of the vortex particles (vortex radius).
The matrix K
K
Kψis assembled by taking advantage of the
skew-symmetric matrix that defines the cross product:
K
K
Kψ×=
0
0
0K
K
KzK
K
Ky
K
K
Kz0
0
0K
K
Kx
K
K
KyK
K
Kx0
0
0
3Nb×3Np
(11)
where K
K
Kx,K
K
Ky, and K
K
Kzare the matrices containing the
x,y,zcomponents of the Rosenhead kernel evaluated
for each particle on each surface panel control point.
Each block matrix has dimension Nb×Np. The non-
penetration condition is enforced on the panels:
u
u
up
b=N
N
N·K
K
Kψ×α
α
αp=K
K
K4α
α
αp(12)
where N
N
Nis the matrix that contains the unit vectors nor-
mal to the panel surface. Again, for more detail on this
derivation, the interested reader is invited to consult Ref.
34.
State-Space Formulation
It is desirable to convert the coupled panel and vortex
particle method from PDE to ODE form. Because the
coupled panel and wake dynamics for a rotating blade
are periodic, consider a nonlinear system of time-periodic
ODEs in first-order form:
˙
x
x
x=f
f
f(x
x
x,u
u
u,t)(13a)
y
y
y=g
g
g(x
x
x,u
u
u,t)(13b)
where x
x
xRnis the state vector, u
u
uRmis the control
input vector, y
y
yRlis the output vector, and tis the di-
mensional time in seconds. Additionally, f
f
fare the non-
linear, coupled panel and vortex particle dynamics and g
g
g
are the output equations. The nonlinear functions f
f
fand
g
g
gare T-periodic in time such that:
f
f
f(x
x
x,u
u
u,t) = f
f
f(x
x
x,u
u
u,t+T)(14a)
g
g
g(x
x
x,u
u
u,t) = g
g
g(x
x
x,u
u
u,t+T)(14b)
The fundamental period of the system is T=2π
ωseconds,
where ωis either the angular speed of the main rotor in
rad/s. Note that, assuming a solution x
x
x(t)and u
u
u(t)ex-
ists, then this solution for NLTP systems will be periodic
such that x
x
x(t) = x
x
x(t+T)and u
u
u(t) = u
u
u(t+T). In the
proposed framework, the state vector of the coupled panel
and vortex particle method is:
x
x
xT=r
r
rT
wr
r
rT
pµ
µ
µT
wα
α
αT
pµ
µ
µT
b(15)
where:
r
r
rware the wake panel positions,
r
r
rpare the vortex particle positions,
α
α
αpare the vortex particle intensities,
µ
µ
µware the wake panel intensities, and
µ
µ
µbthe surface panel intensities.
For a 3-dimensional aerodynamic model, the total num-
ber of states is n=3Nn
w+3Np+Nw+3Np+Nb
where Nn
wis the total number of wake nodes excluding
the trailing-edge wake nodes. The control input vector of
the system is defined as the swashplate inputs:
u
u
uT=θ0θ1cθ1s(16)
where θ0is the collective angle, θ1cis the lateral cyclic,
and θ1sis the longitudinal cyclic. The outputs of the sys-
tem are defined as the wing surface pressure distribution
and the total wing aerodynamic loads:
y
y
yT=p
p
pTF
F
FT(17)
Wake Panel Intensity The dynamics of the wake panel
intensity are obtained by approximating the first-order
derivative with a forward difference scheme:
˙
µ
µ
µw=µ
µ
µt+1
wµ
µ
µw
dt =K
K
K7µ
µ
µwµ
µ
µw
dt +K
K
K8µ
µ
µTE
w
dt =
=(K
K
K7I
I
I)
dt µ
µ
µw+K
K
K8
dt µ
µ
µTE
w=W
W
W1µ
µ
µw+W
W
W2µ
µ
µTE
w
(18)
where K
K
K7and K
K
K8are the shifting matrices. Then, the
wake panel dynamics become:
˙
µ
µ
µw=W
W
W1µ
µ
µw+W
W
W2µ
µ
µTE
w
=W
W
W1µ
µ
µw+W
W
W2K
K
K5µ
µ
µb
=(W
W
W1W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1K
K
K3)µ
µ
µw
W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1K
K
K4α
α
αp
+W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1B
B
Bw
w
w
(19)
4
The various terms in this equation are defined in Ref. 34.
Wing Panel Intensity Substituting Eq. (6a) into Eq. (5)
yields an explicit form for the wing panel intensity:
µ
µ
µb=(K
K
K1+K
K
K2K
K
K5)1K
K
K3µ
µ
µw+K
K
K4α
α
αpB
B
Bw
w
w(20)
The dynamics of the wing doublet intensities are com-
puted by taking the time derivative of the equation as fol-
lows:
˙
µ
˙
µ
˙
µb=(K
K
K1+K
K
K2K
K
K5)1˙
K
˙
K
˙
K3µ
µ
µw+K
K
K3˙
µ
˙
µ
˙
µw
+˙
K
˙
K
˙
K4α
α
αp+K
K
K4˙
α
˙
α
˙
αpB
B
B˙w
˙w
˙w(21)
where the evolution ofK
K
K3and K
K
K4is governed by the wake
transport equation. The evolution of µ
µ
µwfollows Eq. (19),
whereas the evolution of αpis governed by Eq. (22).
Vortex Particle Intensity A constant wake age descrip-
tion 9 of the rotational velocity and the vorticity fields
is provided by the kinematic and dynamical equations of
the trajectory of the material particles and the vorticity as
follows (i.e., the transpose method):
Dα
α
α
Dt =(α
α
αp·
T)u
u
u
=(α
α
αp·
T
p)(U
U
U+u
u
uψ+u
u
uϕ) + ˙
K
K
K6µ
µ
µw+K
K
K6˙
µ
µ
µw
(22)
where u
u
uψ=v
v
vp,u
u
uϕ=v
v
vµ
b+v
v
vσ
b+v
v
vw, and
T
pU
U
U=0.
The vortex particle vorticity equation, i.e., Eq. (22), is
spatially discretized using the method of lines (Ref. 6):
α
α
αp
t+α
α
αp
ζ
ζ
t=(α
α
αp·
T
p)(U
U
U+u
u
uψ+u
u
uϕ)
+˙
K
K
K6µ
µ
µw+K
K
K6˙
µ
µ
µw
(23)
where ζis the wake age parameter at each spanwise lo-
cation:
ζi=rit=Uit(24)
In this equation, riand Uiare the radial location and tan-
gential velocity of the ith wake node. The wake age is
a distance measured along the vortex starting from the
vortex release point on the wing trailing edge such that a
particular wake state represents the position of a wake
node/particle of a given age. The partial derivative of
the wake node positions with respect to the wake age
is discretized using a fourth-order 5-point biased upwind
(5PBU4) scheme. This discretization is key to making
the system of ODE time-periodic in that it associates each
state (i.e., wake panel node and particle position) to a par-
ticular wake age ζ. Thus, each state will always have
the same wake age such that, at equilibrium, the position
states will be periodic and oscillating about a fixed mean.
If one were to solve Eq. (22) directly (i.e., kinematic ap-
proach), then the system would be time varying because
each state would flow down the stream with a higher
wake age at each time step. Not only this would make
the system time varying but, to preserve a fixed number of
states, it would also require to: (i) destroy the last raw of
vortex particles at each time step and (ii) to create a new
row of wake panels at each time step (Ref. 9). Both of
these are impractical. The same applies to the remaining
states of the system discussed below wake panel, vor-
tex particle, and wing panel intensities. It is critical for
the wake dynamics to be a time-periodic system to make
it suitable to harmonic decomposition and thus approx-
imable with a higher-order linear time-invariant system.
This way, the large pool of time-invariant system anal-
ysis tools can be applied for dynamics stability analysis
and control design. The matrix A
A
Aζiis the finite difference
matrix corresponding to the 5PBU4 scheme 6 defined for
each blade radial station i:
A
A
Aζi=Vi
12
25 48 36 16 3
310 18 6 1
18 0 8 1
1 6 18 10 3
(25)
Then, the vortex particle vorticity equation becomes:
˙
α
α
αp=A
A
Aζα
α
αp+ (α
α
αp·
T
p)(U
U
U+u
u
uψ+u
u
uϕ)
+˙
K
K
K6µ
µ
µw+K
K
K6˙
µ
µ
µw
(26)
Wake Panel and Vortex Particle Position The position
of the wake panels and particles is found by using the
vortex transport equation:
Dr
r
r
Dt =v
v
vind (27)
where the induced velocity is calculated using Biot-
Savart law (Refs. 6, 36). The induced velocity at each
wake node is given by:
v
v
vind =v
v
vσ
b+v
v
vµ
b+v
v
vw+v
v
vp(28)
In Eq. (28), v
v
vσ
bis the induced velocity contribution due to
the body sources, v
v
vµ
bis the induced velocity contribution
due to the body doublets, and v
v
vwis the induced velocity
contribution due to the wake panel doublets. Equations
for these induced velocities can be found in (Ref. 36).
Additionally, v
v
vpis the contribution due to the wake par-
ticles. The transport equation, i.e., Eq. (27), is also
transformed into a system of ODEs via the method of
lines (Ref. 6), leading to:
tr
r
r+r
r
r
ζ
ζ
t=v
v
vind (29)
By adopting the same 5-point spatial discretization as
above, a time-periodic system of ODEs for the wake pan-
els and particles position is obtained:
˙
r
r
r=A
A
Aζr
r
r+v
v
vind (30)
Summary The following equations summarize the cou-
pled panel and vortex particle dynamics in state-space
5
form, i.e., the nonlinear function f
f
f(x
x
x,u
u
u,t):
˙
r
r
rw=A
A
Aζr
r
rw+v
v
vind(r
r
rw,r
r
rp,α
α
αp,µ
µ
µw,µ
µ
µb)(31a)
˙
r
r
rp=A
A
Aζr
r
rp+v
v
vind(r
r
rw,r
r
rp,α
α
αp,µ
µ
µw,µ
µ
µb)(31b)
˙
µ
µ
µw=(W
W
W1W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1K
K
K3)µ
µ
µw(31c)
W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1K
K
K4α
α
αp
+W
W
W2K
K
K5(K
K
K1+K
K
K2K
K
K5)1B
B
Bw
w
w
˙
α
α
αp=A
A
Aζα
α
αp(31d)
1
4π1
R3α
α
αj
p×α
α
αp3
R5r
r
rj(r
r
rj·α
α
αj
p×α
α
αp)
(31e)
+α
α
αp·(
T
pv
v
vµ
b+
T
pv
v
vσ
b) + α
α
αp·
T
pv
v
vw+˙
K
K
K6µ
µ
µw
+K
K
K6˙
µ
µ
µw
˙
µ
µ
µb=(K
K
K1+K
K
K2K
K
K5)1˙
K
˙
K
˙
K3µ
µ
µw+K
K
K3˙
µ
˙
µ
˙
µw+˙
K
˙
K
˙
K4α
α
αp(31f)
+K
K
K4˙
α
˙
α
˙
αpB
B
B˙w
˙w
˙w
The output equations, i.e., the nonlinear function
g
g
g(x
x
x,u
u
u,t), are:
C
C
Cp=11
U2
u
u
usurf2+2˙
µ
µ
µb(32a)
F
F
F=ˆ
A
A
Ap
p
p(32b)
For the complete derivation of these equations the inter-
ested reader is referred to Ref. 34.
RESULTS
The coupled panel and wake method is implemented in
MATLAB®for a UH-60-like rotor blade. The rotor blade
characteristics are reported in Table 1. The time step of
the simulation is chosen as t=2π/(Ω∆ψ) = 0.006464
seconds, corresponding to a rotor angular speed of =
27 rad/s and a non-dimensional time step of ψ=10
deg. To find an equilibrium condition, the coupled panel
and vortex wake dynamics are time marched for a swash-
plate setting corresponding to θ0=19.7 deg, θ1c=0, and
θ1s=0. The collective angle corresponds to the hover
trim condition for a UH-60 with a weight of W=17,000
lb. This trim condition was found with the PSUHeloSim
flight dynamics code (Ref. 10). The simulation features
10 spanwise and 10 chordwise blade panels, 10 spanwise
and 5 chordwise near-wake panels, and 10 spanwise and
177 chordwise vortex particles corresponding to approx-
imately five wake revolutions. Figure 2 shows a three-
dimensional representation of the converged wake after
approximately 8 rotor revolutions. In this figure, the wake
is shown to contract below the rotor disk, according to
momentum theory (Ref. 37). Additionally, the strength of
the particle is maximum at the tip of the blade, forming a
helicoidal vortex structure. Based on these observations,
the coupled panel and vortex particle method appears to
capture the well-known physics of a rotor wake.
Next, the response of the coupled panel and vortex wake
dynamics following a 2 deg doublet in the collective an-
gle θ0is simulated. Results are presented for: (i) a repre-
sentative wake panel at the outermost spanwise location
Table 1: Characteristics of the UH-60-like main rotor
blade (Ref. 1).
Parameter Value Units
Radius, R26.8 ft
Blade chord, c1.73 ft
Blade twist, θtw 13 deg
Flapping hinge offset 1.25 ft
Spar length 2.25 ft
Angular speed, 27 rad/s
and with an equivalent wake age of 45 deg, and (ii) a rep-
resentative vortex particle also located at the outermost
spanwise location and with an equivalent wake age of 45
deg. This setup is shown in Fig. 3.
Figure 4 shows the position response of the representative
wake panel. While the longitudinal and lateral positions
of the panel change periodically, the vertical position is
shown to decrease/increase with an increase/decrease of
the collective angle, which suggests that the near wake is
pushed down/up when the inflow is increased/decreased
as a result of an increase/decrease of the collective angle.
Similar observations can be made for the representatie
vortex particle position response, shown in Fig. 5.
CONCLUSIONS
A coupled panel and vortex particle method in state-
variable form was extended from fixed to rotary wings.
The coupled panel and vortex particle dynamics were
formulated as a nonlinear system of time-periodic or-
dinary differential equations in first-order form to be
self-contained and inherently linearizable. The proposed
simulation model consisted of a mesh-free aerodynamic
method based on panel and vortex particle methods. Pan-
els were used to model the wing surface as well as the
near wake, whereas vortex particles were used to model
the far wake. The code was implemented in MATLAB®
and demonstrated through an example involving a rotor
at hover. Based on this work, it is concluded that state-
space modeling of grid-free aerodynamic methods, such
as panel and vortex particle methods for helicopter ro-
tors, is possible. This formulation offers a unique oppor-
tunity to obtain linearized models that can be analyzed
with linear systems tools. These tools include stability
and response analysis, model order reduction, and con-
trol design. Moreover, the coupled panel and vortex par-
ticle dynamics in state-space form can be used to aug-
ment the flight dynamics to provide high-fidelity, time-
accurate simulations of the coupled rigid-body, rotor, and
rotor wake dynamics.
Future work will focus on additional validation and on
the linearization of the state-space coupled panel and vor-
tex particle method using both numerical and analytical
methods (Ref. 34). Linearized models of the coupled
panel and vortex particle dynamics have applications in
the flight dynamics of rotary-wing vehicles, where these
6
-30
-20
-10
20
0
0
30
20
-20 10
0
-10
-20
-30
1600
1800
2000
2200
Fig. 2: Three-dimensional representation of the coupled panel and vortex particle wake at hover for θ0=19.7 deg.
Fig. 3: Schematic indicating the states whose responses
are plotted.
0 0.5 1 1.5 2
-20
0
20
0 0.5 1 1.5 2
-20
0
20
0 0.5 1 1.5 2
-0.4
-0.3
-0.2
Fig. 4: Position response of a representative wake panel
node to a 2 deg doublet in the collective input.
dynamics can be used to augment the rigid-body dynam-
ics. The coupled rigid-body and wake dynamics can be
0 0.5 1 1.5 2
-20
0
20
0 0.5 1 1.5 2
-20
0
20
0 0.5 1 1.5 2
-0.4
-0.2
Fig. 5: Position response of a representative vortex
particle to a 2 deg doublet in the collective input.
leveraged to assess the stability, response characteristics,
and handling qualities of vehicles experiencing aerody-
namic interactions between rotors, wings, and/or obsta-
cles. Moreover, unlike time-marching approaches, state-
space representations of the wake dynamics are suitable
for determinations of unstable equilibria via trim solu-
tion methods. This is particularly important for rotary-
wing aircraft, given their unstable nature across typically
a large portion of their flight envelope.
7
ACKNOWLEDGMENTS
This research was partially funded by the U.S. Govern-
ment under agreement no. N000142312067. The views
and conclusions contained in this document are those of
the authors and should not be interpreted as representing
the official policies, either expressed or implied, of the
U.S. Government.
REFERENCES
1Howlett, J. J., “UH-60A Black Hawk Engineering
Simulation Program. Volume 1: Mathematical Model,
Technical report, NASA-CR-166309, 1980.
2Horn, J. F., Bridges, D. O., Wachspress, D. A., and
Rani, S. L., “Implementation of a Free-Vortex Wake
Model in Real-Time Simulation of Rotorcraft, AIAA
Journal of Computing, Information, and Communica-
tions, Vol. 3, (3), Mar 2006, pp. 93–107.
doi: https://doi.org/10.2514/1.18273
3Keller, J. D., Wachspress, D. A., and Hoffler, J. C.,
“Real Time Free Wake and Ship Airwake Model for Ro-
torcraft Flight Training Applications, Proceedings of the
71st Annual Forum of the American Helicopter Society,
Virginia Beach, VA, May 5-7, 2015.
4Theron, A., Farges, C., Peaucelle, D., and Arzelier, D.,
“Periodic H2synthesis for spacecraft in elliptical orbits
with atmospheric drag and J2perturbations,” Proceedings
of the 2007 American Control Conference, New York,
NY, July 9-13, 2007.
doi: 10.1109/ACC.2007.4282879
5Zhao, J. and He, C., “A Viscous Vortex Particle Model
for Rotor Wake and Interference Analysis, Journal of the
American Helicopter Society, Vol. 55, (1), Jan 2010.
doi: https://doi.org/10.4050/JAHS.55.012007
6Celi and Roberto, “State-Space Representation of Vor-
tex Wakes by the Method of Lines,” Journal of the Amer-
ican Helicopter Society, Vol. 50, (2), 2005, pp. 195–205.
doi: 10.4050/1.3092855
7Bagai, A. and Leishman, G. J., “Rotor Free-
Wake Modeling Using a Pseudo-Implicit Tech-
nique—Including Comparison with Experimental
Data,” Journal of the American Helicopter Society,
Vol. 40, (3), Jul 1995, pp. 29–41.
doi: https://doi.org/10.4050/JAHS.40.29
8Bhagwat, M. J., Transient Dynamics of Helicopter Ro-
tor Wakes Using a Time-Accurate Free-Vortex Method,
Ph.D. thesis, University of Maryland, 2001.
doi: 10.2514/6.2001-993
9Miller, W. O. and Bliss, D. B., “Direct periodic so-
lutions of rotor free wake calculations, Journal of the
American Helicopter Society, Vol. 38, (2), 2005, pp. 53–
60.
doi: 10.4050/JAHS.38.53
10Horn, J. F., “Non-Linear Dynamic Inversion Control
Design for Rotorcraft,” Aerospace, Vol. 6, (38), 2019.
doi: https://doi.org/10.3390/aerospace6030038
11Saetti, U. and Horn, J. F., “Implementation and Lin-
earization of a Rotor Simulation with a State-Space Free-
Vortex Wake Model, Proceedings of the 78th Annual Fo-
rum of the Vertical Flight Society, Fort Worth, TX, May
10-12, 2022.
doi: 10.4050/F-0078-2022-17577
12Saetti, U., “Linearization of a Rotor Simulation with
a State-Space Free-Vortex Wake Model in a Shipboard
Environment, Proceedings of the AIAA Aviation Forum,
Chicago, IL & Virtual, Jun 27 - Jul 1, 2022.
doi: https://doi.org/10.2514/6.2022-3646
13Saetti, U. and Horn, J. F., “Implementation and Lin-
earization of State-Space Free-Vortex Wake Models for
Rotary- and Flapping-Wing Vehicles,” Journal of the
American Helicopter Society, Vol. 68, (4), Apr 2023,
pp. 42004–42017.
doi: https://doi.org/10.4050/JAHS.68.042004
14Johnson, W., Rotorcraft Aeromechanics, Cambridge
University Press, 2013.
doi: https://doi.org/10.1017/CBO9781139235655
15Saetti, U. and Horn, J. F., “Tiltrotor Simulations with
Coupled Flight Dynamics, State-Space Aeromechanics,
and Aeroacoustics,” Journal of the American Helicopter
Society, Vol. 69, (1), Apr 2024.
doi: 10.4050/JAHS.69.012003
16Winckelmans, G. S., Topics in vortex methods for the
computation of three-and two-dimensional incompress-
ible unsteady flows, Ph.D. thesis, California Institute of
Technology, 1989.
doi: 10.7907/19HD-DF80
17Cottet, G.-H., Koumoutsakos, P. D., et al.,Vortex
methods: theory and practice, Vol. 8, Cambridge univer-
sity press Cambridge, 2000.
doi: 10.1017/CBO9780511526442
18Mimeau, C. and Mortazavi, I., “A review of vortex
methods and their applications: From creation to recent
advances, Fluids, Vol. 6, (2), 2021, pp. 68.
doi: 10.3390/fluids6020068
19Zhu, W., Morandini, M., and Li, S., “Viscous Vortex
Particle Method Coupling with Computational Structural
Dynamics for Rotor Comprehensive Analysis, Applied
Sciences, Vol. 11, (7), 2021.
doi: 10.3390/app11073149
20Lu, Y., Su, T., Chen, R., Li, P., and Wang, Y., “A
method for optimizing the aerodynamic layout of a he-
licopter that reduces the effects of aerodynamic interac-
tion,” Aerospace Science and Technology, Vol. 88, 2019,
pp. 73 83.
doi: 10.1016/j.ast.2019.03.005
8
21Alvarez, E. and Ning, A., “Development of a Vor-
tex Particle Code for the Modeling of Wake Interaction
in Distributed Propulsion, AIAA Applied Aerodynam-
ics Conference, Atlanta, GA, 06 2018.
doi: 10.2514/6.2018-3646
22Tan, J., Zhou, T., Sun, J., and Barakos, G., “Numeri-
cal investigation of the aerodynamic interaction between
a tiltrotor and a tandem rotor during shipboard opera-
tions,” Aerospace Science and Technology, Vol. 87, 2019,
pp. 62–72.
doi: 10.1016/j.ast.2019.02.005
23Tugnoli, M., Montagnani, D., Syal, M., Droandi, G.,
and Zanotti, A., “Mid-fidelity approach to aerodynamic
simulations of unconventional VTOL aircraft configu-
rations,” Aerospace Science and Technology, Vol. 115,
2021, pp. 106804.
doi: 10.1016/j.ast.2021.106804
24Savino, A., Cocco, A., Zanoni, A., Zanotti, A., and
Muscarello, V., A Coupled Multibody -Mid Fidelity
Aerodynamic Tool for the Simulation of Tiltrotor Ma-
noeuvres,” Proceedings of the 47th European Rotorcraft
Forum, Glasgow, UK, 09 Sep 6-9, 2021.
25Cocco, A., Savino, A., Montagnani, D., Tugnoli, M.,
Guerroni, F., Palazzi, M., Zanoni, A., Zanotti, A., and
Muscarello, V., “Simulation of Tiltrotor Maneuvers by a
Coupled Multibody-Mid Fidelity Aerodynamic Solver,
Proceedings of the 46th European Rotorcraft Forum,
Moscow, Russia, 09 2020.
26Savino, A., Cocco, A., Zanotti, A., Tugnoli, M.,
Masarati, P., and Muscarello, V., “Coupling mid-fidelity
aerodynamics and multibody dynamics for the aeroelastic
analysis of rotary-wing vehicles, Energies, Vol. 14, (21),
2021, pp. 6979.
doi: 10.3390/en14216979
27Lee, H., Sengupta, B., Araghizadeh, M. S., and My-
ong, R. S., “Review of vortex methods for rotor aerody-
namics and wake dynamics, Advances in Aerodynamics,
Vol. 4, (1), May 2022, pp. 20.
doi: 10.1186/s42774-022-00111-3
28Murua, J., Palacios, R., and Graham, J. M. R., Ap-
plications of the unsteady vortex-lattice method in air-
craft aeroelasticity and flight dynamics,” Progress in
Aerospace Sciences, Vol. 55, 2012, pp. 46–72.
doi: 10.1016/j.paerosci.2012.06.001
29Hilger, J. and Ritter, M. R., “Nonlinear aeroelastic
simulations and stability analysis of the pazy wing aeroe-
lastic benchmark,” Aerospace, Vol. 8, (10), 2021, pp. 308.
doi: 10.3390/aerospace8100308
30Fornasier, L., “Linearized potential flow analysis of
complex aircraft configurations by HISSS, a higher order
panel method,” 23rd Aerospace Sciences Meeting, 1985.
doi: 10.2514/6.1985-281
31Simpson, R., Palacios, R., and Maraniello, S., “State-
space realizations of potential-flow unsteady aerodynam-
ics with arbitrary kinematics,” , 01 2017.
doi: 10.2514/6.2017-1595
32Maraniello, S. and Palacios, R., “State-Space Real-
izations and Internal Balancing in Potential-Flow Aero-
dynamics with Arbitrary Kinematics,” AIAA Journal,
Vol. 57, (6), 2019, pp. 2308–2321.
doi: 10.2514/1.J058153
33Erik, G. and Roeland, D. B., “Reduced-Order Model-
ing of Continuous-Time State-Space Unsteady Aerody-
namics,” 53rd AIAA Aerospace Sciences Meeting, 2015.
doi: 10.2514/6.2015-0260
34Hafez, H., Cocco, A., and Saetti, U., “Implementation,
Linearization, and Order Reduction of a Coupled Panel
and Free-Wake Method in State-Space Form, Proceed-
ings of the AIAA SciTech Forum, Orlando, FL, Jan 8-12,
2024.
doi: https://doi.org/10.2514/6.2024-2265
35Morino, L. and Kuot, C., “Subsonic Potential Aerody-
namics for Complex Configurations: A General Theory,
AIAA Journal, Vol. 12, (2), 1974, pp. 191–197.
doi: 10.2514/3.49191
36Katz, J. and Plotkin, A., Low-Speed Aerodynamics,
Cambridge University Press, second edition, 2001.
37Leishman, J. G., Principles of Helicopter Aerodynam-
ics, Cambridge University Press, 2006.
9
... The coupled panel and vortex particle method used in this work is based on the approach described in [26], which itself is an adaptation of the method proposed in [24] for fixed-wing configurations. This simulation framework employs an aerodynamic methodology that combines panel and vortex particle techniques. ...
... This shifting approach, also known as method of lines [5], has been implemented in many state-space free-wake models, including vortex filament free wake [6,7,31] and vortex particle free wake [24][25][26]. In the current work, the shifting approach is implemented for wake panels as well as wake particles. ...
... Further details on Eqs. (34) and (35) can be found in [24,26]. ...
Conference Paper
Full-text available
This study presents the integration of the Fast Multipole Method (FMM) into a coupled panel and vortex particle method (VPM), formulated in state-variable form, to enhance computational efficiency and scalability for aerodynamic simulations. Panels are utilized to model the surface of the wings or blades and the near wake, while vortex particles are used to represent the far wake dynamics, providing a detailed and comprehensive representation of the flow field. The coupled dynamics are expressed as a system of ordinary differential equations that are self-contained and inherently linearizable, offering a framework for dynamic analysis and control system design. The FMM is subsequently incorporated to efficiently approximate particle-particle interactions, addressing computational challenges associated with large-scale simulations. The enhanced solver, implemented in MATLAB ® , is applied to simulate the aerodynamics of a rotary wing in hover, demonstrating its ability to improve both performance and scalability. By integrating the FMM, the computational complexity of particle-particle interactions is reduced from O (2) to O (), while maintaining an acceptable level of accuracy, enabling the simulation of systems with large numbers of particles. Selection of key FMM parameters such as the truncation order () and the number of levels (), is investigated to balancing accuracy, computational efficiency, and memory usage. This integration establishes a foundation for future advancements in aerodynamic solvers, enhancing their applicability to large-scale rotorcraft simulations.
... As such, the objective of this article is to extend the analytical linearization method proposed in Refs. 54 and 55 to a rotor flight simulation with a coupled panel and VPM in state-space form (Ref. 56). Upon the validation of 1 https://public.gitlab.polimi.it/DAER/dust the linearized dynamics against the nonlinear dynamics, computational speed-up of a linearization process using analytical linearization will be assessed relative to conventional perturbation schemes (Ref. ...
Article
This article describes the implementation and analytical linearization of a dynamic rotor simulation with a coupled panel and vortex particle method in state-variable form. Panels are used to model the wing/blade surface as well as the near wake, whereas vortex particles are used to model the far wake. The coupled panel and vortex particle dynamics are formulated as a nonlinear time-periodic system of ODEs in the first-order form to be self-contained and inherently linearizable. Linearization of this coupled panel and vortex particle method is demonstrated via finite differencing and a novel analytical linearization technique to yield a linear time-periodic (LTP) representation. Harmonic decomposition is used to approximate the LTP dynamics with a linear time-invariant system so as to be suitable for time-invariant system analyses. The code is implemented in MATLAB® for a generic utility helicopter rotor blade and validated against an open-source vortex particle method. The linearized models are verified against the nonlinear dynamics both in time and frequency domains. Linearized models accurately represent the wake dynamics of the equilibrium condition for moderate amplitude and frequency forcing inputs. Analytical linearization is shown to abate the cost of linearization over perturbation methods by O(n2), where n is the total number of states of the system. Linearized models of the coupled panel and vortex particle dynamics have applications in the flight dynamics of rotary-wing vehicles, where these dynamics can be used to augment the rigid-body dynamics.
Conference Paper
Full-text available
This paper describes the implementation and linearization of a coupled panel and vortex particle method in a state-variable form. More specifically, the coupled panel and vortex particle dynamics are formulated as a system of ordinary differential equations in the first-order form to be self-contained and inherently linearizable. Linearization of this coupled panel and vortex particle method is demonstrated via finite differencing and a novel analytical linearization technique to yield a linear time-invariant (LTI) representation. The code is implemented in MATLAB and validated against an open-source aerodynamic solver for a fixed-wing in both stationary and unsteady conditions. The linearized models are also verified against the nonlinear dynamics. Linearized models accurately represent the wake dynamics of the equilibrium condition for moderate amplitude and frequency forcing inputs. Analytical linearization is shown to decrease the cost of linearization. Linearized models of the coupled panel and vortex particle dynamics have precise applications in the flight dynamics of both fixed- and rotary-wing vehicles, where these dynamics can augment the rigid-body dynamics of these vehicles. The coupled rigid-body and wake dynamics can be leveraged to assess the stability, response characteristics, and handling qualities of vehicles experiencing aerodynamic interactions between rotors, wings, and/or obstacles. Moreover, unlike time-marching approaches, state-space representations of the wake dynamics are suitable for determinations of unstable equilibria via trim solution methods. This is particularly important for rotary-wing aircraft, given their unstable nature across most flight envelopes.
Conference Paper
Full-text available
This paper describes the implementation and linearization of a free-vortex wake model in state-variable form and its use in the prediction of complex aerodynamic interactions during shipboard launch and recovery operations. Following a detailed mathematical description, the wake model is implemented for a UH-60 rotor and tested in different flight conditions and for simple control inputs. Interference effects due to the sea surface, ship deck, and ship superstructures are modeled using the method of images. A periodic solution to the wake model is found by time marching the coupled rotor and vortex wake dynamics. Next, linearized harmonic decomposition models are obtained and validated against nonlinear simulations. Order reduction methods are explored to guide the development of linearized wake models with increased runtime performance compared to the nonlinear and linearized harmonic decomposition wake models while guaranteeing satisfactory prediction of the periodic response of the wake.
Conference Paper
Full-text available
This paper describes the implementation and linearization of a free-vortex wake model in state-variable form as applied to a helicopter rotor. Following a detailed mathematical description, the wake model is implemented for a UH-60 rotor and tested in forward flight and for simple control inputs. A periodic solution to the wake model is found by time marching the coupled rotor and vortex wake dynamics. Next, linearized harmonic decomposition models are obtained and validated against nonlinear simulations. Order reduction methods are explored to guide the development of linearized wake models that provide increased runtime performance compared to the nonlinear and linearized harmonic decomposition wake models while guaranteeing satisfactory prediction of the periodic response of the wake.
Article
Full-text available
Electric vertical take-off and landing (eVTOL) aircraft with multiple lifting rotors or prop-rotors have received significant attention in recent years due to their great potential for next-generation urban air mobility (UAM). Numerical models have been developed and validated as predictive tools to analyze rotor aerodynamics and wake dynamics. Among various numerical approaches, the vortex method is one of the most suitable because it can provide accurate solutions with an affordable computational cost and can represent vorticity fields downstream without numerical dissipation error. This paper presents a brief review of the progress of vortex methods, along with their principles, advantages, and shortcomings. Applications of the vortex methods for modeling the rotor aerodynamics and wake dynamics are also described. However, the vortex methods suffer from the problem that it cannot deal with the nonlinear aerodynamic characteristics associated with the viscous effects and the flow behaviors in the post-stall regime. To overcome the intrinsic drawbacks of the vortex methods, recent progress in a numerical method proposed by the authors is introduced, and model validation against experimental data is discussed in detail. The validation works show that nonlinear vortex lattice method (NVLM) coupled with vortex particle method (VPM) can predict the unsteady aerodynamic forces and complex evolution of the rotor wake.
Article
Full-text available
A mid-fidelity aerodynamic solver based on the vortex particle method for wake modeling, DUST, is coupled through the partitioned multi-physics coupling library preCICE to a multibody dynamics code, MBDyn, to improve the accuracy of aeroelastic numerical analysis performed on rotary-wing vehicles. In this paper, the coupled tool is firstly validated by solving simple fixed-wing and rotary-wing problems from the open literature. The transient roll maneuver of a complete tiltrotor aircraft is then simulated, to show the capability of the coupled solver to analyze the aeroelasticity of complex rotorcraft configurations. Simulation results show the importance of the accurate representation of rotary wing aerodynamics provided by the vortex particle method for loads evaluation, aeroelastic stability assessment, and analysis of transient maneuvers of aircraft configurations characterized by complex interactional aerodynamics. The limited computational effort required by the mid-fidelity aerodynamic approach represents an effective trade-off in obtaining fast and accurate solutions that can be used for the preliminary design of novel rotary-wing vehicle configurations.
Article
Full-text available
The Pazy wing aeroelastic benchmark is a highly flexible wind tunnel model investigated in the Large Deflection Working Group as part of the Third Aeroelastic Prediction Workshop. Due to the design of the model, very large elastic deformations in the order of 50% span are generated at highest dynamic pressures and angles of attack in the wind tunnel. This paper presents static coupling simulations and stability analyses for selected onflow velocities and angles of attack. Therefore, an aeroelastic solver developed at the German Aerospace Center (DLR) is used for static coupling simulations, which couples a vortex lattice method with the commercial finite element solver MSC Nastran. For the stability analysis, a linearised aerodynamic model is derived analytically from the unsteady vortex lattice method and integrated with a modal structural model into a monolithic aeroelastic discrete-time state-space model. The aeroelastic stability is then determined by calculating the eigenvalues of the system’s dynamics matrix. It is shown that the stability of the wing in terms of flutter changes significantly with increasing deflection and is heavily influenced by the change in modal properties, i.e., structural eigenvalues and eigenvectors.
Conference Paper
Full-text available
A nonlinear aeroelastic numerical tool was used in the present work for the evaluation of loads and vibratory levels of a tiltrotor aircraft during critical transient manoeuvres. The numerical tool applicable to fixed and rotary-wing aircraft was obtained by joining the multibody solver MBDyn and the mid-fidelity aerodynamic tool DUST, through the partitioned multi-physics coupling library preCICE. The aim of this work was to assess the ability of the nonlinear approach implemented in the coupled MBDyn-DUST tool for the simulation of tiltrotor aerodynamics and dynamics during a roll manoeuvre to be used for the preliminary design of novel tiltrotor configurations. This activity was performed in the framework of the EU funded CleanSky 2 FORMOSA project, aimed to the design of a novel wing movable surface system for the NextGen Civil Tiltrotor aircraft.
Conference Paper
Accurate modeling of rotorcraft aerodynamics and induced flow fields is important for high fidelity flight dynamics simulation and pilot training applications. A real-time, free-wake rotor induced velocity software module has been developed and integrated with a Navy helicopter flight dynamics simulation for testing in multiple pilot evaluations. The model provides a physically-based approach for simulation of rotorcraft aerodynamic phenomena identified by strong vortex wake interactional effects. Such phenomena include wake interactions between the main rotor, tail rotor, fuselage and empennage; vertical descent through vortex ring state; and rotor wake/ship air wake interactions. This paper provides an overview of the wake model and flight dynamics simulation integration. Comparison of the coupled free wake aerodynamics and flight dynamics model with flight test data for an MH-60S helicopter was performed, focusing on vertical descent and shipboard operations. A summary of findings from pilot evaluations within the NAVAIR Manned Flight Simulator facility is also given.
Article
This article describes the development, implementation, and validation of a generic tilt-rotor simulation model with coupled flight dynamics, state-variable aeromechanics, and aeroacoustics. A major novelty of this work lies in the integration of the flight dynamics with a state-space free-vortex wake code that adopts a near-wake vortex-lattice model. This way, the flight dynamics are augmented by the vortex wake dynamics so that the coupled flight and wake dynamics are self-contained and inherently linearizable. The model is implemented for a Bell XV-15 tiltrotor and validated against U.S. Army/NASA XV-15 flight-test data and other data in the literature. Flight control design is performed to provide desired stability, performance, and handling-quality properties and to allow for a fully autonomous transition between hover in helicopter mode and high-speed flight in aircraft mode. The simulation model has clear applications in the development and testing of advanced flight control laws, aeromechanics analysis, and the prediction of aerodynamically generated noise in generalized maneuvering flight.
Article
This article describes the implementation and linearization of free-vortex wake models in state-variable form as applied to rotary- and flapping-wing vehicles. More specifically, the wake models are implemented and tested for a UH-60 rotor in forward flight and for a hovering insect representative of a hawk moth. A periodic solution to each wake model is found by time marching the coupled rotor/wing and vortex wake dynamics. Next, linearized harmonic decomposition models are obtained and validated against nonlinear simulations. Order reduction methods are explored to guide the development of linearized wake models that provide increased runtime performance compared to the nonlinear and linearized harmonic decomposition wake models while guaranteeing satisfactory prediction of the periodic response of the wake. This constitutes a first attempt to extend free-vortex wake methods in state-variable form, originally developed for rotary-wing applications, to flapping-wing flight.