Abstract

This work proposes a control strategy to solve the path tracking problem of a suspended load carried by a tilt-rotor unmanned aerial vehicle (UAV). Initially, the equations of motion for the multibody mechanical system are derived from the load’s perspective by means of the Euler-Lagrange formulation, in which the load’s position and orientation are chosen as degrees of freedom. An unscented Kalman filter (UKF) is designed for nonlinear state estimation of all the system states, assuming that available information is provided by noisy sensors with different sampling rates that do not directly measure the load’s attitude. Furthermore, a model predictive control (MPC) strategy is proposed for path tracking of the suspended load with stabilization of the tilt-rotor UAV when parametric uncertainties and external disturbances affect the load, the rope’s length and total system mass vary during taking-off and landing, and the desired yaw angle changes throughout the trajectory. Finally, numerical experiments are presented to corroborate the good performance of the proposed strategy.

1. Introduction

Firstly used mainly for military purposes, recent advances in technology allowed large-scale production of unmanned aerial vehicles (UAVs) and consequently their civilian usage. Nowadays, UAVs receive great interest from engineers and researchers and have a wide range of applications, such as precision agriculture, cargo transportation, cinematographic filming, search-and-rescue missions, surveillance, fire inspection, and archeology. The most commonly found configurations of UAVs are the fixed-wing, helicopter, and quadrotor ones. Due to the vertical take-off and landing (VTOL) and hovering capabilities of helicopter and quadrotor UAVs, they are used in tasks that require high maneuverability in slow velocities. Thereby, fixed-wing UAVs are used in tasks that require improved forward flight, mostly in open environments.

In the last decades, some hybrid aircrafts have drawn substantial attention due to their ability to perform VTOL, hover, and improved forward flights. The tilt-rotor configuration is among the most popular ones, being provided with fixed wings and rotary wings, and is capable of switching between helicopter and airplane flight modes by tilting its thrusters. Inspired by the capabilities of those aircrafts, recent researches are looking into the design of small-scale tilt-rotor UAVs [13]. Their hybrid characteristics offer advantages over fixed-wing and quadrotor UAVs, which also come with design and control challenges since they are complex underactuated mechanical systems with highly coupled dynamics.

Moreover, an important application of unmanned aerial vehicles is the load transportation in risky and inaccessible zones, allowing dealing with rapid deployment of supplies in search-and-rescue missions [4], vertical replenishment of seaborne vessels [5], and safe landmine detection [6]. However, this kind of task is a challenging subject in terms of modeling and control. Since the payload is often connected to the UAV through a rope, the dynamic behavior of the system varies due to the load’s swing, which can destabilize the whole system if it is not well attenuated. Moreover, the suspended load by a rope adds unactuated degrees of freedom to the system, increasing its underactuation degree. Apart from the exposed, in order to accomplish the load transportation task, the knowledge on the load position is usually required. The problem of estimating the load position then arises, being mostly addressed through visual systems and state estimators [7, 8].

Therefore, due to its hybrid capabilities, a tilt-rotor UAV becomes a promising platform for aerial load transportation, providing improved forward speed when compared with rotary-wing UAVs, which is a desired feature for missions requiring rapid deployment. Furthermore, missions that demand precise positioning of the load cannot be addressed by fixed-wing UAVs, since they are not able to perform hover flights. Thereby, the tilt-rotor UAV can be used in both scenarios.

In the literature, control objectives for aerial load transportation include path tracking of the aircraft with reduced load’s swing [914], obstacle avoidance [15, 16], transportation by multiple aircrafts [17, 18], and path tracking of the suspended load [1924]. Since large load swing may destabilize the aircraft, many works address the problem of swing-free aerial load transportation. In [9], a control strategy based on a cascade structure is proposed for load transportation using an unmanned helicopter. A delayed feedback controller is introduced in an outer loop to reduce load’s swing, while the inner-loop controller does not take into account the dynamics of the load. Open-loop approaches based on trajectory generation for load transportation using quadrotor UAVs are proposed in [10, 11], in order to obtain reduced load’s swing motion. In [13], a robust nonlinear control strategy is proposed in order to transport a suspended load by a quadrotor UAV along a predefined trajectory while avoiding load’s swing. The controller is designed based on nonlinear control theory and Lyapunov redesign taking into account the whole dynamics of the system. Some works have also used tilt-rotor UAVs for load transportation. In [12], a nonlinear cascade control strategy is proposed for path tracking of a tilt-rotor UAV with load’s swing improvement, which is composed of three levels of feedback linearization controllers. In [14], a model predictive control (MPC) strategy is studied for path tracking of a tilt-rotor UAV while carrying a load.

