Your new experience awaits. Try the new design now and help us make it even better

ORIGINAL RESEARCH article

Front. Robot. AI, 07 July 2025

Sec. Robotic Control Systems

Volume 12 - 2025 | https://doi.org/10.3389/frobt.2025.1528415

Hybrid disturbance observer and fuzzy logic controller for a new aerial manipulation system

Alaa Khalifa
Alaa Khalifa1*Shaaban M. ShaabanShaaban M. Shaaban2Ahmed KhalifaAhmed Khalifa3
  • 1Department of Industrial Electronics and Control Engineering, Faculty of Electronic Engineering, Menoufia University, Menouf, Egypt
  • 2Center for Scientific Research and Entrepreneurship, Northern Border University, Arar, Saudi Arabia
  • 3Cardiff School of technologies, Cardiff Metropolitan University, Cardiff, United Kingdom

Aerial manipulation systems are highly attractive for various applications due to their distinctive features. However, the systems discussed in the literature are constrained by either a restricted number of end-effector degrees of freedom (DOFs) or low payload capability. In our previous research, we mounted a manipulator with a gripper on the underside of a quadrotor to enhance environmental interaction. This paper explores a quadrotor equipped with a 2-DOF manipulator featuring a distinctive topology that allows the end-effector to follow a specified 6-DOF trajectory with the least number of actuators required. An overview of the proposed manipulation system, along with its kinematic and dynamic analysis, is presented. Nevertheless, controlling this system presents significant challenges because of its considerable couplings, nonlinearities, and external disturbances. This paper employs a Disturbance Observer (DOb)-based linearization for an aerial manipulation robot. The DOb-based inner loop is responsible for estimating and compensating nonlinearities and disturbances, which simplifies the control problem into a more straightforward linear control algorithm. Subsequently, a fuzzy logic controller is incorporated into the outer loop to achieve the desired control objectives and closed-loop performance while minimizing computational load. Stability analysis of the proposed controller is introduced. Finally, the system is simulated using MATLAB/SIMULINK, and the results demonstrate tracking accuracy during 6-DOF maneuvers under many kinds of disturbances, with low computational load. The system maintains stability during payload exchanges while respecting all actuator constraints (rotor thrust less than 6 N, joint torques less than 0.7 and 0.4 N.m, respectively). These results demonstrate the effectiveness of the proposed control approach. Also, they show that the proposed controller outperforms the DOb-PD controller’s response.

1 Introduction

Recently, there has been significant interest in aerial manipulators due to their crucial applications in areas that ground robots cannot reach (Khamseh et al., 2018). Quadrotors, with their exceptional mobility, are employed for mobile manipulation, opening new avenues in robotics (Wei-hong et al., 2021; Xilun et al., 2019). These systems are used for various tasks such as inspection, firefighting, maintenance, delivering light items like mail or quick meals in crowded cities, surveillance, rescue operations, transportation in remote locations, demining, and performing tasks in hazardous environments (Orsag et al., 2018; Li et al., 2024).

Numerous studies have been conducted in the field of aerial manipulation (Ollero et al., 2022; Meng et al., 2020; Ruggiero et al., 2018; Wei-hong et al., 2021). However, existing systems in the literature that utilize a gripper are constrained by the limited degrees of freedom (DOF) of the end-effector. Some systems feature a 2-DOF manipulator, which in some configurations prevents the end-effector from following an arbitrary 6-DOF trajectory. Other systems have a manipulator with more than two DOF, which significantly reduces the system’s payload capacity (Orsag et al., 2017). In Fanni and Khalifa (2017), Khalifa et al. (2016a), Khalifa et al. (2024), Khalifa et al. introduce a novel aerial manipulation system comprising a two-link manipulator with two perpendicular revolute joints. One of the quadrotor’s in-plane axes and the first joint’s axis are parallel to each other. The end-effector can achieve any desired position and orientation thanks to this configuration, which eliminates the need for horizontal movement.

Existing control strategies in the literature for aerial manipulation systems rely on highly complex nonlinear controllers that demand significant computational resources. Achieving stable position holding is a major challenge in aerial manipulation. To accomplish this, a robust control system is necessary to handle disturbances, nonlinearities, uncertainties, and couplings. This robustness challenge was addressed in Khalifa et al. (2016b) by employing a control technique based on DOb, which estimates uncertainties and nonlinear terms. By doing so, the robotic system behaves akin to a multi-SISO linear system, allowing the use of standard linear control methods for designing the outer loop controller and ensuring accurate tracking performance.

However, prior research (Li et al., 2016; Sariyildiz and Ohnishi, 2014; Choi et al., 2014; Tian et al., 2024) related to Disturbance Observer (DOb) techniques faces challenges in estimating system velocity or acceleration, particularly due to limitations in sensors that are available for flying robots. Although it is possible to measure angular velocities and linear accelerations using encoders and an Inertial Measurement Unit (IMU), Tomić and Haddadin (2014) suggests a model-based method to estimate external forces for a basic UAV, relying on IMU data. However, this method requires knowledge of dynamic models, disregards certain nonlinearities and dynamics, employs a nonlinear controller, and exclusively addresses external disturbances without taking system dynamics comprehensively into consideration. As a result, this technique is not well-suited for the complex dynamical and kinematic characteristics of the considered aerial manipulator.

In Tutsoy et al. (2023), a reduced-order Thau observer was presented that focusses on uncertain rotational dynamics and achieves accurate fault detection with just a third-order design. However, it should be expanded to include control signal delays, state measurement delays, data loss, and sensor failures. There are many kinds of modern artificial intelligence-based observers. However, the main issue is balancing computational cost, accuracy, and estimation speed. The aerial robotic manipulation system has very fast dynamics. So, an approach with low computational cost is needed. Also, all of these computations must be accomplished onboard to avoid any delay. On the other hand, the computational time in artificial intelligence-based observers will be long.

To address these limitations, the traditional DOb is adapted to be practical and compatible for the aerial manipulation system proposed in Fanni and Khalifa (2017); Khalifa et al. (2016a), Khalifa et al. (2024); Khalifa and Fanni (2017). In the traditional DOb structure, the DOb estimates system disturbances using velocity or acceleration measurements. However, it is commonly known that the quadrotor’s linear accelerations and angular rates may be obtained straight from the IMU. Furthermore, the angular velocities of the joints may be monitored using an encoder. As a result, we propose a hybrid DOb-based controller for our robotic system. In this hybrid DOb-based control, two distinct DOb loops are employed. The first is based on measured accelerations, and the second on measured velocities. Instead of using differentiation (which makes the system more sensitive to noise) or integration (which causes drift), the proposed scheme uses the measured velocity and acceleration directly from the onboard sensors, with no differentiation or integration. As a result, we propose and implement a hybrid observer that uses raw measurements (both measured velocities and accelerations) in our robust motion control scheme.

