Next Article in Journal
An Incremental Inverse Reinforcement Learning Approach for Motion Planning with Separated Path and Velocity Preferences
Next Article in Special Issue
Tethered Unmanned Aerial Vehicles—A Systematic Review
Previous Article in Journal
Tunable Adhesion of Shape Memory Polymer Dry Adhesive Soft Robotic Gripper via Stiffness Control
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

UAV Power Line Tracking Control Based on a Type-2 Fuzzy-PID Approach

by
Guilherme A. N. Pussente
1,
Eduardo P. de Aguiar
2,
Andre L. M. Marcato
1 and
Milena F. Pinto
3,*
1
Department of Electrical Engineering, Federal University of Juiz de Fora, Juiz de Fora 36036-900, Brazil
2
Department of Industrial and Mechanical Engineering, Federal University of Juiz de Fora, Juiz de Fora 36036-900, Brazil
3
Federal Center of Technological Education of Rio de Janeiro (CEFET/RJ), Rio de Janeiro 20271-110, Brazil
*
Author to whom correspondence should be addressed.
Robotics 2023, 12(2), 60; https://doi.org/10.3390/robotics12020060
Submission received: 14 March 2023 / Revised: 11 April 2023 / Accepted: 18 April 2023 / Published: 20 April 2023
(This article belongs to the Special Issue UAV Systems and Swarm Robotics)

Abstract

:
A challenge for inspecting transmission power lines with Unmanned Aerial Vehicles (UAVs) is to precisely determine their position and orientation, considering that the geo-location of these elements via GPS often needs to be more consistent. Therefore, a viable alternative is to use visual information from cameras attached to the central part of the UAV, enabling a control technique that allows the lines to be positioned at the center of the image. Therefore, this work proposes a PID (proportional–integral–derivative) controller tuned through interval type-2 fuzzy logic (IT2_PID) for the transmission line follower problem. The PID gains are selected online as the position and orientation errors and their respective derivatives change. The methodology was built in Python with the Robot Operating System (ROS) interface. The key point of the proposed methodology is its easy reproducibility, since the designed control loop does not require the mathematical model of the UAV. The tests were performed using the Gazebo simulator. The outcomes demonstrated that the proposed type-2 fuzzy variant displayed lower error values for both stabilization tests (keeping the UAV centered and oriented with the lines) and the following step in which the trajectory is time-variant, compared to the analogous T1_PID control and a classical PID controller tuned by the Zigler–Nichols method.

1. Introduction

Currently, there is a growing demand for studies on the viability of using Unmanned Aerial Vehicles (UAVs) in tasks that, until recently, were performed partially or exclusively by human workers [1,2]. Characteristics such as the versatility of flight modes, reduced dimensions, and the possibility of integration between sensors and actuators allow these vehicles to help in several areas, such as agriculture [3,4], industry [5,6], military [7,8], in the transportation of goods or people [9,10], in infrastructure inspection [11,12], forest monitoring [13,14], and rescue missions [15,16].
Information gathered by the sensors attached to the UAVs can contribute to decision making remotely, ensuring more secure operations [17]. The main reason for introducing robotic systems in the mentioned tasks is to prevent operators from being exposed to hazardous environments, such as reservoirs containing toxic materials or mines with a potential risk of collapse. Another factor to consider is the repetitive and exhausting nature of specific tasks. The capability of these drones to cover large areas in a relatively short time allows them to help, for example, in the counting and monitoring of cattle [18,19].
Power line inspection is crucial for maintaining the quality of the power distribution. Potential failures or incidents in transmission networks can result in financial losses due to distribution interruption and accidents that can affect cities with the risk of environmental damage. Conventional approaches require workers in helicopters or direct contact with high-voltage components, are resource-demanding, often inefficient, and dangerous [20,21]. In Brazil, accidents in the electrical industry are, on average, 4.8 times greater than other sectors of the economy [22]. Therefore, there is a demand for robotic systems that can support the identification of anomalies in distribution systems. UAVs are ideal for such activity due to the ease of coupling cameras and other sensors in addition to the capability of low-speed flights at a safe distance from the cables, allowing the acquisition of data and images that are significant for the maintenance of the system.
In this field of research, [23] proposed a methodology for transmission line inspection in which a UAV takes off and proceeds to the mission starting point, determined by GPS readings. Then, the transmission cables are detected using a laser scanner, and the inspection is complete. Other studies have focused on establishing local positional control using image-based visual serving (IBVS) approaches. In these strategies, the features extracted directly from the images determine the relative position of the drone, and then a control technique is implemented. Therefore, Global Navigation Satellite System (GNSS) data are one option for locating power lines, but are often inaccurate [24]. Ref. [25] proposed a transmission line localization architecture that uses a histogram method of oriented segments to determine the position of lines. Next, proportional control is applied to align the drone with the lines. Ref. [26] proposed an output feedback control for line tracking relative to a virtual image plane that compensates for the distortion created by the tilt of the drone body frame.
The traditional PID controller is still employed in many applications due to its simplicity of comprehension and ease of implementation, as it is not model-dependent. However, its applicability is limited to controlling nonlinear systems subject to measurement uncertainties, such as UAVs. Another problem faced by this approach is the necessity of controller gain tuning. Some authors employ intelligent techniques for PID controller gain tuning, such as Particle Swarm Optimization (PSO) [27,28] and Genetic Algorithm [29,30]. The sliding mode control is an adaptive tuning tool in [31,32].
The fuzzy logic theory has gained prominence in the controller tuning problem. Its advantage over the abovementioned techniques is the dynamic tuning of gains through fuzzy rules that are easy to interpret, to the detriment of complex equations that are usually difficult to comprehend. Thus, the controller gains adapt according to the behavior of the plant through the fuzzy membership functions. Hybrid approaches of type-1 fuzzy logic PID controllers (T1_PID) were employed for UAV control in [33,34,35,36].
Type-1 fuzzy models have difficulty dealing with uncertainties since they work with fixed membership functions. Therefore, the use of this technique in complex systems such as UAVs, which are subject to inaccurate measurements inherent to IBVS control systems, is worthy of attention. As a result, recent studies have introduced type-2 fuzzy systems, which model the uncertainties on antecedents and consequents through type-2 fuzzy sets via a Footprint of Uncertainty (FOU), the region enclosed by the union of all primary membership functions. Type-2 fuzzy logic as a PID tuning method was explored in [37,38]. In [39], a comparison of hybrid fuzzy-PID systems was conducted, demonstrating the superiority of type-2 fuzzy in controlling UAVs in the presence of disturbances and uncertainties in the model.
This paper presents an interval type-2 fuzzy-PID (IT2_PID) controller for the transmission line follower problem through UAVs. The proposed methodology was compared with a conventional PID controller and a type-1 fuzzy-PID (T1_PID) controller. The fuzzy logic algorithm adaptively determines the proportional, derivative, and integrative gains as the UAV performs tracking. The trajectory is determined through images from a camera attached to the robot. For this purpose, the frame goes through a preprocessing step, and the lines are detected through the Probabilistic Hough Transform [40]. The set of transmission lines should serve as a parameter for defining the trajectory to be followed. Thus, the strategy adopted is to compress all the pixels of the lines obtained into a single curve that will guide the drone. The RANSAC technique performs this process; this is a robust algorithm for curve parameter estimation from a subset of inliers from the complete data set. The advantage of this technique is its robustness against outliers, which are common in geometric shape detection in images. Thus, based on the curve obtained by RANSAC, the error variables are estimated and inserted into the control loop to keep the lines in the center of the image. The entire proposed approach was implemented using the ROS platform and validated through simulations performed by Gazebo. The main contributions presented in this paper can be summarized as follows:
  • The proposal of a power transmission line alignment and tracking methodology based on visual information integrated with a hybrid type-2 fuzzy-PID approach suitable for any multirotor vehicle.
  • The adaptive ability of the technique is demonstrated by the comparisons performed between a type-2 fuzzy-PID controller and its type-1 variant, a PID control tuned by Ziggler–Nichols, and a PID control with the average gains of fuzzy approaches.
  • The methodology is developed in Python with ROS integration making it easy to reproduce in different scenarios.
  • The proposed methodology is based on type-2 fuzzy logic, which has the advantage of dealing well with uncertainty, which is inherent to controls based on visual information.