When precise positioning of the load is of concern, swing-free motion may not be sufficient for the accomplishment of the task; then the problem of path tracking of the suspended load is addressed. For instance, in [19], the authors propose a model-free open-loop approach based on trajectory generation by reinforcement learning for path tracking of the suspended load using a quadrotor UAV. A nonlinear control strategy based on cascade structure and system decoupling is proposed in [20], also for path tracking of a suspended load using a quadrotor UAV. In [22], a nonlinear solution to the suspended load path tracking problem using a quadrotor UAV is presented, in which the authors assume the quadrotor as a system actuated by total thrust and orientation. The control problem is casted into the framework described in [21], which deals with path tracking of underactuated systems driven by directed thrust and angular velocity with a double-integrator structure. By using tilt-rotor UAVs, in [23, 24], the path tracking problem of the suspended load is solved through the design of control and state estimation strategies based on linearized, time-invariant state-space equations, which did not allow yaw angle tracking, neither the occurrence of changes in the load’s mass and rope’s length.

This work intends to solve the problem of suspended load path tracking considering a realistic scenario in which the rope’s length and total system mass are not constant during take-off and landing maneuvers, the desired yaw angle varies during the mission execution, and the sensors embedded in the UAV have different sampling rates and do not measure directly the load’s position and orientation. Due to the tilt-rotor UAV highly nonlinear dynamic behavior, the unscented Kalman filter is chosen as state estimation strategy since it is not based on model linearization. Further, to perform path tracking while dealing with yaw regulation and the rope’s length variation without relying only on controller’s robustness, the MPC strategy is selected because its model-based nature allows dealing with those problems in a simple fashion way. Therefore, the main contributions of this work are as follows: (i) a detailed modeling in which the multibody system’s equations of motion are obtained from the load’s point of view, yielding an input-affine state-space representation with the load’s position and orientation as state variables; (ii) a nonlinear estimation strategy dealing with multirate noisy sensors that do not provide directly information about the load’s pose; and (iii) a control strategy that is able to cope with the path tracking of the suspended load considering yaw angle regulation, to incorporate the rope’s length variation to the control problem formulation, and to keep the UAV stabilized while rejecting external disturbances and parametric uncertainties.

The remainder of this paper is organized as follows: Section 2 develops the equations of motion of the tilt-rotor UAV with suspended load from the load’s perspective, yielding a state-space representation with the load’s position and orientation represented by state variables; Section 3 presents the unscented Kalman Filter design based on the model and measurement equations given by available sensors; Section 4 describes the model predictive control strategy designed to achieve path tracking of the suspended load based on the linearized time-varying model; Section 5 presents the model and design parameters, besides the simulation scenario used to validate the proposed control strategy; in Section 6, the numerical experiments used to demonstrate the good performance of the controller and filter are presented and discussed; finally, Section 7 concludes the work.

2. Tilt-Rotor UAV with Suspended Load Modeling

This section deals with the development of the equations of motion of the tilt-rotor UAV with suspended load, from the load’s perspective. The dynamic equations, assuming a multibody system, are obtained through the Euler-Lagrange formulation, in which the coupling between the aircraft and the load is considered naturally.

2.1. System Description

The computer-aided design (CAD) model of the tilt-rotor UAV with suspended load is shown in Figure 1. The system is regarded as a multibody mechanical system composed of four rigid bodies: (i) the aircraft’s main body, composed of Acrylonitrile Butadiene Styrene (ABS) structure, landing gear, batteries, and electronics; (ii) the right thruster group, composed of the right thruster and its tilting mechanism (a revolute joint); (iii) the left thruster group, composed of the left thruster and its tilting mechanism; and (iv) the suspended load group, comprising the load and the rope. The system is actuated through the aircraft’s thrusters and tilting mechanisms. For modeling purposes, the following assumptions are made:(A1) The rope is rigid and has negligible mass.(A2) The rope is connected to the aircraft’s geometric center.(A3) The main body’s center of mass does not coincide with the aircraft’s geometric center.(A4) The thrusters groups’ centers of mass are located at their respective tilting axes.