Our approach involves several key modifications. First, traditional Dob is redesigned, leveraging angular velocities and linear acceleration data directly obtained from the onboard encoders and IMU. By incorporating these measurements, nonlinearities and disturbances are estimated more effectively. Second, the estimated disturbance data is fed back into the system, enabling compensation. As a result, the system’s behavior becomes linear. Third, in the outer loop, we design a fuzzy logic controller optimized for performance. This controller ensures that the system responds as desired to track 6-DOF trajectories in the task space. Lastly, we construct a simulation environment that includes non-idealities, closely emulating real-world conditions. Through this setup, we validate the effectiveness of our proposed technique. By combining these modifications, we enhance the robustness and feasibility of the DOb for complex aerial manipulators.

This paper is structured as follows: Section 2 provides a description of the robot under consideration. Sections 3, 4 review the kinematics and dynamics analysis of the proposed system, respectively. Section 5 formulates and presents the control system design. Section 6 introduces the simulation results obtained using MATLAB/SIMULINK. Finally, Section 7 highlights the main conclusions.

2 Description of the proposed aerial manipulation system

A 3D computer-aided design (CAD) model for the proposed aerial manipulation system is illustrated in Figure 1. The manipulator and the quadrotor itself are the two integral components of this system. Figure 2 offers an illustration that highlights the relevant frames. Notably, these frames define a distinctive topology, enabling the end-effector to achieve arbitrary poses. To maintain consistency, we adhere to the Denavit-Hartenberg (DH) convention for frame transformations (Spong et al., 2020).

Figure 1
www.frontiersin.org

Figure 1. The proposed aerial manipulation system’s 3D CAD model.

Figure 2
www.frontiersin.org

Figure 2. Schematic diagram of the proposed aerial manipulation system with the related frames.

Two revolute joints with normal axes are incorporated into the manipulator. Parallel to the quadrotor’s body x-axis is the first revolute joint’s axis (z0), which is attached to the body of the quadrotor as shown in Figure 2. The second joint’s axis (z1) is parallel with the quadrotor’s body y-axis when the manipulator is in its fully extended home position. As a result, the end-effector can now pitch and roll independently of the quadrotor’s horizontal movement. Consequently, this new aerial system enables the manipulation of objects in any position and orientation. This non-redundant system enables the end-effector to achieve full 6-DOF motion using the minimum number of actuators and links, a critical consideration for flight applications. The suggested system sets itself apart from all previously documented systems by offering optimal mobility while maintaining a lightweight design. The increased complexity associated with inverse kinematics and control will be addressed subsequently to demonstrate the end-effector’s ability to accurately follow desired 6-DOF trajectories.

Regarding the quadrotor components, we deliberately select specifications to accommodate a payload of 500 g—exceeding the combined weight of the arm and the maximum payload. Our platform of choice is the Asctec Pelican quadrotor, with each rotor capable of generating a maximum thrust force of 6 N. This thrust capacity is determined through a rigorous identification process. The Asctec Pelican quadrotor incorporates an “asctec Autopilot” Flight Control Unit (FCU) and a modular design that facilitates the integration of various components, including position sensors, computer boards, and the manipulator with its associated avionics. The vehicle’s estimated attitude, magnetic orientation, body accelerations, angular velocities are all provided by the IMU that is a part of the FCU. By combining data from the onboard IMU with either laser/ultrasonic range finder or monocular vision data fusion, the system can estimate the quadrotor’s 6-DOF Achtelik et al. (2011).

The manipulator parts are designed, chosen, bought, and assembled with the goal of weighing no more than 200 g overall. The arm can extend to 22 cm and support a 200 g payload. Three DC motors are used: an HS-5485HB (0.70 N.m maximum torque) for the first joint, and another HS-422 (0.40 N.m maximum torque) for the second joint, an HS-422 (0.40 N.m maximum torque) for the gripper. A Motor Driver (SSC) serves as the intermediary interface between the primary control unit and the motors. Remote control commands for the manipulator’s motors are transmitted wirelessly using a PS2 R/C system. The encoder linked to each joint’s motor provides the angular position and speed of the joint. The interface between the onboard computer and the low-level devices (like PS2 wireless receiver, ultrasonic sensor, and motor driver (SSC)) is accomplished utilizing an Arduino Mega 2,560 board.

3 Kinematics analysis

3.1 Forward kinematics

Consider the body-fixed reference frame denoted as Σb, Ob- xbybzb, with its origin located at the quadrotor’s center of mass (as depicted in Figure 2). The position relative to the world-fixed inertial reference frame Σ, O- xyz, represented by the vector pb=[xyz]T. Additionally, Φb = [ψθϕ]T characterizes the orientation of the quadrotor. Rb is the rotation matrix that determines this orientation and can be given by

Rb=CψCθSϕSθCψSψCϕSψSϕ+CψSθCϕSψCθCψCϕ+SψSθSϕSψSθCϕCψSϕSθCθSϕCθCϕ,(1)

where the ZYX yaw-pitch-roll angles represented by the vector Φb = [ψθϕ]T. Note that S* and C* denote abbreviations for sine() and cosine() functions, respectively. Now, we will focus on the frame directly fastened to the manipulator’s end-effector and represented by Σe, O2- x2y2z2 (as depicted in Figure 2). Consequently, the position of Σe relative to the fixed world reference frame Σ can be provided by

pe=pb+Rbpebb,(2)

where pebb is the vector, expressed within the reference frame Σb, that denotes Σe’s position relative to Σb. Additionally, the rotation matrix that can be used to characterize the orientation of Σe is provided by

Re=RbReb,(3)

where Σe’s orientation with respect to Σb is specified by the rotation matrix Reb.

Finding the operational task coordinates χe=[xeyezeψeθeϕe]T based on the coordinates of the joint or vehicle space, denoted as q=[xyzψθϕθ1θ2]T, is the challenge of forward kinematics. Eight variables, q, make up the input for the forward kinematics, while six variables, χe, are generated from a series of six algebraic equations to make up the output. Equation 2 may be used to determine the end-effector’s position. Furthermore, it is possible to get the end-effector’s Euler angles, Φe, from Re as illustrated in Equation 3.

3.2 Inverse kinematics