The rest of this paper is organized as follows: Section 2 describes the power lines tracking problem performed by the aerial robot and its mathematical foundations. Section 3 presents the main outcomes and discusses the proposed methodology results. Finally, Section 4 provides a brief conclusion and ideas for future work.

2. Problem Formulation

The methodology proposed in this paper is in the Image-Based Visual Servo (IBVS) control category, which relies on visual information extracted in the image plane, providing the control actions to be applied. In other words, the detected straight lines in a frame serve as a parameter for the determination of the drone’s position in relation to the power lines and, thus, the strategy adopted for trajectory tracking involves keeping the detected lines in the center of the image with their orientation perpendicular to the lower portion of the frame. Figure 1 and Figure 2 display the lateral and superior views of the proposed problem, respectively. P f is the point of the path used to compute Z, h is the height of the UAV relative to the power lines, θ c is the tilt between the camera and the vertical axis of the UAV, l and d are the distances between the projection of the UAV on the transmission lines plane and the position of the camera to point P f , respectively. The vectors X w , Y w , and Z w are related to the world frame W, while X r , Y r , and Z r are related to the UAV frame R. T is the vector parallel to the lines, while N is a vector perpendicular to N . φ is the UAV’s orientation in relation to W. Table 1 presents the nomenclature used in this paper.
Based on this background, the proposed control methodology focuses on the minimization of two inputs in an uncoupled approach, consisting of one controller for the lateral error (Z) that indicates how far the UAV is away from the center of the frame, and the second one for the angular error ( φ r ) that represents the angular deviation between the UAV and the power lines. Figure 3 illustrates how to calculate these errors through visual information extracted from an image containing transmission power lines.
The position and orientation errors are estimated with Equations (1) and (2).
Z = d p · k
φ r = t a n 1 d y d x
where d y and d x are the latitudinal and longitudinal lengths for the trajectory slope estimation, d p is the distance between the trajectory and the center of the frame in pixels, and k is a conversion factor from pixels to meters ( m / p i x e l s ). Equations (3) and (4) present the relationships that compute k. An illustration is shown in Figure 4.
k = F O V H w = d f L
d = h cos ( θ c )
where f L is the focal length of the camera, F O V H is the camera horizontal field of view, and w is the object width in the image. It is assumed that the height h is known during the tests and that all transmission lines are within the camera’s field of view, which must be pointed downwards.
Note that controlling the x, y, and z inertial positions and φ orientation of a UAV is achieved by adjusting its rotor speeds. In this manner, the dynamics of a quadcopter can be interpreted with four velocities: pitch (u), roll (v), yaw (r), and thrust (t). The trajectory tracking problem introduced in this research work considers that the aircraft has a constant pitching velocity u. v must be estimated to minimize Z, whereas r minimizes φ r . Therefore, an IT2_PID controller was developed for each velocity (IT2_PID_v and IT2_PID_r), with each controller working independently, receiving the desired reference and the respective error value and then generating roll and yaw velocities. A classic PID controller was also employed to keep the UAV under a constant altitude relative to the lines. The rotors are controlled by an internal control loop which is handled by the FCU (Flight Control Unit) via a mixing algorithm that receives the four velocities (u, v, r, and t) and translates them into commands for the actuators that control the rotors.

2.1. Image Processing

The parameters Z and φ r must be defined accurately throughout the flight to prevent the UAV from unwanted oscillations or undesirable routes. A difficulty in computing these variables is caused by the presence of noise in the images, which may induce the rectilinear segment detection techniques to assume spurious features as straight lines or not detect them. To mitigate the effect of noise and increase the detectability of the lines, the obtained frame at a given time t passes through an image preprocessing step.
First, the frame passes through a color space conversion from RGB to grayscale. Next, a Gaussian blur is used to smooth the color transitions in the image frame, reducing the noise interpreted as straight lines. Finally, the image undergoes a contour detection step through the Canny edge detector. This process reduces the quantity of information in the image and, consequently, the computational effort.

2.2. Line Detection and Trajectory Parameter Estimation

Following image processing, the next step is power line detection. The lines are detected through the Probabilistic Hough Transform, a low-computational-cost technique for determining geometric patterns in images based on a scheme of voting accumulators containing candidate regions for the object to be detected. The difference between this approach and the classical Hough Transform is the selection of a random subset of edge points, which ensures less computational effort [40]. In images of environments containing transmission lines, these features are expected to be highlighted against the other elements. However, asphalt markings or concrete structures can also be treated as straight elements and must be addressed as outliers to determine the path.
Following the transmission line detection, a binary image is created in which white pixels correspond to the detected lines. In aerial transmission line imaging scenarios captured by UAVs, the resulting binary mask is generally represented by three or more aligned straight lines corresponding to the transmission cables and other scattered rectilinear elements in the image. Considering these characteristics, the path to be followed by the UAV can be computed through a model-fitting technique. The method employed in this work was the RANSAC (Random Sample Consensus) algorithm. One characteristic that underlies such an approach is its robustness in the presence of outliers, since the model parameters can be estimated using a minimum sample of data.
Although the path is often rectilinear, a second-order curve was used to model the trajectory. The reason for this approach is that regions between two transmission poles can result in an abrupt change in the path orientation. Considering the path as a curve smooths these transitions, allowing navigation without significant oscillations. Figure 5 exemplifies the trajectory estimation processes in two scenarios simulated with the Gazebo simulator.