Regarding the assumptions stated above, it is important to describe the main reasons of assumption (A3), which are as follows: (i) the center of mass is vertically displaced in order to improve the pitch moment; and (ii) the center of mass is displaced with respect to the -axis of the geometric center, allowing obtaining non-null equilibrium points for the angular positions of the tilting mechanisms and pitch angle. This mechanical feature improves the controllability of the system in hover flight, allowing the projection of the thrusts generated by propellers on the -axis without the need to tilt the thrusters’ group.

2.2. Kinematics from the Load’s Perspective

The load’s perspective approach consists in formulating the system’s kinematics regarding the suspended load as a free rigid body, with the aircraft as a multibody mechanical system rigidly coupled to it. Six reference frames are defined, as shown in Figure 2: (i) the inertial reference frame, ; (ii) the aircraft’s geometric center frame, ; (iii) the main body center of mass frame, ; (iv) the right thruster group center of mass frame, ; (v) the left thruster group center of mass frame, ; and (vi) the suspended load group center of mass frame, . The load’s position with respect to the inertial frame is denoted by . The displacement vector from to corresponds to the rope and is expressed in by , with as the rope’s length. The displacement vectors from to are model parameters of the tilt-rotor UAV and are denoted by , expressed in , with .

The orientation of the load with respect to is parametrized by Euler angles, , using the convention about local axes. The associated rotation matrix is given by

On the other hand, the orientation of the aircraft’s geometric center frame with respect to , corresponding to the orientation of the UAV with respect to the rope, is parametrized by two angles, , such that

The reference frames and are parallel to each other and attached to the same rigid body; thus the relative orientation is null, that is, (in this work is an identity matrix with dimension , is by zeros matrix, and is by ones matrix). Furthermore, the orientations of the thrusters’ groups with respect to are described bywhere and are the tilting angles of the right and left thrusters, respectively, and is a fixed inclination angle of the thrusters towards the aircraft geometric center, designed to improve the aircraft’s controllability [25]. The angular velocities of the system are given by , , , , and , where, for instance, denotes the angular velocity of with respect to , expressed in , withand .

From the rigid transformations of the system, the forward kinematics of points that belong to each rigid body are given bywhere is the position of a point that belongs to the suspended load body and belongs to the rigid body with attached frame . Taking the time derivatives of (5) and (6) and making use of several properties of skew-symmetric matrices [26] yieldwhere denotes an operator that maps a vector to a skew-symmetric matrix [26].

The generalized coordinates of the system are chosen according to their degrees of freedom. For the equations of motion describing explicitly the time evolution of the load’s position and orientation, these are included in the generalized coordinates, which are chosen as

Note that, due to the chosen perspective for the system kinematics, the position and orientation of the aircraft with respect to are not degrees of freedom of the system. Thus, they are not included in (9), and consequently their time evolution will not be described explicitly by the developed equations of motion.

2.3. Kinetic and Potential Energies

Initially, in order to derive the equations of motion through the Euler-Lagrange formulation, the kinetic and potential energies of each body of the mechanical system must be obtained. For each th rigid body, these energies can be computed through the volume integrals [27]respectively, where corresponds to its density, to its volume, and to its mass, denotes the gravitational acceleration vector expressed in , and is the position vector obtained from the forward kinematics of the origin of .

The quadratic terms and , are obtained using (7) and (8), respectively. The kinetic energy of the load and the th body of the aircraft are obtained through (10). The total kinetic energy of the system is then computed through Writing the result in the quadratic form , and by defining the inertia tensors and , and taking into account the parallel axis theorem [28], yielding and , we have that the inertia matrix is given bywith denoting terms that are deduced by symmetry, and where , , , and . Note that, from the inertia matrix (12), the four body dynamics are completely coupled, allowing to consider this interaction in the control law design and avoid the need of cascade control structures.

The Coriolis and centripetal forces matrix, , can be calculated via Christoffel symbols of the first kind [26]. The element from its th row and th column is computed throughwhere is an element of the inertia matrix and .

The forward kinematics of each body’s center of mass is obtained by making in (5) and in (6). Thereafter, the potential energies of the load and of each body of the aircraft are obtained using (11). The total potential energy of the system is then computed by .

Then, the gravitational force vector is given by

2.4. Generalized Forces

This section obtains the contributions to generalized forces of all nonconservative forces and torques that actuate on the tilt-rotor UAV with suspended load. Let and denote a nonconservative force and a nonconservative torque, respectively, denote the point of application of , and be a reference frame rigidly attached to the body to which is applied. According to [29], the contributions of and to the generalized forces can be computed through the following mappings:where and .