Finding the coordinates of the joint or vehicle space, denoted as q based on the operational task coordinates χe, is the challenge of inverse kinematics. The robot’s control depends on the inverse kinematics solution, which makes it possible to determine the quadrotor’s required movements and the manipulator joints’ angles in order to position the end effector at a specified location and orientation. The end effector’s rotations can be described using various methods, one of which is the Euler angles Slabaugh (1999). T2I is the overall transformation matrix that connects the inertial world frame and the end effector frame. It is defined by

T2I=ABIA0BA10A21(4)

As a function of the end effector variables χe, specify this transformation matrix’s general format as shown below

Tee=r11r12r13xer21r22r23yer31r32r33ze0001(5)

Since the objective is to get the inverse kinematics for the reset position, T2I in Equation 4 may be rewritten by substituting ϕ=θ=0 as follows

T2I=CψSθ2+Cθ1Cθ2SψCψCθ2Cθ1SψSθ2SψSθ1X+L1Cθ1Sψ+L2CψSθ2+L2Cθ1Cθ2SψSψSθ2CψCθ1Cθ2Cθ2Sψ+CψCθ1Sθ2CψSθ1YL1CψCθ1+L2SψSθ2L2CψCθ1Cθ2Cθ2Sθ1Sθ1Sθ2Cθ1ZL0L1Sθ1L2Cθ2Sθ10001(6)

Using this equation, we can deduce the inverse kinematics for the system. Based on the formulation in Equation 6, the process begins with determining the inverse orientation, which is then succeeded by the calculation of inverse position. The inverse orientation encompasses three cases, outlined as follows.

CASE 1. Assume that neither r13 nor r23 is equal to zero. From Equation 6, we conclude that sin(θ1) is not equal to zero and that r33 is not equal to ±1. Therefore, it follows that cos(θ1)=r33 and sin(θ1)=±1r332, leading to the conclusion

θ1=atan2±1r332,r33(7)
ψ=atan2±r13,r23(8)
θ2=atan2±r32,r31(9)

Consequently, there are two possible solutions based on the selected sign for sin(θ1). In cases where r13 and r23 equal zero, the orthogonality of Tee indicates that r33 must be either +1 or 1.

CASE 2. When r13 = r23=0 and r33=1, it follows that cos(θ1) equals 1 and sin(θ1) equals 0, leading to θ1 being 0. In this scenario, based on the rotation matrix from Equation 6, the expression for θ2+ψ can be calculated as

θ2+ψ=atan2r11,r12(10)

We can assign any value to ψ to determine θ2, resulting in an infinite number of solutions.

CASE 3. When r13=r23=0 and r33=1, it follows that cos(θ1)=1 and sin(θ1)=0, leading to θ1=π. In this scenario, from Equation 6, θ2ψ can be calculated using the equation

θ2ψ=atan2r11,r12(11)

Any value can be assigned to ψ to find θ2, resulting in an infinite number of potential solutions.

In both cases two and three, one might set ψ=0 to determine θ2. Ultimately, the inverse position can be established through

X=xeL1Cθ1Sψ+L2CψSθ2+L2Cθ1Cθ2Sψ(12)
Y=yeL1CψCθ1+L2SψSθ2L2CψCθ1Cθ2(13)
Z=zeL0L1Sθ1L2Cθ2Sθ1(14)

4 Dynamics analysis

Figure 3 presents a schematic diagram showing the effects of integrating a manipulator with a quadrotor. To analyze the dynamics of the manipulator, the Recursive Newton-Euler method (Tsai, 1999; Fanni and Khalifa, 2017) is employed to formulate the equations governing motion. Given that the quadrotor serves as the manipulator’s base platform, the initial angular and linear accelerations and velocities utilized in the Newton-Euler method are those of the quadrotor represented in its body frame. By considering the link (of length L0) that is attached to the quadrotor as the base link and implementing the Newton-Euler technique for the manipulator, one can derive the equations of motion for the manipulator. Also, the forces and moments generated by the manipulator that influence the quadrotor can be obtained.

Figure 3
www.frontiersin.org

Figure 3. Effects of integrating a manipulator with a quadrotor.

The quadrotor platform is considered a rigid and symmetrical body. Similarly, each manipulator link is assumed to be rigid. The dynamic behavior of the manipulator is described by

M1qθ̈1+N1q,q̇,q̈=τm1,(15)
M2qθ̈2+N2q,q̇,q̈=τm2,(16)

where τm1 and τm2 represent the torques generated by the manipulator’s actuators. The terms M1(q), M2(q), N1(q,q̇,q̈), and N2(q,q̇,q̈) introduce nonlinearities into the system and are functions of the system’s states (q, q̇), and accelerations χb̈. The dynamic behavior of the quadrotor, incorporating the force and torque contributions from the manipulator, was determined using the Newton-Euler formulation. These equations are expressed as follows

mẍ=TCψSθCϕ+SψSϕ+Fm,qx(17)
mÿ=TSψSθCϕCψSϕ+Fm,qy(18)
mz̈=mg+TCθCϕ+Fm,qz(19)
Ixϕ̈=θ̇ϕ̇IyIzIrθ̇Ω̄+Ta1+Mm,qϕb(20)
Iyθ̈=ψ̇ϕ̇IzIx+Irϕ̇Ω̄+Ta2+Mm,qθb(21)
Izψ̈=θ̇ϕ̇IxIy+Ta3+Mm,qψb(22)

where Fm,qx, Fm,qy, and Fm,qz indicate the forces applied by the manipulator on the quadrotor along the x, y, and z axes in the inertial frame, respectively. Likewise, Mm,qϕb, Mm,qθb, and Mm,qψb refer to the moments produced by the manipulator around the xb, yb, and zb axes of the quadrotor’s body frame.

The parameters in Equations 1722 are described as follow. The quadrotor’s total mass is denoted by m. Each rotor j possesses an angular velocity Ωj. As a result, it generates both thrust force Fj and drag moment Mj, which can be expressed as follows

Fj=KfjΩj2,(23)
Mj=KmjΩj2,(24)

where Kfj and Kmj correspond to the thrust and drag coefficients for rotor j, respectively.

The four rotors’ combined thrust is symbolized by T and provided by

T=j=14Fj.(25)

The control torques around the quadrotor’s body axes xb, yb, and zb are indicated by Ta1, Ta2, and Ta3, respectively. They are provided by

Ta1=dF4F2,(26)
Ta2=dF3F1,(27)
Ta3=M1+M2M3+M4.(28)

d is the perpendicular distance between each rotor’s rotation axis and the centre of mass of the quadrotor. The rotor speed vector Ω̄ is defined as follows:

Ω̄=Ω1Ω2+Ω3Ω4.(29)