2.3. Fuzzy Logic—PID Controllers

The hybrid approach of PID with fuzzy logic controllers combines the simplicity and robustness of traditional PID controllers with the capability of the fuzzy systems to introduce linguistic rules to the model, enabling it to behave in distinct ways based on the different input signals fed to the system. Therefore, the role of the fuzzy algorithm is to operate as an adaptive mechanism, adjusting the PID gains according to the current state of the plant.
In [34], a type-1 fuzzy PID controller (T1_PID) was proposed for the positional control of a UAV as a starting point for the proposed methodology. The main difference is the replacement of the type-1 with a type-2 fuzzy logic block (IT2_PID). The internal architecture of this approach is similar to the T1_PID controller, except for replacing type-1 fuzzy sets (T1_FS) with type-2 fuzzy sets (T2_FS) and adding a type-reduction stage. A type-2 fuzzy set ( A ˜ ) can be characterized by its type-2 membership function as follows:
A ˜ = x , u , μ A ˜ ̲ x , u x X , u J x [ 0 , 1 ]
0 μ A ˜ ( x , u ) 1
A ˜ can also be written as
A ˜ = x X u J x μ A ˜ ( x , u ) ( x , u ) , J x [ 0 , 1 ]
where denotes the union of all admissible values for x and u. J x is known as the primary membership of x, while μ A ˜ is a type-1 fuzzy set referred to as the secondary set i.e.: μ A ˜ = 1 . Equation (8) defines the Footprint of Uncertainty (FOU), which, as the name suggests, is the region that encloses the system input and output uncertainties.
F O U ( A ˜ ) = x X J x = ( x , u ) : u J x [ 0 , 1 ]
The F O U of a type-2 fuzzy set is enclosed by the lower membership function (LMF) and the upper membership function (UMF) denoted by μ A ˜ ¯ ( x ) and μ A ˜ ̲ ( x ) , which are defined as follows:
μ A ˜ ¯ ( x ) = F O U ( A ˜ ) ¯ , x X
μ A ˜ ̲ ( x ) = F O U ( A ˜ ) ̲ , x X
The following steps organize the type-2 fuzzy logic block:
  • Fuzzifier: In this step, each crisp input is converted into a fuzzy input comprising the UMF and LMF. The MFs used in this paper are trapezoidal and triangular, a particular type of the first one.
  • Fuzzy Rule Base: The rule set of an IT2_FLS which is similar to a T1_FLS can be expressed by Equation (11)
    I F e 1 i s F ˜ 1 i a n d a n d e p i s F ˜ p i , T H E N y i s G l , l = 1 , , n
    where e n are the input variables, F ˜ p i are the antecedents, and y is the output of the i t h rule.
  • Inference: Since the fuzzy sets of an IT2_FLS comprise the MFs ( μ A ˜ ¯ ) and ( μ A ˜ ̲ ), the firing strengh for the i t h rule is given by
    F ˜ i = [ f i ̲ , f i ¯ ]
    f i ̲ and f i ¯ are given by
    f i ̲ = i = 1 n μ F ˜ n i ̲
    f i ¯ = i = 1 n μ F ˜ n i ¯
  • Type Reduction: The type-reduction stage converts T2_FS into T1_FS, so that crisp outputs can be obtained. In this paper, the centroid type-reduction method was employed as follows:
    C A ˜ = 1 [ y l , y r ]
    y l and y r are computed as follows:
    y l = i = 1 L y i μ A ˜ ¯ ( y i x ) + i = L + 1 N y i μ A ˜ ̲ ( y i x ) i = 1 L μ A ˜ ¯ ( y i x ) + i = L + 1 N μ A ˜ ̲ ( y i x )
    y r = i = 1 R y i μ A ˜ ¯ ( y i x ) + i = R + 1 N y i μ A ˜ ̲ ( y i x ) i = 1 R μ A ˜ ¯ ( y i x ) + i = R + 1 N μ A ˜ ̲ ( y i x )
    The type-reduced set that is represented by the left ( y l ) and right ( y r ) end points can be determined by the Karnik and Mendel method (KM) [41].
  • Defuzzifier: Finally, the outputs undergo a defuzzification process, depicted by Equation (18).
    y = y l + y r 2
Figure 6 provides a type-2 fuzzy inference system diagram.
In this work, two type-2 fuzzy-PID controllers, IT2_PID_v and IT2_PID_r, were adopted. The first is related to the lateral error Z, which also considers its time derivative, and the second is related to the angular error φ r and its derivative. Both operate independently to minimize errors simultaneously as the UAV follows the trajectory. Figure 7 displays the schematic of the IT2_PID control used to control the input variable Z. K P , K I and K D are the proportional, integrative and derivative gains. v is the roll velocity. The controller for the φ r error is similarly built.
Table 2 presents the fuzzy rules used in this paper, based on the rules presented by [34]. The errors are addressed as small, medium, and large, while the derivative of the error can be either positive, negative, or zero. The consequents shown in the table refer to the set ( K P , K D , and α ), which can assume small (L), medium (M), and large (B) values, indicating the gains of the PID controller. The integrative gain K i is obtained from the formula given by Equation (19) in which α is a weighting factor.
K I = K p 2 α K d
The upper and lower bounds of the controller gains were established according to [34,42]. The derivative and integrative gains are discarded, and the proportional gain is increased to the point that the plant produces consistent oscillations. Thus, the values of the ultimate gain K u and oscillation period T u can be calculated. For the I T 2 F P I D v controller, the values obtained were K u = 2.3 and T u = 1.8 s, whereas for I T 2 F P I D r , K u = 6.4 and T u = 1.2 s.
The upper ( K P , m a x , K D , m a x ) and lower ( K P , m i n , K D , m i n ) limits of the gains are then calculated using Equations (20)–(23).
K P , m i n = 0.32 K u
K D , m i n = 0.08 K u P u
K P , m a x = 0.6 K u
K D , m a x = 0.15 K u P u
Finally, compression of the PID controller gain range is performed for a greater smoothing of the UAV’s movements. Thus, the bounds K P , m i n , K D , m i n , K P , m a x , and K D , m a x are obtained with Equations (24)–(27).
K P , m i n = K P , m i n K P , m i n 5
K D , m i n = K D , m i n K D , m i n 5
K P , m a x = K P , m i n + K P , m a x 5
K D , m a x = K D , m i n + K D , m a x 5
The input variables (i.e., errors and time derivatives) are transformed into fuzzy sets through the fuzzification process represented by the membership functions shown in Figure 8 and Figure 9. Finally, the outputs are subjected to a defuzzification stage to establish precise gain values.

3. Results and Discussion