The thrust forces generated by the aircraft’s propellers, denoted by and , and the torques generated by the servomotors composing the tilting mechanisms, denoted by and , correspond to the input forces and torques of the system. Expressed in their respective thrusters’ frames (see Figure 2), they are given by , , , and , where . In the inertial reference frame, these vectors are expressed as , , , and , with .

This work assumes that the thrust forces are applied to the centers of mass of the respective thrusters’ groups, which correspond the origins of and . Making in (6) to obtain and yields

Then, using (16) and (18) yields

The servomotors’ torques are applied to the respective thrusters’ bodies, and opposite torques due to reaction are also applied to the aircraft’s main body. These pairs of torques are mapped to generalized forces through (17). From the addition of angular velocities [26], we have

Comparing (21), (22), and (23) to , , and , respectively, and using (17) lead to

This work also takes into account drag torques generated by the propellers. These are reaction torques applied to the thrusters’ bodies, due to the blades’ acceleration and drag [30]. Assuming steady-state for the angular velocity of the blades, the drag torques are given in the thrusters’ reference frames by , , where and are parameters obtained experimentally, and and are given according to the direction of rotation of the corresponding propeller: if counter-clockwise, ; if clockwise, . In the inertial reference frame, we then have and .

As the drag torques are applied to the thrusters’ bodies, through (17), (22), and (23), we have

Finally, the total mapping of the system inputs to generalized forces is obtained by summing up the contributions of the thrust forces, servomotor torques, and drag torques. Then, from (19)-(20) and (24)–(27),where

Note that, although in this current work no aerodynamic surfaces are considered in the tilt-rotor UAV (see Figure 1), the system modeling developed here is general enough to describe the dynamics of any tilt-rotor carrying a suspended load. The only constraint is that the aircraft needs to be seen as a multibody system with similar frames definitions as those shown in Figure 2. Further, in presence of aerodynamics surfaces (e.g., wings and horizontal and vertical stabilizers), the lift and drag forces generated by them can be added to the model in a straightforward manner, by including these terms in (28), which will allow dealing with both helicopter and airplane flight modes.

In addition, viscous friction is taken into account at the revolute joints of the tilting mechanisms and also at the point of connection between the rope and the tilt-rotor UAV. It is assumed that the friction torques are mapped to generalized forces aswhere with and being constant parameters.

External disturbances applied to the suspended load are also considered, which may represent wind gusts affecting the system. Defining these disturbances in the inertial reference frame as the force vector , and assuming that is applied to the load’s center of mass, it can be mapped to generalized forces through (16), yieldingwhere is obtained by making in (7).

2.5. Equations of Motion

From (12), (14), and (15), the equations of motion of the tilt-rotor UAV with suspended load can be written in the Euler-Lagrange formulation as [27]where is the total generalized forces vector, obtained by summing up the contributions from the input forces and torques (28), viscous friction torques (30), and external disturbances (31). Thus, substituting in (32) yields

Finally, by defining the state vectorand recalling the input vector defined in (28), the dynamic equations (33) can be written in the state-space representationwhich is nonlinear and highly coupled. Since the load’s position and orientation are among the generalized coordinates (9), they are represented by the state variables (34), and, consequently, the load’s behavior is described explicitly by (35). On the other hand, the aircraft’s position and orientation are described only with respect to the load, thus appearing in (35) only implicitly.

3. Nonlinear State Estimation

This section presents a state estimation strategy to cope with the problem of predicting the states related to the load’s pose, using the information of noisy sensors with different sampling rates, in order to gather the information necessary to build the state vector (34). The following sensors are assumed to be available: (i) a Global Positioning System (GPS) equipment to measure the and positions of the UAV; (ii) a barometer to measure the UAV’s altitude; (iii) an Inertial Measurement Unit (IMU) that provides the orientation and angular velocity of the UAV; (iv) a camera that gives the position of the load with respect to the UAV; and (v) embedded sensors at the servomotors to provide the tilting angles and their time derivatives.

The measurement model is highly nonlinear and therefore some well-known estimation techniques based on linearized transformations may have limited performance. Thereby, this paper considers the unscented Kalman filter strategy that estimates the mean and covariance of the likelihood distribution by means of the Unscented Transform (UT) and then uses the Kalman Filter (KF) equations to compute the posterior distribution [31, 32].

3.1. Measurement Equation