The rotor’s inertia is represented by Ir. Under the assumption that the vehicle exhibits symmetry along the xb, yb, and zb axes, the inertia matrix of the quadrotor relative to its body frame is denoted by If. The mathematical depiction of the aerial manipulation system’s dynamic model is outlined as

Mqq̈+Cq,q̇q̇+Gq+dex=Bu,(30)

The matrix M, an 8×8 symmetric positive definite matrix, encapsulates the inertia characteristics of the combined system. The Coriolis and centrifugal effects are represented by the matrix CR8×8, while the gravitational forces are captured in the 8-dimensional vector G. External disturbances acting on the system are aggregated in the vector dexR8. The actuator inputs are organized into the 6-dimensional control vector u=[F1F2F3F4τm1τm2]TR6. The input matrix B=H(q)N(Kfj,Kmj,d) maps the actuator inputs to the generated body forces and moments. The control matrix N has the following structure

N=000000000000111100γ1γ2γ3γ400d0d0000d0d00000010000001,(31)

where γj=Kmj/Kfj. Also, the body input forces are converted to be represented in Σ by the matrix HR8×8, as follows

H=RbO3O2O3TbTRbO2O2×3O2×3I2.(32)

By analyzing the translational dynamic part of Equations 1719, the following second-order nonholonomic constraint equations can be derived

sinϕẍfSψÿfCψẍf2+ÿf2+z̈f2=0,(33)
tanθẍfCψ+ÿfSψz̈f=0,(34)

where ẍf = ẍFm,qxm, ÿf = ÿFm,qym, and z̈f = z̈+gFm,qzm.

It is important to highlight that the force terms in the equations mentioned previously are function of the states of the system and their derivatives. By substituting the desired trajectories of the other variables into Equations 33, 34, the desired trajectories for ϕ and θ can be determined.

It is worth mentioning that the dynamics of the actuators are much faster than the dynamics of the aerial manipulation system. So, they can be neglected.

Wind dynamics, τw, may be viewed as external disturbances, hence it is inherently included in the dex term. Wind dynamics, τw, may be modelled as follows Hsu (2011), Viktor et al. (2015):

Average wind speed is computed by

Vwz=Vwz0zz0,(35)

where Vwz represents the wind speed at altitude z, whereas Vwz0 represents the recorded wind speed at altitude z0.

To replicate wind disturbances, calculate the wind force, Fw, which affects the platform rather than the wind speed. The force may be calculated using

Fw=0.61AeVwz2,(36)

where 0.61 is used to convert the wind speed to pressure, and Ae is the quadrotor’s impact effective area, which is determined by its construction and orientation. This force may be projected on the frame Σ as

Fwx=f1z2sinθ+f2z2cosθ,Fwy=f3z2sinϕ+f4z2cosϕ,(37)

where f1=0.61Ae1(Vwz0z0)2cos(ψw), f2=0.61Ae2(Vwz0z0)2cos(ψw), f3=0.61Ae1(Vwz0z0)2sin(ψw), f4=0.61Ae2(Vwz0z0)2sin(ψw), ψw denotes the wind direction angle, whereas Ae1 and Ae2 are determined by the quadrotor’s design parameters.

5 Controller design

We wish to accomplish the following objectives by designing the control input τ:

1. System Linearization: The external disturbances and nonlinearities of the system are estimated by utilizing measurement data directly obtained from onboard sensors. This guarantees that the error in estimation, τ̃dis=τdisτ̂dis converges to zero as time progresses to infinity.

2. Robust Stability: In spite of uncertainties, external disturbances, and measurement noise, the robotic manipulation system maintains stability and robustness.

3. Trajectory Tracking The deviation in the position of the end-effector tends to diminish to zero as time progresses towards infinity.

Our suggestion for a control strategy is to use a modified DOb and fuzzy logic controller to meet these control objectives. In this approach, system uncertainties, nonlinearities, and external disturbances (τdis) are regarded as disturbances. These disturbances are estimated using angular velocity and linear acceleration measurements (τ̂dis) and are eliminated by the DOb. This allows the system to be viewed as linear Single Input Single Output (SISO) plants. Consequently, the outer loop employs a fuzzy logic controller to generate τdes in order to acquire the required system performance.

5.1 DOb loop

Figure 4 illustrates a block diagram for the DOb controller in the inner loop, which will later facilitate the creation of a robust control system for the intended aerial manipulation system. It is widely known that the IMU can directly capture the quadrotor’s angular rates and linear accelerations. Moreover, joint angular velocities can be obtained using an encoder. Consequently, two separate DOb loops are utilized, one utilizing the measured velocity and the other utilizing the detected acceleration.

Figure 4
www.frontiersin.org

Figure 4. Block diagram of the proposed DOb and fuzzy logic controller.

In Figure 4, the expression Mn=MnaO3×5O5×3MnvR8×8 denotes the nominal inertia matrix of the system. Here, MnaR3×3 represents the nominal inertia associated with accelerations p̈b, whereas MnvR5×5 corresponds to the nominal inertia related to velocities Φ̇b and Θ̇. The variables τ and τdes indicate the current and desired inputs to the robotic system, respectively. The matrix Q(s)=diag([g1s+g1gis+gig8s+g8])R8×8 functions as the low-pass filter matrix for the DOb, with Qa(s)=diag([g1s+g1g3s+g3]), and Qv(s)=diag([g4s+g4g8s+g8]). The matrix P=diag([g1gig8]) indicates the bandwidth for the ith variable of q, while Pv=diag([g4gig8]) pertains to the portion related to velocity. Additionally, the term τdis reflects the disturbances affecting the system, encompassing Coriolis, centrifugal, and gravitational influences, while τ̂dis=[τ̂adisTτ̂vdisT]T denotes the estimated disturbances within the system.

The system disturbance, τdis, can be considered as

τdis=MqMnq̈+τd,τd=Cq,q̇q̇+Gq+dex.(38)

The control input, τ, shown in Figure 4 can be determined as

τ=Mnq̈des+τ̂dis,(39)

where

τ̂dis=QτMnq̈.(40)

When the DOb operates flawlessly, it can be presumed that all external and internal disturbances are accurately estimated and mitigated (i.e., τ̂dis=τdis). As a result, the relationship between the input to the DOb loop (τdes) and the output of the robotic manipulator is described as

Mnq̈=τdes.(41)

Given Mn is a diagonal matrix, the system can be considered as multi-decoupled linear SISO systems, as

Mniiq̈i=τides,(42)

or more straightforwardly in the acceleration space as

q̈i=q̈ides.(43)

The final step in designing the DOb-based controller is to develop the tracking controller in the DOb outer loop. A fuzzy logic controller for the system described in Equation 43 is selected.