The results presented in this section were obtained through Gazebo. This open-source robotic simulator enables the interaction between simulated sensors and robot actuators and integrates these robots with three-dimensional models. The communication between the sensors and actuators with the simulator is accomplished through the framework ROS.
For this purpose, a scenario was developed consisting of transmission towers connected by power cables, as seen in Figure 10. The UAV was simulated via a PX4 flight controller through Software-in-the-Loop (SITL) simulation. The control node proposed in this paper receives visual information from the frontal camera attached to the UAV, estimates the relative position to the lines, and calculates the PID gains that are converted into a velocity command, which is sent to the light management unit (FMU) through an ROS driver, the MAVROS. It is worth noting that the fuzzy controllers were developed using the Python library PyIT2FLS [43].
The tests were performed on a computer with an Intel Core i5-10400F processor, an AMD Radeon RX 5600XT graphics card, and 16 GB of RAM. The operating system is Ubuntu 20.04.5 LTS 64-bit with ROS Noetic.

3.1. Horizontal Controller

Initially, the experiments were conducted involving the lateral control of the drone. For this purpose, the drone was positioned four meters above the lines, with a one-meter offset from the middle cable. The proposed controller, IT2_PID, was compared with a similar type-1 controller (T1_PID), the classic Ziegler–Nichols PID controller, and a PID controller using the mean gains assumed for the fuzzy approaches. The reason for this analysis is to investigate the capability of the proposed controller to adapt to different input scenarios compared with fixed-gain approaches.
Table 2 shows the rule sets for both fuzzy approaches. Each controller was tested 50 times. The profile of the mean error over time is provided in Figure 11. The solid line indicates the setpoint, while the dotted lines indicate the thresholds of the steady-state region. Table 3 presents the quantitative results of the tests. IAE is the integral absolute error, M p is the maximum peak, T p is the peak time, T s is the settling time, and E s s is the steady-state error. Additionally, the runtime for each controller was computed.
From the graphical analysis, it is seen that the four controllers could keep the UAV close to the established setpoint. However, the PID_ZN control displayed a high overshoot with higher oscillations, which is undesirable in UAV applications. The controllers IT2_PID and T1_PID presented lower values of IAE, which evaluates the absolute error throughout the test, with a slight advantage for the type-2 fuzzy version. The smallest value for the maximum peak was achieved by the PID_Mean control, despite higher values for the peak and accommodation times compared to the adaptive approaches. These findings justify the employment of fuzzy models to adjust the parameters compared to fixed-gain approaches. It is important to note that there are minor inconsistencies in the estimation of the lateral error in scenarios where the UAV has a certain degree of tilt, especially when the lines are near the end of the camera’s field of view. This effect was mitigated through an image rectification process, which employs a rotation matrix to correct the image perspective. Despite this behavior, the proposed controller kept the UAV close to the desired setpoint.
When comparing the two fuzzy approaches, the IT2_PID has superior results in all observed metrics based on mean values despite, as expected, having a longer processing time. However, it did not impact the overall system, which processes the information and sends velocity commands with a frequency of 10 Hz.
Finally, the accumulated error, which shows how far the UAV is from the desired position over the test period, is given in Figure 12. All controllers display a similar behavior until approximately 1.4 s, when fixed-gain controllers exhibit more significant error variations. At 2.0 s, the distinction between the fuzzy approaches can be noticed, with the difference increasing throughout the steady state.

3.2. Modifications on Fuzzy Rules

By examining the set of rules expressed in Table 2, proposed by [35], it is possible to imply that the controller behaves uniformly in instances where the derivative of the error is either negative or positive, that is, whenever the absolute error decreases or increases, respectively. With this background information, some changes to the rule set were proposed to make the controller more aggressive as the UAV moves away from the setpoint and moves more smoothly as it heads toward it. Additionally, the derived gain was reduced for minor errors. Therefore, Table 4 presents the new proposed rule set.
The graphical results of this modification are presented in Figure 13, and the quantitative data can be seen in Table 5.
From the graphical analysis, the rule set modifications could induce a slight reduction in the UAV oscillation in the transient regime. Such reduction can also be noticed in the quantitative results, with the reduction in the IAE and M p for the mean values. E s s and processing time remain substantially unaffected.

3.3. Angular Controller

Subsequently, an angular controller was introduced to maintain the UAV in parallel alignment with the power transmission lines. For the tests, the UAV was positioned at a height of 4 m from the lines with an angular deviation of 1 r a d relative to the power lines. The membership functions for the fuzzy approaches are shown in Figure 9, while the used rule set is presented in Table 4.
Figure 14 shows the evolution of the error over time, while Table 6 presents the quantitative measurements. As observed for the lateral error, the PID_ZN controller exhibited a significant main peak value, an expected behavior due to the aggressive nature of this type of controller. In comparison to the other approaches, it can be observed that the fixed-gain PID has the lowest peak maximum value; however, the integral of the absolute error is considerably higher than the adaptive gain controllers.
As observed for the lateral controller, the IT2_PID controller has outperformed the T1_PID over both the IAE and the M p considering the mean values. This can also be noted by a slight reduction in the error deviation. From Figure 15, it can be noticed that the difference in the cumulative error between the two methods was again in the transient state of the system, remaining relatively unchanged throughout the steady state. At approximately 1.5 s, the cumulative error of the PID_Mean increases, which emphasizes the capability of adaptive models to deal with several different settings.

3.4. Simulation of an Inspection Mission

Finally, a simulation of a transmission line inspection mission was carried out. For this purpose, the UAV starts the tracking at a lateral offset of 1 m with an angular error of 0.75 r a d . The drone follows the trajectory of three transmission towers connected by three cables, as shown in Figure 10, with a forward speed of 0.4 m/s. The mission has a duration of 160 s. At approximately 90 s, the trajectory exhibits an inflection point, at which the line detection and path estimation algorithms display a degree of inaccuracy due to the addition of spurious rectilinear elements. For this experiment, the two fuzzy approaches, IT2_PID and T1_PID, were tested with 50 executions of each controller.
Figure 16 and Figure 17 display the evolution of the horizontal and angular errors during the mission. It is possible to notice that both controls successfully kept the UAV in the equilibrium condition. At 90 s, the UAV has crossed the point where the trajectory changes direction, which leads to oscillatory behavior in the inferred measurements. Despite this, the UAV remained on the established path throughout the mission.
The numerical results for the IAE are presented in Table 7. The IT2_PID controller achieved better performance for both the lateral and angular errors. This behavior can be explained by the capability of type-2 fuzzy systems to better cope with uncertainties in the input and output variables of the model [44]. Figure 18 and Figure 19 present the accumulated errors during the mission. It is possible to notice that the two controllers behave similarly for both variables, with a slight advantage of the IT2_PID controller. When uncertainty is inserted into the model, the difference between the curves becomes more significant for both variables, highlighting the better performance of type-2 fuzzy systems in such scenarios.