The relation between the variables measured by the embedded sensors and the state vector at time instant is given by the measurement equation where is the measured vector, corresponds to a nonlinear mapping to be obtained, and is the measurement noise.

Let be the position of the aircraft with respect to (see Figure 3). Then, through forward kinematics, the following holds:

Additionally, let be the aircraft attitude with respect to parametrized by Euler angles using the local roll-pitch-yaw convention. Therefore,

Recalling that the relation holds and considering , it is possible to state that

Furthermore, the angular velocity provided by the IMU is given bywhere the matrices and were defined in (4).

Let denote the displacement vector from to , expressed in , which is the measurement provided by the camera (see Figure 3). Then,

Finally, (37), (39), (40), and (41) along with the system’s states , , , , and the measurement noise can be grouped into the nonlinear measurement equation

This work assumes synchronized sensors with sampling rates equal to , , and , respectively, for the GPS, camera, and remaining sensors, being the control sampling time. Since not all information is available at time instant , the dimension of the vector , as well as the transformation , will change with time. Thus, from now on, the variables that have different data acquisition rates will be denoted with the subscript .

3.2. Unscented Kalman Filter

In the unscented Kalman filter (UKF), a fixed number of sigma points are chosen deterministically to capture the mean and covariance of the prior distribution. These points are then propagated through a nonlinear transformation to estimate the posterior distribution [32].

Consider the discrete representation of (35) and the measurement equation (42)where is the process noise. Also, let denote estimated variables, denote information at time instant given measurements up to instant , and be the expected value operator. This work assumes that measures of are always available, and the mean and covariance are known. Furthermore, the process and measurement noises are assumed to have zero mean and covariances and , respectively, and the cross-covariance between them is assumed to be null, that is, .

In order to describe the prior statistics using UT, only sigma points are necessary, where is the dimension of the state vector [31]. The sigma points must satisfywhere are weights defined as subject to .

The sigma point matrix is chosen aswhere is the Cholesky square root.

The likelihood distribution statistics can be obtained by propagating the sigma points through the nonlinear measurement equation (42), yieldingsuch that

Algorithm. The UKF algorithm is formed by a forecast and a data assimilation step [32]. The operations presented below must be performed at each measurement step .

(i) Forecast Step(1) Form the sigma points using (46),(2) Propagate the sigma points through the nonlinear transformation (43) (3) Compute the predicted mean and covariance using (45) together with the process noise covariance (4) Form the sigma point matrix with the estimation of (5) Propagate the sigma points through the measurement model (44)(6)  Compute the measurement statistics using (48) together with the measurement noise covariance and the cross-covariance of the states and measurements

(ii) Data Assimilation Step(1)Compute the filter gain and the innovations (2)Compute the corrected mean and covariance conditional on the measurement information

Observe that the UKF algorithm uses at all time instant all available information from the sensors to estimate the posterior distribution. For those time instants in which the measurement vector is full, that is, it has all sensors information, the estimation of will be more accurate and the covariance reduced. On the other hand, when neither GPS nor camera information is available, the data assimilation step will have a less important role on the estimation algorithm, and will be less accurate and bigger.

Finally, the state vector estimated in this section, , will be used by the control strategy presented in the next section to perform the state feedback control.

4. Suspended Load Path Tracking Controller

This section describes the model predictive controller design for performing the suspended load path tracking. The main objectives of the control system are as follows: ensure closed-loop stability, reject constant external disturbances and parametric uncertainties, and satisfy constraints on state deviations and control inputs.

Aiming at an improved path tracking control and recalling the system’s underactuated behavior, the load’s position and its yaw angle are chosen to be regulated, while the other degrees of freedom will be only stabilized.

This paper works with the incremental MPC framework [33], for which the prediction model is obtained using a discrete linear time-varying state-space model that is not affine in the parameters. On one hand, the use of this kind of linear system improves the aircraft’s nonlinear dynamics representation, when comparing to time-invariant linearized models, and, particularly for the proposed application, allows yaw movements regulation and copes with the rope’s length variation during the take-off and landing. On the other hand, because the time-varying linearized model used in this work is non-affine in the time-varying parameters, it is not possible to obtain, for instance, a polytopic representation for the linearized model and, then, use some well-know techniques to improve the MPC robustness.

4.1. Linearized Error Dynamics