5.2 Fuzzy logic controller

In recent times, fuzzy logic control has emerged as a viable substitute for traditional control algorithms in controlling complex processes (Sridharan, 2022; Rzayev et al., 2023; Baharuddin and Basri, 2023; Lara Alabazares et al., 2021; Hosseinpour and Martynenko, 2022). It offers an effective approach for developing controllers by utilizing heuristic data, making it suitable for various challenging control applications. Additionally, it combines the benefits of conventional controllers with the expertise of human operators. This paper introduces the design of an intelligent controller for an aerial manipulation system, utilizing MATLAB simulation (Simulink).

A fuzzy logic controller is composed of three main components: the Fuzzification module, Inference Engine and Rule Base, and Defuzzification module (Siddique and Siddique, 2014). The process of obtaining a set of fuzzy membership values from a crisp input value is referred to as fuzzification. To facilitate a seamless mapping of the system, the membership functions should have some degree of overlap. Fuzzy rules, crucial for representing knowledge and past experiences in fuzzy logic, are expressed as conditional statements of the form: If <condition>, Then <action>.

The inference engine involves assessing fuzzy rules to generate an output corresponding to each rule (Kovacic and Bogdan, 2018; Domingos et al., 2016). The output from the fuzzification module, which reflects the degree of membership functions of the input fuzzy sets pertaining to the current state of the process, is compared against each rule’s antecedent to determine a match degree for every rule. This match degree influences the adjustment of the control output variable specified in the rule’s consequent. Composition refers to the integration of the results from all the rules. The result of the combination process is a clipped fuzzy set that signifies the fuzzy values of the control output variable. Following the fuzzy reasoning, we obtain a linguistic output variable that must be converted into a precise crisp value. The goal is to obtain a singular crisp numeric value that most accurately reflects the inferred fuzzy values of the linguistic output variable. Defuzzification effectively translates the output from the fuzzy domain back into the crisp domain.

In Figure 4, fuzzy logic controllers have been developed to manage the position of every joint in the aerial manipulation system. These controllers utilize a similar set of inputs, which include the error e, the difference between the target and actual joint position, and the rate of change of this error de.

Each fuzzy logic controller employs five symmetric triangular membership functions with linguistic labels of Negative Big NB, Negative Small NS, Zero ZR, Positive Small PS, and Positive Big PB to represent input and output values. These membership functions are overlapped as shown in Figure 5. To achieve the desired performance, the scaling factors for the error Kei, change of error Kdei, and fuzzy output Kui of each FLC were carefully tuned.

Figure 5
www.frontiersin.org

Figure 5. Membership functions of the fuzzy logic controllers.

The fuzzy logic controllers share an identical rule base, provided in Table 1, crafted to function as a PD-like fuzzy logic controller. The Mamdani fuzzy inference approach is utilized, employing a min-max operator for aggregation and the center of gravity technique for defuzzification.

Table 1
www.frontiersin.org

Table 1. Rule base of the fuzzy logic controllers.

5.3 Stability analysis

Control input, τ, is provided as

τ=11QsMnq̈desQsMnq̈=Mnq̈des+MnPev,ev=q̇desq̇.(44)

The application of this control law leads to

Mqėv+Cq,q̇ev+Kvev=δ,Kv=PMn,(45)

where

δ=ΔMqq̈des+Cq,q̇q̇des+Gq+dex,ΔMq=MqMn.(46)

The following may be used to establish the stability of the inner loop:

Consider a Lyapunov function as

V=12evTMqev.(47)

This function has the following time derivative

V̇=evTMqėv+12evTṀqev.(48)

When Equation 48 is substituted with Equation 45,

V̇=evTδevTKvev+12evTṀq2Cq,q̇ev.(49)

This proof will use the dynamic equation of motion’s properties Equation 30. These properties are From et al. (2014), Spong et al. (2020):

property 1

λminν2νTMqνλmaxν2,(50)

property 2

νTṀq2Cq,q̇ν=0,(51)

where νR8 denotes an 8-dimensional vector, and the positive real constants λmin and λmax represent the minimum and maximum eigen values of the matrix M(q).

When Equation 51 is substituted, Equation 49 becomes

V̇=evTδevTKvev.(52)

The property Equation 50 yields

V̇γV+2Vλmin|δ|,γ=2Kvλmax.(53)

Based on the analysis in Sadegh and Horowitz (1990), the analysis is concluded as follows.

After division of Equation 53 by V0.50, we get

ddtV0.5+0.5γV0.52λmin|δ|,(54)

Multiplying Equation 54 by e0.5γ and performing integration yields

V0.5e0.5γtV0.50,ev0+Vc,,(55)

with

Vc=12λmin0te0.5γtι|δι|dι,(56)

where ι is a dummy variable representing time in the integral. It ranges from 0 to t (current time).

Vc can be rewritten in the form

Vc=12λmine0.5γt|δt|.(57)

Applying the .p, where p is the norm order, leads to

Vcp=12λmine0.5γtδtp.(58)

Hence

Vcp=12λmine0.5γt1δtp.(59)

Since e0.5γt1 = 0.5γ, it follows that

Vcp=0.5γ12λminδtp.(60)

Consequently, Equation 55 becomes

V0.5pe0.5γtV0.50,ev0p+0.5γ12λminδtp.(61)

Through simplification, Equation 61 becomes

evp1γ+2λmin2pγ1pV0,ev0δp.(62)

Let Lp refers to the space of signals with finite .p. Therefore, the error dynamics is Lp input/output stable with respect to the pair (δ, ev) for all p[1,] with the assumption that the system states, q and q̇, are bounded.

Lemma 1.

The fuzzy system’s global asymptotic stability is guaranteed, supported by a Lyapunov function proof in Tanaka and Wang (2004).

Lemma 2. (Ioannou and Sun, 2012). Let

e=HFLCev,(63)

where HFLC is exponentially stable. Then evLp implies that eLp and ėLp.

6 Simulation results

In this section, MATLAB/SIMULINK is utilized to simulate the previously suggested control technique for managing the aerial manipulation system under consideration.

6.1 Simulation environment

To ensure a realistic simulation, we have established the following setup and made specific assumptions:

Our model is based on real data obtained from experimental tests Fanni and Khalifa (2017). The identified parameters are provided in Table 2.

We access to the quadrotor’s linear and angular positions, as well as its velocities, at a 1 KHz sampling rate. Similarly, the manipulator joints’ positions and velocities are accessible at a 1 KHz sampling rate.

To account for real-world conditions, we introduce measurement noise. Specifically, we add normally distributed noise to the measured signals, with a mean 103 and 5×103 standard deviation.