3.5. Result Discussions

In the literature, most works involving the use of fuzzy logic as a tuning tool for PID controllers use type-1 fuzzy systems. In this work, however, the use of a type-2 interval fuzzy system was proposed. This modification included an FOU in the membership functions of the model, making it more robust to the effect of noisy data, which is common in robotic systems. The IT2_PID approach showed superior quantitative performance results for the proposed transmission line tracking application over the T1_PID and the classical Ziegler–Nichols tuning method. When comparing the proposed approach with the Ziegler–Nichols method, it was possible to observe reductions in the average values of 29.4% for the IAE, 41.7% in the M p for the horizontal controller, and 2.47% in the IAE and 58.6% in the M p for the angular controller. In addition, the settling time was reduced by 51.3% for the horizontal controller and increased by 29.5% for the angle controller.
In the original approach that supported this work, the fuzzy rule set was not modified based on whether the derivative of the error was positive or negative. The authors emphasized this, and thereby a new rule set was introduced in this research to allow the controller to behave more aggressively in situations where the error increases and smooths out otherwise. The results indicated a reduction of 1.9% in the integral of the absolute error and 5.8% for the M p . It is worth mentioning that further rule combinations can be tested, and this is a topic for future works. Additionally, the rule sets should be evaluated according to the proposed application. Moreover, in order to mitigate the discontinuity behavior brought by fuzzy logic in the control system, the membership functions and rule bases were appropriately designed to ensure smooth transitions between fuzzy sets.
It is also important to highlight that all sensor and actuator integration, image processing, fuzzy logic algorithms, PID controllers, and commands sent to the UAV are handled through the ROS framework in Python scripts, making it possible to test the methodology on several UAV models without the need for significant modifications.

4. Conclusions and Future Work

UAVs have been the focal point of many types of research, expanding the range of possible applications that increasingly support human workers in various tasks. In the scope of power grid maintenance, UAVs can be helpful in the inspection of transmission lines; therefore, algorithms must perform this task as safely and efficiently as possible. With that in mind, the presented work proposed an interval type-2 fuzzy-logic-based PID controller to allow the alignment and tracking of transmission power lines using a UAV.
The algorithm receives the positional and angular errors of the UAV relative to the lines by processed images taken by a camera attached to the aircraft’s base. Next, an interval type-2 fuzzy logic block provides the controller gains based on the errors and their respective derivatives. This approach allows the controller to perform differently based on the magnitude of the input variables. The type-2 fuzzy system introduces a region of uncertainty in these variables, which helps the model deal with noisy data.
The proposed methodology was tested through flights conducted by the Gazebo simulator. For the UAV alignment tests, it can be noticed that the IT2_PID controller achieved superior metrics compared to its T1_PID variant and the traditional Zigler–Nichols tuning technique for both lateral and angular errors, exhibiting lower cumulative error values with lower M p values. The comparison of the proposed technique with a fixed-gain PID controller based on the average of the fuzzy gain range demonstrated the ability of these models to adapt according to the stage the system is inserted. Experiments involving the following of the UAV through the power lines have shown the capability of the type-2 fuzzy system to better handle the presence of uncertainties in the measurements.
Note that this simulation experiment serves as a prior estimate for the proposed application viability, indicating that the proposed methodology would be feasible to be applied in the proposed scenario. It is also important to highlight that the implemented methodology is thoroughly ready to be tested on a physical PixHawk PX4 FCU due to its robust simulation results and the implemented MavROS ready-to-use offboard controller package. Therefore, testing the developed methodology in a real vehicle is an important next step. However, potential challenges, such as lighting conditions and winds, could harm the process in real applications. In this sense, this work opens several future possibilities. The main point to be addressed is the implementation of the proposed methodology in an embedded system in a real scenario. This task requires robust transmission line detection techniques with a computational effort suitable to the controller requirements in order to mitigate the mentioned issues in a real scenario.
One possible option to be explored for this issue is merging the information acquired by the cameras with laser sensors, allowing for the identification and determination of the distance of the UAV in terms of the power lines to be followed. Another aspect to investigate is the modification of the shape of the membership functions and the effect of the variation in the number of these functions on the controller behavior.

Author Contributions

Conceptualization, G.A.N.P., E.P.d.A. and A.L.M.M.; methodology, G.A.N.P., E.P.d.A. and A.L.M.M.; software, G.A.N.P., E.P.d.A., and A.L.M.M.; formal analysis, E.P.d.A. and A.L.M.M.; investigation, G.A.N.P.; writing—original draft preparation, G.A.N.P., E.P.d.A. and A.L.M.M.; writing—review and editing, G.A.N.P., E.P.d.A., A.L.M.M. and M.F.P.; visualization, G.A.N.P.; supervision, E.P.d.A. and A.L.M.M.; project administration, E.P.d.A. and A.L.M.M.; funding acquisition, M.F.P. All authors have read and agreed with the submission of the current manuscript version.

Funding

The authors also would like to thank their home Institute CEFET/RJ, the federal Brazilian research agencies CAPES (code 001) and CNPq, and the Rio de Janeiro research agency FAPERJ, for supporting this work.

Data Availability Statement

The source codes are openly available in https://github.com/guiaugustoga987/it2fpid_ltc (accessed on 13 March 2023).

Acknowledgments

The authors have no conflicts of interests to declare that are relevant to the content of this article. The authors acknowledge the support of the Federal Univerisity of Juiz de Fora (UFJF) throughout this work and the financial support of PBPG/UFJF. Additionally, they would like to thank CEFET/RJ, CAPES, CNPq, and FAPERJ for their support.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
FOUFootprint of Uncertainty
GNSSGlobal Navigation Satellite System
GPSGlobal Positioning System
IBSVImage-based visual servoing
IT2_PIDType-2 fuzzy logic
LMFLower membership function
PSOParticle Swarm Optimization
PIDProportional-Integral-Derivative
RGBRed, blue, and green
ROSRobot Operating System
T1_PIDType-1 Fuzzy Logic PID controllers
UAVUnmanned Aerial Vehicle
UMFUpper membership function