Seeking to obtain the discrete linear time-varying state-space model to construct the prediction model, the equations of motion (35) must be linearized around a time-varying trajectory. Additionally, due to limited computational resources, this process needs to be done with most of the physical parameters numerically evaluated. However, it is possible to let some physical parameters be variables in a way that they will appear in the linearized Jacobians after finishing the linearization process.

Let and denote trajectory values and, for linearization purposes, consider (see (31)). This work assumes that the desired trajectory is feasible, that is,

Then, linearizing the state-space equations (35) around these trajectories, through first-order expansion in Taylor series, yieldswhere , , and

In this work, the trajectory values for and are given bywhere denotes the left pseudoinverse of and , , and are provided reference signals with , in which is the state’s equilibrium value. Notice that , since it is computed using a left pseudoinverse, will be an exact solution to the dynamic equations (33) only if the desired trajectory is feasible.

Therefore, by linearizing the system using (59) with the trajectories defined in (60) and (61) added to the rope’s length as a time-varying parameter, the linearized Jacobians are and , where is the vector of time-varying parameters.

To improve the trajectory tracking of the regulated variables and provide constant disturbance and parametric uncertainties rejection, the state vector is augmented with integral actions [34], yieldingwhose dynamics are given by

To obtain a discrete prediction model using the incremental form and, thereafter, improve performance with input integrators added to the closed-loop system [33], it will be necessary to map the model (63) from the continuous-time to the discrete-time domain, which yields being the matrices and obtained after discretizing the model using a zero-order hold with sampling time (in this work, variables in continuous-time and discrete-time domain are differentiated by the time variable and the sampling variable ).

Finally, choosing the control increment to be the control input, the extended discrete linearized system can be rewritten in the incremental form as

4.2. Prediction Model

The state-space model (65) gives the one-step ahead prediction and can be used recursively to obtain the prediction model considering a prediction horizon and control horizon . Thus, considering the case where and assuming , the -step ahead prediction yields

Thereby, defining and , it is possible to write the prediction model aswhere the matrices and are given by

4.3. Optimization Problem

Consider the standard quadratic cost functionwhere for , being the reference trajectory at the instant . Moreover, and are, respectively, weighting matrices of states error and control effort.

The cost function (69) can be written in the matrix form by means of the prediction model (67) aswhere and are block diagonal matrices, and .

Finally, (70) can be rewritten in the canonical quadratic form aswhere , , and .

Adding constraints on the objective variable , the most general optimization problem must be solved:

The constraints considered above can be used to limit the control signal amplitude avoiding saturation in the actuators and to limit the maximum state error. In both cases, the constraints must be mapped to the amplitude of the control increment as in [14]where and are, respectively, the maximum and minimum values allowed for the variable, and the matrices and are defined as

4.4. Applied Control Signal

Using the relations and , the control signal at the time instant can be written aswhere results from the optimization problem (72) and is the feedforward term (61).

5. Simulation Scenario

This section describes the simulation scenario used to evaluate the performance of the proposed control and state estimation strategy. The implemented control structure is presented in Figure 4.

5.1. Model and Design Parameters

The model parameters of the tilt-rotor UAV with suspended load are shown in Table 1. Mass, inertia, and displacement parameters of the aircraft were obtained from CAD model, designed in Solidworks® software. The parameters related to the suspended load, as well as and , are the same considered in [12]. The gravitational acceleration is assumed constant, and and are given according to the following: the right propeller of the aircraft rotates counter-clockwise and the left one rotates clockwise. From those data, and assuming , the following equilibrium points was obtained to construct the vector used in (60) and (61)

For simplicity, the sensors’ noise was assumed to have a Gaussian probability distribution, and the measurement error is defined as three times the standard deviation. However, such assumption is not required by the UKF to estimate the system states (34). Additionally, this work considers known disturbances affecting the aircraft, which may represent the presence of wind gusts, and all sensors are synchronized. Table 2 shows the sensors’ measurement error and their sampling time. The relations between the measured variables and those presented in (42) are as follows: , , , , , , , and .

For time instants multiples of 120 ms, the measurement vector is full, being = , while for those multiples of 24 ms the vector does not have GPS information, and then Finally, for time instants multiples of 12 ms, the measurement vector does not have neither GPS nor camera information; thus .

The initial state vector is considered to be precisely known, that is, , and the covariance matrices used in the filter algorithm are given by and being a diagonal matrix composed by the sensor standard deviation, that is, the measurement error divided by three, regarding the sensors information available at the time instant .

For discretization of the linearized Jacobians, and , in (63), it is assumed that = 12 ms. The prediction and control horizons, chosen considering the trade-off between good performance and small computational cost, are and . Furthermore, the saturation level of the tilt-rotor UAV actuators and the maximum state error allowed, used in (73), arewhere the error limitations were chosen regarding measurement error and disturbances effect on the system. The actuators’ bounds are due to physical constraints.

The Bryson’s rule [35] was used as starting point to synthesize the MPC controller’s weighting matrices, which are given by

5.2. Desired Trajectory

To explore the controller capabilities, the proposed trajectory to be tracked by the suspended load is composed of several interconnected paths, which are described by polynomial and/or sinusoidal functions. It starts with vertical take-off, followed by straight line tracking with changes in direction, and ends with vertical landing. Along with the desired position, yaw’s movements are specified in order to always have the aircraft performing the trajectory head-on (see Figure 5). Moreover, to evaluate the disturbance compensation of the proposed strategy, external forces are applied to the suspended load. Figure 6 shows the disturbance profile for the desired trajectory, which may represent sustained wind gusts affecting the load. The magnitude of the disturbances may seem low at a first glance; however the mass of the load is very small (see Table 1).

6. Numerical Results and Discussion

This section presents the numerical results obtained with the proposed control and state estimation strategy when subjected to the simulation scenario described before. The simulations have been carried out using the MATLAB/Simulink® environment. A detailed analysis about the performance of the control system when solving the path tracking problem of a suspended load carried by a tilt-rotor UAV is provided.

The trajectories performed by the tilt-rotor UAV and the suspended load are shown in Figures 5 and 7. The tracking error is illustrated in Figure 8. The path tracking was performed successfully, from take-off to landing, and throughout the different paths that compose the trajectory, including yaw angle regulation. These results demonstrate the joint performance of the designed MPC controller and the UKF estimator, using the adopted control structure.

During the vertical take-off, the aircraft starts to fly while the load remains in the ground. Only when the distance between the aircraft and the floor is greater than the rope’s length, the tilt-rotor UAV starts to carry the load. Vice versa, in the landing maneuver, the aircraft flies free of load once it has touched the ground. Figure 9 highlights this behavior in the first 5 and last 10 seconds of simulation. At the beginning of the simulation, the rope’s length increases until it reaches its maximum value; then, the aircraft starts to carry the suspended load and the total mass increases. Likewise, during the landing, last 10 seconds, the load touches the ground and the rope’s length decreases until the aircraft landing finishes. Also, Figure 9 shows the total mass reduction when the load touches the ground. The controller was capable of dealing with this problem due to the incorporation of in the time-varying parameters vector and the model-based nature of predictive controllers. The load’s mass was not incorporated in for two main reasons: (i) in order to consider the mass variation as a time-varying parameter in the same way that was considered, the load’s mass needs to be estimated or informed to the controller before the flight starts; (ii) it is reasonable to assume that the relation between the UAV’s mass and the load’s mass is small enough to be rejected by the controller as parametric uncertainty when the actual load’s mass is different from the one considered in Table 1.

Figure 10 shows the time evolution of the remaining degrees of freedom, which are kept stable as the trajectory is performed. Since the aircraft’s behavior is described implicitly by those variables, one can conclude that the UAV was stabilized along the trajectory. It is important to note that the designed MPC controller was able to stabilize the aircraft without the need of a cascade control structure, since the proposed modeling considered all the dynamic couplings between the rigid bodies.

Figure 11 shows the actuator signals generated by the MPC controller. Despite being noisy, the control signals did not reach the actuators’ limits. In an experimental setup, the inherent inertial properties of the aircraft actuators, which are commonly brushless DC motors and servomotors, would attenuate such noise naturally.

Figures 12 and 13 present, respectively, the estimation error for the generalized coordinates and for their time derivatives, along with the confidence limits (i.e., three times the standard deviation). In all cases, the estimation error is close to zero and is kept inside the confidence limits, demonstrating the performance of the unscented Kalman filter. Recalling the nonlinearities of the system (35) and the measurement equation (42), the UKF was then able to estimate the means and covariances of the posterior distributions in a consistent manner, despite the sensors’ different sampling rates.