Our controller computes outputs at a 1 KHz sampling rate.

To assess robustness against model uncertainties, we introduce a step disturbance in the control matrix N (representing actuators’ losses) at 15 s. The disturbance assumes that the elements are 90% of their true values (i.e., a 10% error).

A time-varying wind disturbance has been added. Figure 6a depicts a simulation of the wind angle profile, ψw. Figure 6b shows that the wind speed Vwz0 has two components: a constant portion and a random variable portion to imitate gust effects (sudden and unpredictable variations in wind speed).

Finally, the end-effector is tasked with picking up a 150 g payload at 15 s and releasing it at 55 s.

Table 2
www.frontiersin.org

Table 2. Parameters of the new aerial manipulation system.

Figure 6
www.frontiersin.org

Figure 6. Profile of the wind: (a) angle, and (b) speed.

6.2 Results and discussion

A comparison of the proposed controller (DOb-FLC) to a DOb-PD controller is achieved. For the conducted simulation experiment, the actual response of the quadrotor space coordinate [x,y,z,ϕ,θ,ψ] is illustrated in Figure 7. While the actual response of the manipulator’s joints space coordinate [θ1,θ2] is presented in Figure 8. These figures demonstrate the feasibility of the new aerial manipulation system. Furthermore, they show that the quadrotor/joint space trajectories remain within the joints’ limits and do not breach the quadrotor/joints motion constraints. Also, they prove that the proposed controller is capable of effectively tracking the desired trajectories and rapidly correcting errors. The DOb-PD controller, on the other hand, has a steady state error and a limited ability to perform good trajectory tracking, particularly when faced with practical challenges. Thus, these results show that the proposed controller outperforms the DOb-PD controller’s response.

Figure 7
www.frontiersin.org

Figure 7. The actual response for the quadrotor space: (a) x, (b) y, (c) z, (d) ϕ, (e) θ, and (f) ψ

Figure 8
www.frontiersin.org

Figure 8. The actual response of the manipulator’s joints: (a) θ1, and (b) θ2

Additionally, Figure 9 demonstrates that the necessary efforts u from the actuators in the case of DOb-FLC, including the motor torque for each manipulator joint and the thrust force needed from each rotor, remain within the permissible range. The identification process determined that each rotor produces a maximum thrust force of 6 N. According to the motors’ data sheet, the motor for joint 1 has a permissible input torque of 0.7 N.m, while joint 2 has a permissible input torque of 0.4 N.m. Consequently, it can be argued that the desired control goals are accomplished through the implementation of this motion control strategy.

Figure 9
www.frontiersin.org

Figure 9. The required control efforts in case of DOb-FLC.

Figure 10 illustrates the system’s response in the task space, where forward kinematics is utilized to compute the end effector’s actual position and orientation. This figure highlights the proposed method’s capability to precisely follow the desired 6-DOF end-effector trajectories, even when faced with practical challenges such as measurement noise, wind disturbances, and payload pickup or release. On the other hand, the DOb-PD controller has a steady state error and is less capable of performing good trajectory tracking, especially when faced with practical challenges. Therefore, it can be concluded that the proposed motion control approach is successful in meeting the control objectives.

Figure 10
www.frontiersin.org

Figure 10. The actual response for the task space: (a) xe, (b) ye, (c) ze, (d) ϕe, (e) θe, and (f) ψe

6.3 Limitations and future extensions

The current study has some limitations that should be acknowledged. First, while the controller is designed for joint-space operation, most practical applications require accurate trajectory tracking in task space (rather than point-to-point) to ensure effective environmental interaction. Second, the control strategy is based on precise onboard positioning systems. Third, while the DOb assures bounded estimating error, this error does not equal zero, which may have an influence on performance in challenging environments that involve significant disturbances.

To address these limitations and expand upon this work, several promising research directions emerge. Future research should focus on experimental validation to evaluate the controller’s performance under realistic situations. The development of task-space control techniques, particularly sensor-based systems for direct environmental interaction, should be a priority. The disturbance estimating technique might be improved with algorithm enhancements targeted at either reaching zero estimate error or drastically reducing its bounds. These extensions would significantly improve the system’s practical applicability and performance.

7 Conclusion

For a quadrotor manipulation system, this paper investigates the challenge of more efficient and reliable robust linearization and control. The description of a new aerial manipulation system, consisting of a quadrotor vehicle and a 2-DOF manipulator that has a unique topology, is introduced. This unique topology enables the system to achieve 6-DOF trajectory tracking with a minimal number of actuators. Kinematics and dynamics analysis are investigated in detail. A modified DOb is utilized to ensure robust response by mitigating disturbances, noise in measurements, and mismatches between the actual plant and its model. In contrast to traditional approaches, the DOb uses measurement data from the encoders and IMU to estimate disturbances. Following this, the outer loop implements a fuzzy logic controller to attain the desired control objectives and closed-loop performance with minimal computational load. Stability analysis of the proposed controller is presented. The suggested control system was carefully tested using MATLAB/SIMULINK simulations. A comparison of the proposed controller to a DOb-PD controller is provided. The results show that the proposed controller outperforms the DOb-PD controller’s response. The results indicate precise trajectory tracking across all 6-DOF, even under diverse disturbances. The proposed controller maintains stable operation during payload handling while working within strict actuator limitations—specifically, rotor thrust remains below 6 N and joint torques remain below 0.7 N m (Joint 1) and 0.4 N m (Joint 2). These data verify the control strategy’s robustness and computational efficiency. In future work, the proposed system will undergo experimental testing.

Data availability statement

The raw data supporting the conclusions of this article will be made available by the authors, without undue reservation.

Author contributions

AlK: Conceptualization, Data curation, Formal Analysis, Funding acquisition, Investigation, Methodology, Project administration, Resources, Software, Supervision, Validation, Visualization, Writing – original draft, Writing – review and editing. SS: Writing – review and editing, Data curation, Supervision, Conceptualization, Formal analysis, Investigation, Funding acquisition, Resources, Software. AhK: Conceptualization, Data curation, Formal Analysis, Funding acquisition, Investigation, Methodology, Project administration, Resources, Software, Supervision, Validation, Visualization, Writing – original draft, Writing – review and editing.

Funding

The author(s) declare that no financial support was received for the research and/or publication of this article.

Acknowledgments

The authors extend their appreciation to Northern Border University, Saudi Arabia, for supporting this work through project number (NBU-CRP-2025-289).

Conflict of interest

The authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Generative AI statement

The author(s) declare that no Generative AI was used in the creation of this manuscript.

Publisher’s note

All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article, or claim that may be made by its manufacturer, is not guaranteed or endorsed by the publisher.

References

Achtelik, M., Achtelik, M., Weiss, S., and Siegwart, R. (2011). “Onboard imu and monocular vision based control for mavs in unknown in-and outdoor environments,” in 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 09-13 May 2011 (IEEE), 3056–3063.

CrossRef Full Text | Google Scholar

Baharuddin, A. D., and Basri, M. A. M. (2023). Self-tuning PID controller for quadcopter using fuzzy logic. Int. J. Robotics Control Syst. 3, 728–748. doi:10.31763/ijrcs.v3i4.1127

CrossRef Full Text | Google Scholar

Choi, H.-T., Kim, S., Choi, J., Lee, Y., Kim, T.-J., and Lee, J.-W. (2014). “A simplified model based disturbance rejection control for highly accurate positioning of an underwater robot,” in Oceans-St. John’s, St. John's, NL, Canada, 14-19 September 2014 (IEEE), 1–5.

Google Scholar

Domingos, D., Camargo, G., and Gomide, F. (2016). Autonomous fuzzy control and navigation of quadcopters. IFAC-PapersOnLine 49, 73–78. doi:10.1016/j.ifacol.2016.07.092

CrossRef Full Text | Google Scholar

Fanni, M., and Khalifa, A. (2017). A new 6-dof quadrotor manipulation system: design, kinematics, dynamics, and control. IEEE/ASME Trans. Mechatronics 22, 1315–1326. doi:10.1109/tmech.2017.2681179

CrossRef Full Text | Google Scholar

From, P. J., Gravdahl, J. T., and Pettersen, K. Y. (2014). Vehicle-manipulator systems. Springer.

Google Scholar

Hosseinpour, S., and Martynenko, A. (2022). Application of fuzzy logic in drying: a review. Dry. Technol. 40, 797–826. doi:10.1080/07373937.2020.1846192

CrossRef Full Text | Google Scholar

Hsu, S. (2011). Verifying wind profile equations under hurricane conditions. Open Ocean Eng. J. 4, 60–64. doi:10.2174/1874835x01104010060

CrossRef Full Text | Google Scholar

Ioannou, P., and Sun, J. (2012). Robust adaptive control courier corporation. Cour. Corp.

Google Scholar

Khalifa, A., and Fanni, M. (2017). A new quadrotor manipulation system: modeling and point-to-point task space control. Int. J. Control, Automation Syst. 15, 1434–1446. doi:10.1007/s12555-015-0467-3

CrossRef Full Text | Google Scholar

Khalifa, A., Fanni, M., and Khalifa, A. (2024). Sensorless contact force estimation and robust impedance control for a quadrotor manipulation system. Sci. Rep. 14, 28772. doi:10.1038/s41598-024-79606-6

PubMed Abstract | CrossRef Full Text | Google Scholar

Khalifa, A., Fanni, M., and Namerikawa, T. (2016a). “Hybrid acceleration/velocity-based disturbance observer for a quadrotor manipulation system,” in 2016 IEEE Conference on Control Applications (CCA), Buenos Aires, Argentina, 19-22 September 2016 (IEEE), 556–561.

CrossRef Full Text | Google Scholar

Khalifa, A., Fanni, M., and Namerikawa, T. (2016b). “Mpc and dob-based robust optimal control of a new quadrotor manipulation system,” in 2016 European Control Conference (ECC), Aalborg, Denmark, 29 June 2016 - 01 July 2016 (IEEE), 483–488.

CrossRef Full Text | Google Scholar

Khamseh, H. B., Janabi-Sharifi, F., and Abdessameud, A. (2018). Aerial manipulation—a literature survey. Robotics Aut. Syst. 107, 221–235. doi:10.1016/j.robot.2018.06.012

CrossRef Full Text | Google Scholar

Kovacic, Z., and Bogdan, S. (2018). Fuzzy controller design: theory and applications. CRC Press.

Google Scholar

Lara Alabazares, D., Rabhi, A., Pegard, C., Torres Garcia, F., and Romero Galvan, G. (2021). Quadrotor uav attitude stabilization using fuzzy robust control. Trans. Inst. Meas. Control 43, 2599–2614. doi:10.1177/01423312211002588

CrossRef Full Text | Google Scholar

Li, G., Liu, X., and Loianno, G. (2024). Rotortm: a flexible simulator for aerial transportation and manipulation. IEEE Trans. Robotics 40, 831–850. doi:10.1109/tro.2023.3336320

CrossRef Full Text | Google Scholar

Li, S., Yang, J., Chen, W.-h., and Chen, X. (2016). Disturbance observer-based control: methods and applications. CRC Press.

Google Scholar

Meng, X., He, Y., and Han, J. (2020). Survey on aerial manipulator: system, modeling, and control. Robotica 38, 1288–1317. doi:10.1017/s0263574719001450

CrossRef Full Text | Google Scholar

Ollero, A., Tognon, M., Suarez, A., Lee, D., and Franchi, A. (2022). Past, present, and future of aerial robotic manipulators. IEEE Trans. Robotics 38, 626–645. doi:10.1109/tro.2021.3084395

CrossRef Full Text | Google Scholar

Orsag, M., Korpela, C., Bogdan, S., and Oh, P. (2017). Dexterous aerial robots—mobile manipulation using unmanned aerial systems. IEEE Trans. Robotics 33, 1453–1466. doi:10.1109/tro.2017.2750693

CrossRef Full Text | Google Scholar

Orsag, M., Korpela, C., Oh, P., Bogdan, S., and Ollero, A. (2018). Aerial manipulation. Springer.

Google Scholar

Ruggiero, F., Lippiello, V., and Ollero, A. (2018). Aerial manipulation: a literature review. IEEE Robotics Automation Lett. 3, 1957–1964. doi:10.1109/lra.2018.2808541

CrossRef Full Text | Google Scholar

Rzayev, R., Habibbayli, T., and Aliyev, M. (2023). “The use of fuzzy controllers in automatic control systems for quadcopters,” in Proceedings of SAI intelligent systems conference (Springer), 59–74.

Google Scholar

Sadegh, N., and Horowitz, R. (1990). Stability and robustness analysis of a class of adaptive controllers for robotic manipulators. Int. J. Robotics Res. 9, 74–92. doi:10.1177/027836499000900305

CrossRef Full Text | Google Scholar

Sariyildiz, E., and Ohnishi, K. (2014). “A guide to design disturbance observer based motion control systems,” in 2014 International Power Electronics Conference (IPEC-Hiroshima 2014-ECCE-ASIA), Hiroshima, Japan, 18-21 May 2014 (IEEE), 2483–2488.

CrossRef Full Text | Google Scholar

Siddique, N., and Siddique, N. (2014). Fuzzy control. Springer.

Google Scholar

Slabaugh, G. G. (1999). Computing euler angles from a rotation matrix. Retrieved on August 6, 39–63.

Google Scholar

Spong, M. W., Hutchinson, S., and Vidyasagar, M. (2020). Robot modeling and control. John Wiley and Sons.

Google Scholar

Sridharan, M. (2022). Short review on various applications of fuzzy logic-based expert systems in the field of solar energy. Int. J. Ambient Energy 43, 5112–5128. doi:10.1080/01430750.2021.1927839

CrossRef Full Text | Google Scholar

Tanaka, K., and Wang, H. O. (2004). Fuzzy control systems design and analysis: a linear matrix inequality approach. John Wiley and Sons.

Google Scholar

Tian, Y., Shi, Y., Shao, X., Hu, Q., Yang, H., and Zhu, Z. H. (2024). Spacecraft proximity operations under motion and input constraints: a learning-based robust optimal control approach. IEEE Trans. Aerosp. Electron. Syst. 60, 7838–7852. doi:10.1109/taes.2024.3419763

CrossRef Full Text | Google Scholar

Tomić, T., and Haddadin, S. (2014). “A unified framework for external wrench estimation, interaction control and collision reflexes for flying robots,” in 2014 IEEE/RSJ international conference on intelligent robots and systems, Chicago, IL, USA, 14-18 September 2014 (IEEE), 4197–4204.

CrossRef Full Text | Google Scholar

Tsai, L.-W. (1999). Robot analysis: the mechanics of serial and parallel manipulators. Wiley-Interscience.

Google Scholar

Tutsoy, O., Asadi, D., Ahmadi, K., and Nabavi-Chasmi, S.-Y. (2023). Robust reduced order thau observer with the adaptive fault estimator for the unmanned air vehicles. IEEE Trans. Veh. Technol. 72, 1601–1610. doi:10.1109/tvt.2022.3214479

CrossRef Full Text | Google Scholar

Viktor, V. S., Valery, F. I., Yuri, Z. A., Shapovalov, I., and Beloglazov, D. (2015). Simulation of wind effect on a quadrotor flight. ARPN J. Eng. Appl. Sci. 10, 1535–1538.

Google Scholar

Wei-hong, X., Li-jia, C., and Chun-lai, Z. (2021). Review of aerial manipulator and its control. Int. J. Robotics Control Syst. 1, 308–325. doi:10.31763/ijrcs.v1i3.363

CrossRef Full Text | Google Scholar

Xilun, D., Pin, G., Kun, X., and Yushu, Y. (2019). A review of aerial manipulation of small-scale rotorcraft unmanned robotic systems. Chin. J. Aeronautics 32, 200–214. doi:10.1016/j.cja.2018.05.012

CrossRef Full Text | Google Scholar

Nomenclature

b Body-fixed reference frame

World-fixed inertial reference frame

pb Position relative to Σ, represented by [xyz]T

Φb Orientation vector [ψθϕ]T (ZYX yaw-pitch-roll angles)

Rb Rotation matrix from body frame to world frame

e Frame attached to manipulator’s end-effector

pe Position of Σe relative to Σ

pebb Position of Σe relative to Σb, expressed in Σb

Re Rotation matrix of Σe

Reb Rotation matrix specifying orientation of Σe w.r.t Σb

χe Operational task coordinates

q Vehicle/joint space coordinates

θi joint i angle of the manipulator (i=1,2)

L0 Length of link attached to quadrotor (base link)

L1 Length of first manipulator link

L2 Length of second manipulator link

m Quadrotor’s total mass

Ωj Angular velocity of rotor j (j=1,2,3,4)

Fj Thrust force of rotor j

Mj Drag moment of rotor j

Kfj Thrust coefficient for rotor j

Kmj Drag coefficient for rotor j

T Total thrust

d Perpendicular distance from center of mass to rotor axis

Ω̄ Rotor speed vector

Ir Inertia of the rotor

Ix,Iy,Iz Quadrotor moments of inertia about body axes

M(q) System inertia matrix

C(q,q̇) Matrix of Coriolis and centrifugal terms

G(q) Vector of gravity terms

dex Vector of external disturbances

u Actuator input vector

B Input matrix

N Control matrix

H Transformation matrix for body input forces to Σ

τmi Torque on manipulator joint i (i=1,2)

Fm,qx Manipulator force on quadrotor along x

Fm,qy Manipulator force on quadrotor along y

Fm,qz Manipulator force on quadrotor along z

Mm,qϕb Manipulator moment about xb

Mm,qθb Manipulator moment about yb

Mm,qψb Manipulator moment about zb

τdis System disturbances

τ̂dis System disturbances

τ̂dis System estimated disturbances

Mn Nominal inertia matrix

Q(s) DOb low-pass filter matrix

P Bandwidth matrix

gi Low-pass filter bandwidth of ith variable

ψw Wind angle

Vwz Wind speed at altitude z

Fw Wind disturbance force

Ae Quadrotor’s effective impact area

e Error signal in fuzzy controller

de Rate of change of the error

Keywords: aerial manipulation, dynamics, disturbance observer, fuzzy logic controller, kinematics, quadrotor

Citation: Khalifa A, Shaaban SM and Khalifa A (2025) Hybrid disturbance observer and fuzzy logic controller for a new aerial manipulation system. Front. Robot. AI 12:1528415. doi: 10.3389/frobt.2025.1528415

Received: 14 November 2024; Accepted: 02 June 2025;
Published: 07 July 2025.

Edited by:

Shaoming He, Beijing Institute of Technology, China

Reviewed by:

Önder Tutsoy, Adana Science and Technology University, Türkiye
Barış Can Yalçın, University of Luxembourg, Luxembourg
Fatemeh Nasr Esfahani, Lancaster University, United Kingdom

Copyright © 2025 Khalifa, Shaaban and Khalifa. This is an open-access article distributed under the terms of the Creative Commons Attribution License (CC BY). The use, distribution or reproduction in other forums is permitted, provided the original author(s) and the copyright owner(s) are credited and that the original publication in this journal is cited, in accordance with accepted academic practice. No use, distribution or reproduction is permitted which does not comply with these terms.

*Correspondence: Alaa Khalifa, YWxhYS5raGFsaWZhQGVsLWVuZy5tZW5vZmlhLmVkdS5lZw==

Disclaimer: All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article or claim that may be made by its manufacturer is not guaranteed or endorsed by the publisher.