References

  1. Pinto, M.F.; Honorio, L.M.; Melo, A.; Marcato, A.L. A robotic cognitive architecture for slope and dam inspections. Sensors 2020, 20, 4579. [Google Scholar] [CrossRef] [PubMed]
  2. Biundini, I.Z.; Pinto, M.F.; Melo, A.G.; Marcato, A.L.; Honório, L.M.; Aguiar, M.J. A framework for coverage path planning optimization based on point cloud for structural inspection. Sensors 2021, 21, 570. [Google Scholar] [CrossRef]
  3. Delavarpour, N.; Koparan, C.; Nowatzki, J.; Bajwa, S.; Sun, X. A technical study on UAV characteristics for precision agriculture applications and associated practical challenges. Remote Sens. 2021, 13, 1204. [Google Scholar] [CrossRef]
  4. Zhang, H.; Wang, L.; Tian, T.; Yin, J. A review of unmanned aerial vehicle low-altitude remote sensing (UAV-LARS) use in agricultural monitoring in China. Remote Sens. 2021, 13, 1221. [Google Scholar] [CrossRef]
  5. Mourtzis, D.; Angelopoulos, J.; Panopoulos, N. UAVs for Industrial Applications: Identifying Challenges and Opportunities from the Implementation Point of View. Procedia Manuf. 2021, 55, 183–190. [Google Scholar] [CrossRef]
  6. Pathak, N.; Mukherjee, A.; Misra, S. AerialBlocks: Blockchain-enabled UAV virtualization for industrial IoT. IEEE Internet Things Mag. 2021, 4, 72–77. [Google Scholar] [CrossRef]
  7. Ramesh, P.; Jeyan, J.M.L. Comparative analysis of the impact of operating parameters on military and civil applications of mini unmanned aerial vehicle (UAV). AIP Conf. Proc. 2020, 2311, 030034. [Google Scholar]
  8. Utsav, A.; Abhishek, A.; Suraj, P.; Badhai, R.K. An IoT based UAV network for military applications. In Proceedings of the 2021 Sixth International Conference on Wireless Communications, Signal Processing and Networking (WiSPNET), Chennai, India, 25–27 March 2021; IEEE: Piscataway, NJ, USA, 2021; pp. 122–125. [Google Scholar]
  9. Hedjar, R.; Al Zuair, M.A. Robust altitude stabilization of VTOL-UAV for payloads delivery. IEEE Access 2019, 7, 73583–73592. [Google Scholar] [CrossRef]
  10. Gupta, A.; Afrin, T.; Scully, E.; Yodo, N. Advances of UAVs toward future transportation: The State-of-the-Art, challenges, and Opportunities. Future Transp. 2021, 1, 326–350. [Google Scholar] [CrossRef]
  11. Almadhoun, R.; Taha, T.; Dias, J.; Seneviratne, L.; Zweiri, Y. Coverage path planning for complex structures inspection using unmanned aerial vehicle (UAV). In Proceedings of the International Conference on Intelligent Robotics and Applications, Shenyang, China, 8–11 August 2019; Springer: Cham, Sitzerland, 2019; pp. 243–266. [Google Scholar]
  12. Lekidis, A.; Anastasiadis, A.G.; Vokas, G.A. Electricity infrastructure inspection using AI and edge platform-based UAVs. Energy Rep. 2022, 8, 1394–1411. [Google Scholar] [CrossRef]
  13. Krause, S.; Sanders, T.G.; Mund, J.P.; Greve, K. UAV-based photogrammetric tree height measurement for intensive forest monitoring. Remote Sens. 2019, 11, 758. [Google Scholar] [CrossRef]
  14. Wang, X.; Wang, Y.; Zhou, C.; Yin, L.; Feng, X. Urban forest monitoring based on multiple features at the single tree scale by UAV. Urban For. Urban Green. 2021, 58, 126958. [Google Scholar] [CrossRef]
  15. Alotaibi, E.T.; Alqefari, S.S.; Koubaa, A. Lsar: Multi-uav collaboration for search and rescue missions. IEEE Access 2019, 7, 55817–55832. [Google Scholar] [CrossRef]
  16. Alsamhi, S.H.; Shvetsov, A.V.; Kumar, S.; Shvetsova, S.V.; Alhartomi, M.A.; Hawbani, A.; Rajput, N.S.; Srivastava, S.; Saif, A.; Nyangaresi, V.O. UAV computing-assisted search and rescue mission framework for disaster and harsh environment mitigation. Drones 2022, 6, 154. [Google Scholar] [CrossRef]
  17. Pinto, M.F.; Honório, L.M.; Marcato, A.L.; Dantas, M.A.; Melo, A.G.; Capretz, M.; Urdiales, C. Arcog: An aerial robotics cognitive architecture. Robotica 2021, 39, 483–502. [Google Scholar] [CrossRef]
  18. Shao, W.; Kawakami, R.; Yoshihashi, R.; You, S.; Kawase, H.; Naemura, T. Cattle detection and counting in UAV images based on convolutional neural networks. Int. J. Remote Sens. 2020, 41, 31–52. [Google Scholar] [CrossRef]
  19. de Lima Weber, F.; de Moraes Weber, V.A.; de Moraes, P.H.; Matsubara, E.T.; Paiva, D.M.B.; Gomes, M.d.N.B.; de Oliveira, L.O.F.; de Medeiros, S.R.; Cagnin, M.I. Counting cattle in UAV images using convolutional neural network. Remote. Sens. Appl. Soc. Environ. 2022, 29, 100900. [Google Scholar] [CrossRef]
  20. Hui, X.; Bian, J.; Zhao, X.; Tan, M. Vision-based autonomous navigation approach for unmanned aerial vehicle transmission-line inspection. Int. J. Adv. Robot. Syst. 2018, 15, 1729881417752821. [Google Scholar] [CrossRef]
  21. Zhang, T.; Dai, J. Electric Power Intelligent Inspection Robot: A Review. J. Phys. 2021, 1750, 012023. [Google Scholar] [CrossRef]
  22. Silva, A.J.N.d. Análise Organizacional de Acidentes de Trabalho no Setor de Distribuição de Energia elétrica. Master’s Thesis, Universidade Estadual Paulista Julio de Mesquita Filho, Sao Paulo, Brazil, 2015. [Google Scholar]
  23. Takaya, K.; Ohta, H.; Kroumov, V.; Shibayama, K.; Nakamura, M. Development of UAV system for autonomous power line inspection. In Proceedings of the 2019 23rd International Conference on System Theory, Control and Computing (ICSTCC), Sinaia, Romania, 9–11 October 2019; IEEE: Piscataway, NJ, USA, 2019; pp. 762–767. [Google Scholar]
  24. Menéndez, O.; Pérez, M.; Auat Cheein, F. Visual-based positioning of aerial maintenance platforms on overhead transmission lines. Appl. Sci. 2019, 9, 165. [Google Scholar] [CrossRef]
  25. Cerón, A.; Mondragón, I.; Prieto, F. Onboard visual-based navigation system for power line following with UAV. Int. J. Adv. Robot. Syst. 2018, 15, 1729881418763452. [Google Scholar] [CrossRef]
  26. Rafique, M.A.; Lynch, A.F. Output-feedback image-based visual servoing for multirotor unmanned aerial vehicle line following. IEEE Trans. Aerosp. Electron. Syst. 2020, 56, 3182–3196. [Google Scholar] [CrossRef]
  27. Abdullah, M.N.; Dagher, K.E. Airborne Computer System Path-Tracking Based Multi-PID-PSO Controller Design. Int. J. Intell. Eng. Syst. 2021, 14, 403–411. [Google Scholar] [CrossRef]
  28. Feng, H.; Ma, W.; Yin, C.; Cao, D. Trajectory control of electro-hydraulic position servo system using improved PSO-PID controller. Autom. Constr. 2021, 127, 103722. [Google Scholar] [CrossRef]
  29. Takaoğlu, F.; Alshahrani, A.; Ajlouni, N.; Ajlouni, F.; Al Kasasbah, B.; Özyavaş, A. Robust Nonlinear Non-Referenced Inertial Frame Multi-Stage PID Controller for Symmetrical Structured UAV. Symmetry 2022, 14, 689. [Google Scholar] [CrossRef]
  30. So, G.B. A modified 2-DOF control framework and GA based intelligent tuning of PID controllers. Processes 2021, 9, 423. [Google Scholar] [CrossRef]
  31. Noordin, A.; Mohd Basri, M.A.; Mohamed, Z.; Mat Lazim, I. Adaptive PID controller using sliding mode control approaches for quadrotor UAV attitude and position stabilization. Arab. J. Sci. Eng. 2021, 46, 963–981. [Google Scholar] [CrossRef]
  32. Kang, B.; Miao, Y.; Liu, F.; Duan, J.; Wang, K.; Jiang, S. A second-order sliding mode controller of quad-rotor UAV based on PID sliding mode surface with unbalanced load. J. Syst. Sci. Complex. 2021, 34, 520–536. [Google Scholar] [CrossRef]
  33. Rabah, M.; Rohan, A.; Mohamed, S.A.; Kim, S.H. Autonomous moving target-tracking for a UAV quadcopter based on fuzzy-PI. IEEE Access 2019, 7, 38407–38419. [Google Scholar] [CrossRef]
  34. Andrade, F.A.; Guedes, I.P.; Carvalho, G.F.; Zachi, A.R.; Haddad, D.B.; Almeida, L.F.; de Melo, A.G.; Pinto, M.F. Unmanned Aerial Vehicles Motion Control with Fuzzy Tuning of Cascaded-PID Gains. Machines 2021, 10, 12. [Google Scholar] [CrossRef]
  35. Carvalho, G.; Guedes, I.; Pinto, M.; Zachi, A.; Almeida, L.; Andrade, F.; Melo, A.G. Hybrid PID-Fuzzy controller for autonomous UAV stabilization. In Proceedings of the 2021 14th IEEE International Conference on Industry Applications (INDUSCON), Sao Paulo, Brazil, 15–18 August 2021; IEEE: Piscataway, NJ, USA, 2021; pp. 1296–1302. [Google Scholar]
  36. Rao, J.; Li, B.; Zhang, Z.; Chen, D.; Giernacki, W. Position Control of Quadrotor UAV Based on Cascade Fuzzy Neural Network. Energies 2022, 15, 1763. [Google Scholar] [CrossRef]
  37. Al-Mahturi, A.; Santoso, F.; Garratt, M.A.; Anavatti, S.G. Self-learning in aerial robotics using type-2 fuzzy systems: Case study in hovering quadrotor flight control. IEEE Access 2021, 9, 119520–119532. [Google Scholar] [CrossRef]
  38. Tavoosi, J.; Shirkhani, M.; Abdali, A.; Mohammadzadeh, A.; Nazari, M.; Mobayen, S.; Asad, J.H.; Bartoszewicz, A. A new general type-2 fuzzy predictive scheme for PID tuning. Appl. Sci. 2021, 11, 10392. [Google Scholar] [CrossRef]
  39. Sarabakha, A.; Fu, C.; Kayacan, E.; Kumbasar, T. Type-2 fuzzy logic controllers made even simpler: From design to deployment for UAVs. IEEE Trans. Ind. Electron. 2017, 65, 5069–5077. [Google Scholar] [CrossRef]
  40. Kiryati, N.; Eldar, Y.; Bruckstein, A.M. A probabilistic Hough transform. Pattern Recognit. 1991, 24, 303–316. [Google Scholar] [CrossRef]
  41. Wu, D.; Mendel, J.M. Enhanced karnik–mendel algorithms. IEEE Trans. Fuzzy Syst. 2008, 17, 923–934. [Google Scholar]
  42. Larson, K. Fuzzy Logic Tuning of a Proportional-Integral-Derivative Controller. Master’s Thesis, California State Polytechnic University, Pomona, CA, USA, 2016. [Google Scholar]
  43. Haghrah, A.A.; Ghaemi, S. PyIT2FLS: A New Python Toolkit for Interval Type 2 Fuzzy Logic Systems. arXiv 2019, arXiv:1909.10051. [Google Scholar]
  44. De, A.K.; Chakraborty, D.; Biswas, A. Literature review on type-2 fuzzy set theory. Soft Comput. 2022, 26, 9049–9068. [Google Scholar] [CrossRef]