Some patterns arose in the confidence limits due to the greater sampling rates of the GPS and the camera, whose measurements are available only every 120 ms and 24 ms for performing the data assimilation step, respectively. The other sensors’ data are available every 12 ms, which is also the controller sampling time. These patterns are expected since the estimation is more accurate and has smaller confidence limits every time that more data are available to be used in the data assimilation step. This result illustrates that, despite having nonlinear dynamics and sensors with different sampling rates, the unscented Kalman filter is able to recover the state vector from the information provided only by the UAV’s embedded sensors.

Based on the presented results, the proposed modeling, control and estimation strategies were demonstrated to be appropriate to solve the problem of path tracking control of the suspended load. A next research step consists in validating the proposed approach considering an experimental setup.

7. Conclusions

This paper proposed a detailed model and the design of a control and state estimation strategy to solve the path tracking control problem of a suspended load using a tilt-rotor UAV when it is operating in the helicopter flight-mode.

A modeling approach was presented, in which the kinematics of the system were formulated from the load’s perspective, being the load’s position and orientation chosen as degrees of freedom of the multibody mechanical system. The UAV’s position and orientation were described only with respect to the load. By using the Euler-Lagrange formulation, the equations of motion were obtained, while taking into account the dynamic coupling between the aircraft and the load, the existence of viscous friction at the suspension point and at the tilting mechanisms, and also external forces affecting the load. The nonlinear state-space representation of the system was obtained, with the load’s position and orientation as state variables.

Assuming that the UAV’s embedded sensors provide noisy information with different sampling rates, an unscented Kalman filter was proposed for nonlinear state estimation of all the state variables, based on the model attained and measurement equations developed from kinematic concepts. Moreover, based on linearized time-varying state-space equations augmented with integral actions, a model predictive control strategy was designed for path tracking of the suspended load with stabilization of the tilt-rotor UAV. The proposed model predictive controller allows yaw angle tracking, take-off and landing maneuvers, situations where the rope’s length and the total system mass are not constant. The feedback control loop was performed using the estimation provided by the UKF.

The proposed strategy in this work was evaluated through numerical experiments in MATLAB/Simulink environment. The trajectory performed by the load comprised vertical take-off, straight line following with direction changing, and vertical landing, with disturbances being applied to the load and also under total mass and rod’s length variation. The unscented Kalman filter was able to estimate the entire state vector from the information provided by the sensors, while the MPC controller was able to perform the control task using the provided estimation, without saturating the aircraft actuators. The presented results demonstrated the good performance of the designed MPC controller and the unscented Kalman filter for path tracking of the load using a tilt-rotor UAV, in this challenging, not yet addressed scenario.

One of the biggest appeals of tilt-rotor UAVs is their ability to take-off and land vertically, perform hover flights, and achieve improved forward velocities when in airplane-like mode. This work dealt only with helicopter-like flights, in which the thrusters’ groups motions are limited to small tilting angles. However, as stated before, the inclusion of aerodynamic surfaces into the proposed model is straightforward. Further, the proposed estimation and control strategy is general enough to cope with both flight modes, including the transition between them.

7.1. Future Works and Limitations

The main limitation of the proposed approach is the computational cost associated with the estimation and control algorithms. Since one of the goals of this work was to perform yaw angle tracking, the use of a nonlinear estimator and a controller based on a linearized time-varying model became necessary. As discussed in Section 4, this model is not affine in the parameters; that is, it is not possible to obtain a polytopic representation for the linearized model. This fact prevents the use of techniques that could allow the prediction horizon reduction, which is directed related to the controller computational cost. Regarding the estimator, the requirement to perform yaw motion on flight, which makes the linearized model unsuitable far from the chosen operational points, together with the inability to derive Jacobian and Hessian matrices from the model derived in Section 2 using numerical computation software, made the choice of a filter with higher computational cost necessary.

Future works will propose ways to reduce the computational cost of the proposed controller allowing implementing it in embedded systems. Approaches that use piecewise linearized models or models identified in subspace models could be a possible way to address this issue. Also, studying computational efficient ways to implement UKF algorithms will be a future work. Once the problems related to computational cost have been solved and the prototype is finished, future works will present the aircraft aerodynamic design, that is currently being developed, together with simulation and experimental results for load transportation tasks.

Conflicts of Interest

The authors declare that there are no conflicts of interest regarding the publication of this paper.

Acknowledgments

This work was supported by the Brazilian agencies CNPq, CAPES, FAPEMIG, and Pró-Reitoria de Pesquisa of UFMG. A. Ferramosca would like to acknowledge the Argentinean Agency of Scientific and Technological Development (ANPCyT) under the FONCyT Grant PICT-2016-0283.