Figure 1. Lateral view of the line-following problem.
Figure 1. Lateral view of the line-following problem.
Robotics 12 00060 g001
Figure 2. Superior view of the line-following problem.
Figure 2. Superior view of the line-following problem.
Robotics 12 00060 g002
Figure 3. Extraction of errors using visual information.
Figure 3. Extraction of errors using visual information.
Robotics 12 00060 g003
Figure 4. Visual information extracted from the image.
Figure 4. Visual information extracted from the image.
Robotics 12 00060 g004
Figure 5. Trajectory estimation based on the RANSAC algorithm.
Figure 5. Trajectory estimation based on the RANSAC algorithm.
Robotics 12 00060 g005
Figure 6. IT2_FLS block diagram.
Figure 6. IT2_FLS block diagram.
Robotics 12 00060 g006
Figure 7. Schematic of the IT2_PID controller.
Figure 7. Schematic of the IT2_PID controller.
Robotics 12 00060 g007
Figure 8. IT2_PID_v membership functions.
Figure 8. IT2_PID_v membership functions.
Robotics 12 00060 g008
Figure 9. IT2_PID_r membership functions.
Figure 9. IT2_PID_r membership functions.
Robotics 12 00060 g009
Figure 10. Simulated scenario in Gazebo.
Figure 10. Simulated scenario in Gazebo.
Robotics 12 00060 g010
Figure 11. Comparison of the presented approaches-lateral error.
Figure 11. Comparison of the presented approaches-lateral error.
Robotics 12 00060 g011
Figure 12. Comparison of the accumulated lateral error.
Figure 12. Comparison of the accumulated lateral error.
Robotics 12 00060 g012
Figure 13. Comparison of the lateral error for different fuzzy rule sets.
Figure 13. Comparison of the lateral error for different fuzzy rule sets.
Robotics 12 00060 g013
Figure 14. Comparison of the presented approaches—angular error.
Figure 14. Comparison of the presented approaches—angular error.
Robotics 12 00060 g014
Figure 15. Comparison of the accumulated angular error.
Figure 15. Comparison of the accumulated angular error.
Robotics 12 00060 g015
Figure 16. Comparison of the error for a transmission line inspection mission with fuzzy-PID—lateral control.
Figure 16. Comparison of the error for a transmission line inspection mission with fuzzy-PID—lateral control.
Robotics 12 00060 g016
Figure 17. Comparison of the error for transmission line inspection mission with fuzzy-PID—angular control.
Figure 17. Comparison of the error for transmission line inspection mission with fuzzy-PID—angular control.
Robotics 12 00060 g017
Figure 18. Accumulated error evolution for the transmission line inspection mission simulation—lateral control.
Figure 18. Accumulated error evolution for the transmission line inspection mission simulation—lateral control.
Robotics 12 00060 g018
Figure 19. Accumulated error evolution for the transmission line inspection mission simulation—angular control.
Figure 19. Accumulated error evolution for the transmission line inspection mission simulation—angular control.
Robotics 12 00060 g019
Table 1. Descriptions of variables used in the methodology.
Table 1. Descriptions of variables used in the methodology.
SymbolDescription
ZLateral error
φ r Angular error
P f Point of the path used to compute Z
hRelative height of the UAV to the transmission lines
θ c Camera tilting
lDistance between the projection of the UAV on the path plane and P f
dDistance between the camera and P f
WWorld frame
RUAV frame
d p Trajectory distance to the center of the frame
d y Latitudinal length for trajectory slope estimation
d x Longitudinal length for trajectory slope estimation
kPixels to meters conversion factor
f L Focal length of the camera
F O V H Camera horizontal field of view
wObject width in the image
u , v , r , t Pitch, roll, yaw, and thrust velocities
K P , K D , K i Proportional, derivative, and integrative gains
α Factor to compute K i
K u , T u Ultimate gain and oscillation period
Table 2. Fuzzy rule set.
Table 2. Fuzzy rule set.
Z
dZ/dtSmallMediumBig
NegativeL/B/BM/M/MB/L/L
ZeroB/B/MB/M/LB/L/L
PositiveL/B/BM/M/MB/L/L
Table 3. Quantitative results—horizontal controller.
Table 3. Quantitative results—horizontal controller.
ControllerIAE M p ( m ) T p ( s ) T s ( s ) E ss ( m ) Proc. Time (s)
IT2_PID 2.3392 ± 0.1869 0.2005 ± 0.0572 3.72 ± 0.3423 9.21 ± 0.48 0.0164 ± 0.0078 0.0103 ± 2.57 × 10 4
T1_PID 2.4742 ± 0.1896 0.2111 ± 0.0545 3.75 ± 0.3823 9.45 ± 0.54 0.0209 ± 0.0090 0.0077 ± 1.7267 × 10 4
PID_Mean 2.5490 ± 0.1746 0.1563 ± 0.0292 4.85 ± 0.3823 10.32 ± 0.61 0.0184 ± 0.0075 1.0873 × 10 4 ± 1.9944 × 10 5
PID_ZN 3.3122 ± 0.1634 0.3437 ± 0.0252 3.05 ± 0.1526 18.91 ± 0.46 0.0219 ± 0.0057 1.0310 × 10 4 ± 1.3417 × 10 5
Table 4. Modified fuzzy rule set.
Table 4. Modified fuzzy rule set.
Z
dZ/dtSmallMediumBig
NegativeL/M/BM/M/MB/L/L
ZeroB/B/MB/M/LB/L/L
PositiveM/M/BB/M/MB/L/L
Table 5. Comparison between original and modified fuzzy rule sets -quantitative results.
Table 5. Comparison between original and modified fuzzy rule sets -quantitative results.
ControllerIAE M p ( m ) T p ( s ) T s ( s ) E ss ( m ) Proc. Time (s)
Original 2.3392 ± 0.1869 0.2005 ± 0.0572 3.72 ± 0.3423 9.21 ± 0.48 0.0164 ± 0.0078 0.0103 ± 2.5738 × 10 4
Proposed 2.2936 ± 0.1692 0.1887 ± 0.0407 3.99 ± 0.3821 9.11 ± 0.43 0.0170 ± 0.0070 0.0098 ± 3.4819 × 10 4
Table 6. Quantitative results—angular controller.
Table 6. Quantitative results—angular controller.
ControllerIAE M p ( m ) T p ( s ) T s ( s ) E ss ( m ) Proc. Time (s)
IT2_PID 0.7514 ± 0.0147 0.2012 ± 0.0238 1.23 ± 0.377 3.32 ± 0.49 1.12 × 10 3 ± 1.91 × 10 4 0.0150 ± 6.1912 × 10 4
T1_PID 0.7647 ± 0.0179 0.2194 ± 0.0555 1.22 ± 0.366 3.28 ± 0.54 1.13 × 10 3 ± 1.77 × 10 4 0.0099 ± 6.7115 × 10 4
PID_Mean 0.8608 ± 0.0192 0.1825 ± 0.0059 2.05 ± 0.140 3.35 ± 0.71 1.06 × 10 3 ± 1.63 × 10 4 1.0489 × 10 4 ± 1.5211 × 10 5
PID_ZN 0.7704 ± 0.0262 0.4863 ± 0.0667 0.92 ± 0.043 2.34 ± 0.349 1.18 × 10 3 ± 2.13 × 10 4 1.0811 × 10 4 ± 1.5917 × 10 5
Table 7. Inspection mission—IAE comparison.
Table 7. Inspection mission—IAE comparison.
ControllerIAE_ZIAE_ φ r
IT2_PID 5.6645 ± 0.3721 1.5028 ± 0.1112
T1_PID 5.8454 ± 0.4960 1.5221 ± 0.1557
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Pussente, G.A.N.; de Aguiar, E.P.; Marcato, A.L.M.; Pinto, M.F. UAV Power Line Tracking Control Based on a Type-2 Fuzzy-PID Approach. Robotics 2023, 12, 60. https://doi.org/10.3390/robotics12020060

AMA Style

Pussente GAN, de Aguiar EP, Marcato ALM, Pinto MF. UAV Power Line Tracking Control Based on a Type-2 Fuzzy-PID Approach. Robotics. 2023; 12(2):60. https://doi.org/10.3390/robotics12020060

Chicago/Turabian Style

Pussente, Guilherme A. N., Eduardo P. de Aguiar, Andre L. M. Marcato, and Milena F. Pinto. 2023. "UAV Power Line Tracking Control Based on a Type-2 Fuzzy-PID Approach" Robotics 12, no. 2: 60. https://doi.org/10.3390/robotics12020060

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop