Next Article in Journal
Multi-Level Contextual and Semantic Information Aggregation Network for Small Object Detection in UAV Aerial Images
Previous Article in Journal
Autonomous Underwater Vehicle Adaptive Altitude Control Framework to Improve Image Quality
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Flybbit: Design and Control of a Novel Rabbit-like Flying Robot

1
College of Electronic and Information Engineering, Tongji University, Caoan Road 4800, Shanghai 201804, China
2
Shanghai Research Institute for Intelligent Autonomous Systems, Tongji University, Caoan Road 4800, Shanghai 201804, China
*
Author to whom correspondence should be addressed.
Drones 2025, 9(9), 609; https://doi.org/10.3390/drones9090609
Submission received: 2 July 2025 / Revised: 20 August 2025 / Accepted: 27 August 2025 / Published: 29 August 2025
(This article belongs to the Section Drone Design and Development)

Abstract

In this paper, we present the design and control of a novel aerial vehicle inspired by the biomechanics of a rabbit named “Flybbit”. Flybbit consists of two main components, namely a movable “Ears” part and a rigid “Body” part, forming a composite flying system with five controllable degrees of freedom (DOFs). The “Ears” part is equipped with two tiltable motors paired with optional-sized propellers, enabling additional thrust generation and flight stability maintenance, and the “Body” part incorporates four fixed motors, analogous to a rabbit’s limbs, to provide the primary propulsion. To fully exploit the actuation capability, we derive the system dynamics and introduce a dynamic control allocation method with an adaptive strategy to mitigate actuator saturation during complex combined maneuvers. Furthermore, we analyze the differential flatness property and develop a nonlinear inverse dynamics controller enhanced with hybrid external wrench estimation, enabling accurate trajectory tracking in five DOFs. Flybbit supports both manual operation via RC and autonomous flight via onboard computation. Comprehensive simulations and real-world experiments validate the proposed design and control framework.

1. Introduction

The technology of multirotor unmanned aerial vehicles (UAVs) has undergone significant advancements over the past decade. Driven by the rapid evolution of integrated circuit technology, multirotor systems have achieved a progressive reduction in size while simultaneously enhancing computational power, stability, and endurance. Furthermore, leveraging their vertical take-off and landing (VTOL) and hovering capabilities, multirotor UAVs have been widely investigated and deployed as aerial platforms for physical interaction tasks, including wall painting [1,2], item transportation [3,4], and industrial destruction [5,6,7], broadening the workspace of traditional ground-based robots.
However, most planar multirotor vehicles (e.g., quadrotor and hexarotor) are underactuated, i.e., their degrees of freedom (DOFs) in Euclidean space are coupled and can only generate thrust along the normal vector. A typical example is that a quadrotor requires coupled pitch or roll rotational movements to achieve horizontal translations, which makes it challenging to perform higher-dimensional tasks in space. In recent studies, two primary approaches have been proposed to address this problem. (1) Integration of lightweight manipulators with additional DOFs involves creating a new unmanned aerial manipulator (UAM) system to compensate for the missing DOFs of the planar vehicle itself. In [8], the development and evolution of UAM systems over recent years are comprehensively summarized and presented, while [9,10] provides a more comprehensive analysis of the differential flatness of UAM systems and offers a generalized, dynamically feasible task space planning method. (2) Designing novel multirotor configurations increases the controllable DOFs. One approach is to redesign the geometry and orientation of fixed-tilt motors [11,12], enabling independent control of the six DOFs and fully decoupling translational and rotational dynamics. Another approach incorporates tiltable servos attached to motors [13,14,15], where servo tilting provides additional directional thrust, achieving partial decoupling of dynamics to increase the dimensionality of the configuration space.
Another significant challenge arises when employing traditional underactuated planar vehicles for target tracking or swarm tasks. As these tasks heavily rely on a fixed-body stereo camera, which is used for both simultaneous localization and mapping (SLAM) and target recognition, they thus inevitably face the problem of a limited field of view (FOV). Aggressive translational motion is more likely to cause excessive attitude tilting, which leads to the loss of effective information within the FOV, ultimately causing task failure. Although the authors of [16] proposed a yaw-based active position correction system to address the inter-agent localization problem in swarm tasks under a limited FOV, it fails to account for additional planning in the pitch direction, thus not solving the problem of losing tracking capability during high-speed horizontal motion.
In this paper, we present the design of a novel rabbit-like flying robot named “Flybbit”, which is shown in Figure 1. Mimicking the posture of a real rabbit, Flybbit can be divided into two sections: the “Ears” and the “Body”, The “Ears” section employs a tiltable motor mechanism, where the propeller size can be flexibly chosen according to a mission’s requirements, providing additional forward thrust and balance control during motion. The “Body” section features four fixed motors resembling the four limbs of a rabbit, which supply the primary propulsion for aerial flight. Unlike a conventional quadrotor, Flybbit possesses five independently controllable DOFs, with an additional DOF enabling decoupled control in the pitch direction. As mentioned in [10], having at least two independent rotational angle controls (e.g., yaw and pitch) is sufficient to achieve a nearly omnidirectional FOV. Compared with the five-DOF multirotor vehicle presented in [14], the Flybbit actuator design is also redundant, providing a substantial energy margin for aggressive maneuvers.
Since the Flybbit remains underactuated, it is necessary to design a cascaded controller comprising a position outer-loop control and an attitude inner-loop control. The primary challenge lies in selecting appropriate configuration variables to determine the dimensionality of the control inputs and computing the input for the attitude controller. In [17], a solution was proposed for a quadrotor by ingeniously applying the concept of differential flatness. Furthermore, previous approaches to modeling vehicle dynamics often neglected the random propeller disturbances and hard-modeled air resistance, which are typically assumed to be external disturbances. Inspired by the impedance control approach in [18,19], we directly treat all of these factors as external wrenches, i.e., forces and torques. First, we design an estimator to compute the external wrenches solely based on IMU measurements. These estimated values will be reintegrated into the control law design to improve the accuracy of trajectory tracking. Both software-in-the-loop (SITL) and hardware-in-the-loop (HITL) simulations, as well as real-world flight experiments, are conducted to evaluate the performance of the Flybbit system and the proposed algorithms.
The primary contributions of this paper are as follows:
  • We design a novel underactuated flying robot named “Flybbit”, featuring a unique hybrid multirotor configuration that integrates both tiltable and fixed-angle propellers. This structure enables five controllable degrees of freedom (3D position, 2D pitch, and yaw attitude) and combines the maneuverability of tiltrotors with the stability of fixed-rotor systems.
  • We develop a comprehensive dynamic model and propose a dynamic adaptive control allocation strategy to address actuator saturation during complex combined maneuvers. Specifically, the five-DOF system’s differential flatness is analyzed to facilitate trajectory planning and control.
  • We implement a nonlinear inverse dynamics controller based on hybrid external wrench estimation, with explicit handling of attitude singularities. The full system is validated through hardware-in-the-loop and real-world experiments and supports both RC-based manual operation and fully autonomous flight.
Figure 2 and Table 1 provide a comparative analysis of the structural designs and performance characteristics of recently developed multirotors featuring diverse configurations. It can be observed that recent multirotor designs aiming to increase the number of controllable DOFs generally follow two main approaches. The first is employing fixed-tilt rotor orientations such that the resultant wrench vectors are synthesized in multiple directions. While this design is relatively simple in its architecture, it often leads to increased energy consumption and shorter flight endurance. The second approach is equipping rotors with tiltable servo mechanisms, which enables each rotor thrust vectors in multiple directions. This design offers improved endurance but at the cost of increased mechanical complexity and higher requirements for servo actuator and controller performance.
In contrast, the proposed Flybbit adopts a hybrid configuration that combines both fixed-tilt and tiltable rotors, effectively leveraging the structural simplicity of the former and the control versatility of the latter. This design not only improves controller performance but also introduces actuation redundancy, which is beneficial for fault tolerance and complex maneuvering. As shown in Table 1, while many existing platforms adopt impedance or admittance control for interaction tasks or simple PID control for motion tasks, our nonlinear inverse dynamics controller (NIDC) is specifically designed for agile flight. By incorporating system dynamics and external wrench disturbances, it offers improved tracking accuracy and robustness. Furthermore, unlike many existing studies that rely solely on real-world experiments, we establish a hardware-in-the-loop (HITL) simulation platform prior to flight testing. This allows for comprehensive validation of both the flight control software and hardware components, significantly reducing experimental risks and development costs.

2. System Design

In this section, we first introduce the overall design of the proposed Flybbit, including its mechanical structure, individual components, and physical properties. The modeling is divided into two main components, including the dynamics model and control allocation model. We also derive the differential flatness property of Flybbit, demonstrating that it is a five-DOF underactuated system, which benefits the design of the motion controllers and trajectory planners.

2.1. Overall Design

The mechanical structure of Flybbit is also divided into two main components: the “Ears” and “Body”. In the “Body” section, four brushless motors are arranged in an “X” configuration. In the “Ears” section, each motor is mounted on a tiltable base driven by a servo motor, providing an independent rotational DOF. We adopted an “asymmetric” propulsion system design; larger propellers (5 inches) were selected for the “Body” to provide the primary propulsion and enhance the robot’s dynamic capabilities, while the propeller size on the “Ears” is more flexible, e.g., 3 inches or 4 inches, chosen to grant more aggressive forward thrust and maneuverability or to reduce the energy consumption.
Furthermore, to enable agile tracking of aggressive trajectories, the design of Flybbit prioritizes a compact and lightweight form factor while integrating essential sensors. The flight control unit (FCU) of the vehicle is a Pixhawk 6c Mini. For the actuators, brushless motors are driven by Dshot600 electronic speed controllers (ESCs), while the servo motors mounted between the brushless motor and arm are directly controlled by 50 Hz PWM signals from the FCU. Additionally, a low-latency ESP32 WiFi telemetry radio is utilized for wireless communication with a ground computer, enabling data transmission and reception of external control commands, and a remote receiver is employed in manual mode to process joystick inputs. The hardware configuration is illustrated in Figure 3, with the final prototype of Flybbit measuring 210 × 210 × 180 mm and weighing only 0.89 kg. Table 2 details the weight distribution of each component.

2.2. Modeling of Flybbit

Three coordinate frames are utilized in this paper: the world frame W , the body frame B , and the motor frame R i . As shown in Figure 4, all these frames are represented using the north- east down (NED) system. We assume that Flybbit operates in a uniform gravitational field, and the mass distribution is assumed to be rigid and constant such that the center of mass (COM) and center of gravity (COG) are effectively equivalent and interchangeable. The origin of the body frame is fixed at the COM of the vehicle, with the + x B axis initially aligned with the forward direction of the vehicle. The initial orientation of all motor frames is aligned with that of the body frame, and the rotational angle θ i of motors 1–2 around the + y R i axis is defined as the positive direction of rotation. More complete descriptions of the symbols and definitions used in modeling are expressed in Table 3.

2.2.1. COM Calculation

The COM of Flybbit does not coincide with its geometric center. We treat the “Ears” and “Body” as single rigid bodies fixed together. By establishing a coordinate frame with the geometric center as the origin, we can compute the offset vector r COM R 3 between the COM and the geometric center:
r C O M = m b o d y r b o d y + m e a r s r e a r s m b o d y + m e a r s .

2.2.2. Dynamics Model

The state of the vehicle is represented by x = { p , v , R , ω } , where p = [ p x , p y , p z ] T and v = [ v x , v y , v z ] T represent the position and velocity of the vehicle, respectively, in the world frame. R denotes the rotation matrix of the body frame B relative to the world frame W , and ω = [ ω x , ω y , ω z ] T represents the angular velocity in the body frame. We also define the Tait–Bryan rotation sequence Z Y X . The Euler angles describing the system’s orientation are expressed as Θ = { ψ , θ , ϕ } , where ψ , θ , and ϕ represent the yaw, pitch, and roll angles, respectively. Any minor interactions resulting from assembly tolerances or actuation are considered negligible, and the vehicle is modeled as a single rigid body with a total mass m and an inertia tensor J , with the translational and rotational dynamics expressed in the Newton–Euler form as follows:
p ˙ = v , v ˙ = g + R f a + R f e / m , R ˙ = R S ( ω ) , ω ˙ = J 1 ω × J ω + τ a + τ e ,
where f a = [ f a , x , f a , y , f a , z ] T and τ a = [ τ a , x , τ a , y , τ a , z ] T represent the control forces and torques generated by the vehicle’s actuators expressed in body frame, respectively. We consider modeling errors, rotor disturbances, propeller gyroscopic torques, aerodynamic drag, and other factors that are difficult to accurately model as unified external disturbances. These external forces and torques are represented by the generalized external force h e = [ f e , τ e ] , where f e = [ f e , x , f e , y , f e , z ] T and τ e = [ τ e , x , τ e , y , τ e , z ] T , with both expressed in the body frame and regarded as external disturbances. In Section 3.1, we will design a specialized estimator to compute these external wrenches in real time, which will be used in the nonlinear controllers.

2.2.3. Nonlinear Control Allocation

The desired force and torque control inputs must be generated by the motors and servo actuators. To achieve this, we establish a nonlinear control allocation model for Flybbit in the body frame, which is described by the following equation:
f a = i = 0 N f i R i a i , τ a = i = 0 N f i p i × R i a i k m i f i R i a i ,
where f i represents the thrust generated by the ith rotor, a i = [ 0 , 0 , 1 ] T denotes the direction of the thrust in the rotor frame, p i indicates the geometric position of the ith rotor relative to the COM, and R i represents the attitude of the rotor frame relative to the body frame. For rotors 1–2, R i = R y ( θ i ) , while for rotors 3–6, R i = E 3 is the identity matrix. In addition, k m i denotes the torque coefficient of the rotor i, which defines the linear relationship between the rotor’s generated thrust and the reactive torque, with counterclockwise (CCW) rotation taken as positive and clockwise (CW) rotation taken as negative. The rotors’ geoometry is expressed as [ p x i , p y i , p z i ] T . In our design, the “Ears” section uses smaller propellers compared with the “Body” section. As a result, rotors 1–2 have smaller k m i values compared with rotors 3–6.
Following the approach of decomposing the thrust generated by tiltable rotors used in [22], for tiltable rotors 1–2, we decompose the generated thrust into vertical and lateral components, expressed as f i sin ( θ i ) and f i cos ( θ i ) in Figure 5, respectively. By expanding and rearranging Equation (3), we can express it in matrix form as follows:
f a τ a = M u , u = f 1 sin θ 1 , f 1 cos θ 1 , f 2 sin θ 2 , f 2 cos θ 2 , f 3 , f 4 , f 5 , f 6 , M = 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 1 1 1 1 1 k m 1 p y 1 k m 2 p y 2 p y 3 p y 4 p y 5 p y 6 p z 1 p x 1 p z 2 p x 2 p x 3 p x 4 p x 5 p x 6 p y 1 k m 1 p y 2 k m 2 k m 3 k m 4 k m 5 k m 6 ,
where in the 8 × 1 actuator vector, u , u 1 4 express the nonlinear coupling terms generated by the tiltable “Ears”, and u 1 = f 1 sin θ 1 and u 3 = f 2 sin θ 2 denote the projections of the thrust generated by the two “Ears” rotors onto the body frame’s x b axis, which provide the fundamental actuation for forward and backward horizontal motion. In contrast, u 2 = f 1 cos θ 1 and u 4 = f 2 cos θ 2 represent their projections onto the body frame’s z b axis, which together with the fixed motor thrust u 5 8 = f 3 6 contribute to the vertical motion. Simultaneously, we define the 6 × 8 constant matrix M as the control effectiveness matrix.
As we have extracted the time-varying trigonometric components sin ( θ i ) and cos ( θ i ) to the actuator vector u , the matrix M is composed entirely of constant geometric parameters and actuator configuration terms. As the rank of the matrix is rank ( M ) = 5 6 , the designed Flybbit therefore possesses five independent DoFs in Euclidean space that can be controlled and input, classifying our vehicle design as underactuated, in accordance with the classification for multirotors presented in [8]. Furthermore, since the rank of the control efficiency matrix is 5 (i.e., 5 < 8 ), which is less than the number of actuators, the Flybbit is also redundantly actuated. To establish the relationship between the desired force and torque commands obtained from the controller and the output control commands for the motors and servos, a common method is to define the pseudo-inverse as follows:
M = M ( M M T ) 1 ,
As described in [11], the actuator input commands can further be expressed as follows:
u = M f a τ a ,
where u represents the least squares solution. Additionally, through trigonometric calculations, we decouple the motor and servo commands for the “Ears” section from the components f i sin ( θ i ) and f i cos ( θ i ) as follows:
a i = f i sin θ i , b i = f i cos θ i , f i = a i 2 + b i 2 , θ i = tan 1 a i b i .
It is worth noting that when solving for the tilt angle θ i based on the decomposed thrust component f i , a singularity may arise in the case where f i = 0 . In such scenarios, the direction of the tilt becomes underdetermined, leading to an infinite number of possible solutions for θ i , which can cause numerical instability and actuator saturation. To address this issue, we introduce a simple yet effective engineering approach by defining a small dead zone threshold, where δ > 0 . Specifically, when | f i | < δ , the corresponding tilt mechanism is held at its previous angle, avoiding unnecessary and rapid oscillations caused by small fluctuations around zero thrust. This strategy ensures smooth behavior from the tilt actuators near singular points while preserving the controller’s overall responsiveness and stability.
For the servo motors, the control command could be directly expressed as the angle θ i , while for the motors, by defining the thrust coefficient C T , we can establish a quadratic function relating the motor speed command to the thrust as f i = C T i · w i 2 . Here, C T i is a dimensionless thrust coefficient that characterizes the aerodynamic efficiency of the rotor and defines the proportional relationship between the square of the motor angular speed and the generated thrust. Then, we can easily solve for the motor speed command w i as w i = ( f i / C T i ) .
The specific values of C T i need to be determined through parameter identification methods, considering the actual motor types and propeller sizes used.

2.2.4. Dynamic Adaptive Strategy for Actuator Saturation

The design of redundant actuators provides Flybbit with the necessary power to freely perform both translational and rotational motion in space. Upon real measurement, only relying on the “Body” section can still achieve a thrust-to-weight ratio of at least 5.47, which indicates that the power system of Flybbit has a sufficient energy margin to perform aggressive aerial maneuvers.
However, actuator redundancy does not eliminate the possibility of actuator saturation. Upon further analysis of the control effectiveness matrix of Flybbit, it can be observed that the control thrust along the x axis of the body frame f x is entirely generated by the horizontal component f i sin ( θ i ) of the tilting thrust in the “Ears” section, which is also used to generate the control torques along the y and z axes τ y and τ z , respectively. Consider a scenario where Flybbit is commanded to move along the x axis with high acceleration. This could easily lead to saturation of the tilting motor speed and the servo angle of the tilting actuators in the “Ears”. If, at the same time, a yaw rotation along the z axis is commanded, then there will be less of a force margin available to control this motion, which could result in tracking control failure.
To address the issue of actuator saturation during aggressive or combined translational and rotational maneuvers, and to further enhance the system’s control performance, we propose a dynamic adaptive control allocation strategy based on the controller output feedback.
Starting from the actuator allocation relationship described in Equation (4), we reorganize the total control force and torque in the following block matrix form:
f a τ a = M 11 M 12 M 21 M 22 u ears u body ,
where f a R 3 and τ a R 3 denote the desired total force and torque in the body frame B and u ears , u body R 4 represent the control inputs of the ear-mounted and body-mounted actuators, respectively. All submatrices M i j R 3 × 4 are constant matrices determined solely by the geometric configuration and actuator placement, as discussed earlier.
To avoid actuator overload in the z-axis torque, which is particularly prone to saturation due to the structural symmetry and dynamic coupling, we introduce a dynamic redistribution strategy. Specifically, we redefine the last row of the torque equation (corresponding to τ a , z ) as follows:
τ a , z = w ( a t ) M 21 ( 3 , : ) u ears + 1 0.5 w ( a t ) M 22 ( 3 , : ) u body , w ( a t ) = 1 2 + 1 2 cos ( a t a x , m a x π ) , a t = a x ( t ) [ 0 , a x , m a x ] , a x , m a x = ς · ( f 1 , m a x + f 2 , m a x ) m t o t a l .
where w ( a t ) acts as a dynamic weighting function, continuously adjusting the relative torque contributions of the “Ears” and “Body” actuator groups based on the instantaneous control demand. The variable a t represents the desired linear acceleration on the x axis of the body frame obtained directly from the control output. This choice ensures that aerodynamic drag and controller objectives are taken into account, unlike using estimated system acceleration a e s t , x , which may not fully reflect external disturbances.
The cosine-shaped profile of w ( a t ) guarantees a smooth transition of torque distribution between the “Ears” and “Body” actuator groups, preventing abrupt control switching and helping to avoid actuator saturation in extreme forward and backward acceleration scenarios. The scalar factor ς ( 0 , 1 ) serves as a tunable safety margin for estimating the saturation threshold a x , max . This adaptive strategy effectively enhances tracking robustness while preserving actuator availability, especially during high-speed translational maneuvers.
It is worth noting that in typical multicopter powertrain design, it is recommended to reserve approximately 20–30% of the total thrust capacity as a safety margin for aggressive maneuvering and disturbance rejection. Operating near the actuator saturation limit reduces control flexibility and increases the risk of instability. Therefore, in our implementation, we conservatively set the weight threshold at ς = 1 30 % = 70 % of the maximum available thrust from the two tiltable rotors, ensuring sufficient headroom for reliable control performance under high dynamic conditions, and the final dynamic control allocation is dynamically updated at a lower frequency of 10 Hz based on control output feedback, minimizing computational resource usage.

2.3. Differential Flatness

For a system with differential flatness, it means that we can find some flat outputs such that the system’s states and inputs can be uniquely represented by these flat outputs and their derivatives. The differential flatness of a standard quadrotor and a bicopter system has been thoroughly demonstrated in previous works [25,26], where both systems have a four-dimensional flat output represented by σ = [ x , y , z , ψ ] , corresponding to the position and yaw angle.
The flat space and input space have the same dimension [9]. From the rank of the control allocation matrix for our Flybbit, we can observe that its input space is represented by the vector v = [ f x , f z , τ x , τ y , τ z ] , where f x and f z are the control forces along the body’s x axis and z axis, respectively, and τ x , τ y , and τ z are the control torques around the roll, pitch, and yaw, respectively. This input vector v is directly generated by the combined outputs of the position and attitude controllers and transformed into a unified representation in the body frame B from the world frame W, ensuring that each element reflects a control command that can be realized by the system actuators. Therefore, we select five differential independent flat outputs as follows:
σ = [ x , y , z , ψ , θ ] ,
The position, velocity, and acceleration states can be directly expressed as the derivatives of the first three flat output components σ , σ ˙ , a n d   σ ¨ , respectively. The next step is to demonstrate that the rotation matrix R representing the attitude is also a function of the flat outputs.
Since we have defined the Euler angles’ rotation sequence as Z Y X , we decompose the rotation into two steps as shown in Figure 6. The first rotation is calculated from the known flat output variables ψ and θ , and the second rotation is a rotation around the newly generated coordinate axis X B by ϕ , as expressed by the equation
R 1 ( ψ , θ ) = R ( ψ ) R ( θ ) , R 2 ( ϕ ) = R ( ϕ ) , R = R ( ψ ) R ( θ ) R ( ϕ ) = R 1 ( ψ , θ ) R 2 ( ϕ ) .
Given the yaw and pitch angles, we can express the direction vector X C as follows:
X C = R ( ψ ) R ( θ ) e 1 = [ cos ψ cos θ , sin ψ cos θ , sin θ ] .
For Flybbit, the thrust that can be generated is always in the XOZ plane. We use f B to represent the direction vector along the thrust direction:
f B = t | | t | | , t = σ ¨ 1 , σ ¨ 2 , σ ¨ 3 g .
Since the direction vector X C is also the rotation axis for the second rotation, it does not change during the rotation. As both the thrust vector f B and the direction vector X C are in the body frame’s XOZ plane, we can determine Y B and Z B as follows:
X B = X C , Y B = X B × f B X B × f B , Z B = X B × Y B X B × Y B ,
Provided that | | X B × f B | | 0 , we can uniquely determine the body frame’s current attitude rotation matrix R B as follows:
R B = X B , Y B , Z B ,
For the singularity where X B and f B coincide in the case of Flybbit, this will be handled specifically in the controller’s attitude resolution part.
Given the current attitude rotation matrix, the final roll angle of the Euler angles will also be uniquely determined, and the Euler angles can be rewritten as a function of Θ ( σ 2 ) , representing a function formed by the second derivatives of the flat outputs. Then, the angular velocity can also be solved as follows:
ω = W 1 ( Θ ) Θ ˙ , where Θ ˙ = ( Θ ) σ ( 2 ) σ ( 3 ) .
The net thrust f a and torque τ a of the vehicle, expressed in the body frame, can be directly computed from the Newton–Euler dynamic model in Equation (2) and are also functions formed by the flat outputs and their derivatives. It is particularly noted that for the generalized external wrenches not considered, these external wrenches are treated as known variables by estimation and will not affect the system’s differential flatness property. As any flat system is controllable based on the foundational propositions in differential flatness theory [27], the controllability of the proposed Flybbit platform is inherently guaranteed under normal flight conditions.
After proving the differential flatness of Flybbit, we can select the five flat outputs as the desired input variables for the controller. Any five-DOF smooth trajectory planned in the flat space, subject to reasonable bounded constraints, is dynamically feasible and can be tracked well by Flybbit.

3. Controller Design

The principal objective of the control design is to enable the underactuated Flybbit system, with its five controllable DOFs, to accurately track smooth and feasible trajectories defined in flat space. This requires the controller to effectively accommodate actuator limitations and mitigate external disturbances, thereby ensuring robust and precise flight performance.
In this section, we propose a nonlinear cascaded control strategy for underactuated Flybbit to track smooth trajectories precisely. Specifically, we design an external wrench estimator that relies solely on IMU measurements to dynamically estimate and compensate the system disturbance dynamics for controlling.

3.1. Hybrid External Wrench Estimation

We leverage the raw angular velocity and linear acceleration measurements provided by the IMU integrated within the used Pixhawk 6C Mini flight controller and, in conjunction with the vehicle’s dynamics model, use them to indirectly infer the external disturbances acting on the system. These disturbance estimates are computed in real time and incorporated as dynamics feedforward compensation terms within the control law presented in Section 3.2. As a result, the controller can instantaneously adjust actuator commands, generating additional forces and torques to mitigate the effect of external disturbances and maintain stable flight performance. We divide the hybrid external wrench estimator into the following two components.

3.1.1. Momentum-Based External Torque Estimation

The vehicle’s angular momentum is represented by I = J ω . By taking the derivative of I and substituting it into the rotational dynamics in Equation (2), we have
I ˙ = J ω ˙ = τ a + τ e ω × J ω .
We define a residual vector as follows:
τ ^ e = K i [ J ω τ a + τ ^ e ω × J ω d t ] ,
where K i R 3 × 3 is a positive definite diagonal observation matrix. Differentiating Equation (18) again results in the residual dynamics:
τ ^ ˙ e = K i τ e K i τ ^ e .
It can be observed that K i also represents the gain of the first-order filter applied to the angular velocity measurements, which balances noise attenuation and responsiveness in estimating the external torque τ e .

3.1.2. Acceleration-Based External Force Estimation

By rearranging the translational dynamics in Equation (2), the true external force can be directly expressed as follows:
f e = m R 1 ( a g ) f a .
Considering that the acceleration measured by the accelerometer a is subject to noise, we apply a first-order filter to obtain the estimated dynamics:
f ^ ˙ e = K j f e K j f ^ e .
By substituting Equation (20) into Equation (21) and integrating both sides of the equation, we finally obtain
f ^ e = K j m R 1 ( a g ) f a f ^ e .
where K j R 3 × 3 is also a positive definite diagonal observation matrix. Since ω and R 1 ( a g ) are the IMU measurements in the body frame, the hybrid external wrench estimation method allows the use of a single IMU without any additional measurement units or differential operations.
It should be noted that while the proposed method estimates external force using only IMU-based acceleration, the effect of integration drift is negligible over short durations. However, to ensure robustness in long-term operations, the acceleration input is obtained from an EKF2-based sensor fusion framework that incorporates additional measurements (e.g., GPS, Vicon, and optical flow) as shown in Figure 7, thereby mitigating drift and enhancing estimator reliability.
In the actual implementation, Equations (18) and (22) are discretized using a sampling frequency of 100 Hz. A first-order forward difference method is employed for numerical implementation due to its simplicity and sufficient accuracy under high sampling rates. Specifically, the external wrench estimator follows the discrete-time update rule:
h e [ k ] = a i / j h ^ e [ k 1 ] + ( 1 a i / j ) h e [ k ] , a i / j = 1 1 + K i / j T s .
where the coefficient a i / j ( 0 , 1 ) is related to the observer gain through a i / j = 1 / ( 1 + K i / j T s ) , with T s = 0.01 s being the sampling period.
The observer gains are set as K i = diag ( 10.0 , 10.0 , 10.0 ) and K j = diag ( 5.0 , 5.0 , 5.0 ) , denoting the observer gain. When K i = 10 , we obtain a i = 0.909 , and for K j = 5 , a j = 0.952 . These values ensure that the poles of the discrete system lie within the unit circle, thus maintaining observer stability. The choice of gains reflects a balance between noise attenuation and responsiveness to external disturbances.

3.2. Nonlinear Inverse Dynamics Control

Given that Flybbit is a five-DOF underactuated system, its translational and rotational dynamics are partially coupled. Similar to the control design for other underactuated models (e.g., quadrotors), we need to design a cascaded controller structure that separates position control from attitude control. The proposed control architecture is illustrated in Figure 7. Initially, the position controller computes the desired forces, and together with the given yaw and pitch setpoints, the desired attitude is resolved. The desired torques are then generated by the inner loop controller to track the desired attitude. Ultimately, the motor speeds and servo angle commands are determined through control allocation and transmitted to the actuators for execution.

3.2.1. Outer-Loop Position Control

We define the vehicle’s position controller in the world frame. For a high-precision motion tracking controller, the ideal error dynamics take the form of a second-order system:
e p = p p d , e ˙ p = p ˙ p ˙ d , e ¨ p + K d e ˙ p + K p e p = 0 , where K d , K p > 0 .
where e p is the position error. K d and K p are the damping and spring coefficients, respectively, which ensure the closed-loop system’s stability. By substituting the translational dynamics Equation (2) into (23), the control law for the desired thrust is given by
f a W = R B f a = m ( p ¨ des g + K d e ˙ p + K p e p ) R B f e .
This control law can be decomposed into three main components: the feedforward term for the known, desired acceleration, the PD feedback term for the trajectory tracking error, and the inverse dynamics compensation term for gravity and the external generalized forces.
Since Flybbit can only generate thrust on the XOZ plane of the body frame, we project the desired control force expressed in the world coordinate system into the current body frame, selecting the x-axis and z-axis components while neglecting the y-axis component, which then becomes the input for the actual control allocation:
f a , des B = R 1 f a , des W , f a , des B = f a , d e s ( x ) , 0 , f a , d e s ( z ) .
Once the desired thrust f a , des expressed in world frame is computed, the desired attitude can also be derived based on the expected yaw and pitch angles ψ ( t ) and θ ( t ) , respectively, of the desired trajectory in the flat space as follows from the differential flatness derived in the previous chapter:
f B , des = f a , des w f a , des w , X B , des = cos ψ T sin θ T sin ψ T cos θ T sin θ T , Y B , des = X B , des × f B , des X B , des × f B , des , Z B , des = X B , des × Y B , des X B , des × Y B , des .
This gives the desired attitude rotation matrix R d e s .
Singularity: The condition X B × f B = 0 represents a singular point in the so(3) space. Near or across this singular point, small perturbations can cause drastic attitude changes. To address this, we use a conservative approach; whenever the system detects proximity to the singular point, we manually set the unit direction vector of the desired force to f B , des = [ 0 , 0 , 1 ] T in order to “push” the system away from the singularity and ensure a safe desired attitude for the inner loop controller.

3.2.2. Inner-Loop Attitude Control

We use a cascaded controller structure to track the desired attitude of the vehicle. Unlike the outer-loop position controller, all calculations in the inner loop are performed in the body frame. We define the attitude error vector as follows:
e R = 1 2 Vex R des T R R T R des ,
where the Vex ( · ) function denotes the operation of transforming the skew-symmetric matrix in so ( 3 ) into a vector in R 3 , as shown in [25]. Initially, we use proportional control to track the desired attitude:
ω des = ω ff + K R · e R ,
where the desired angular velocity is composed of a feedforward term ω ff derived from the trajectory generator and a proportional feedback term derived from the orientation error. Since angular velocity control is generally the lowest-level control loop in most flight control systems, it directly determines the stability and responsiveness of the vehicle. Finally, the desired torque in the body frame is computed as follows:
e ω = ω des ω , τ a B = K ω e ω + K I e ω d t + K D e ˙ ω τ e B .
where τ e B are external torques. Typically, the inner-loop attitude control bandwidth is set to be 4–10 times higher than the outer-loop position control bandwidth. Therefore, in the controller implementation, we set the angular velocity controller and control allocation to run at 650 Hz, while the attitude and position controllers run at 150 Hz.

3.2.3. Stability Analysis

To assess the stability of the proposed control architecture for five-DOF trajectory tracking, a formal Lyapunov-based analysis is conducted as follows.
Firstly, we choose the following Lyapunov candidate function for the translational subsystem:
V p = 1 2 e ˙ p e ˙ p + 1 2 e p K p e p ,
Consider Equation (24) to be the expression of the system’s closed-loop position dynamics funtion. The time derivative of Equation (31) can expressed as follows:
V ˙ p = e ˙ p e ¨ p + e p K p e ˙ p = e ˙ p ( K d e ˙ p K p e p ) + e p K p e ˙ p = e ˙ p K d e ˙ p 0 ,
Since K d > 0 , we have V ˙ p 0 , and V ˙ p = 0 only if e ˙ p = 0 . Thus, the translational subsystem is globally exponentially stable.
Secondly, since we have defined the attitude error using the rotation matrices as Equation (28), and the control torque is Equation (30), consider the Lyapunov function candidate for the rotational subsystem:
V r = 1 2 K R tr I R des T R + 1 2 e ω J e ω ,
where J is the moment of inertia matrix and K R > 0 is a positive definite diagonal gain matrix, expressed in Equation (29). By assuming the bounded external torque and neglecting the disturbance compensation error, we obtain
V ˙ r = e ω K ω e ω 0 .
By combining V p and V r , the closed-loop system is stable in the Lyapunov sense. Under ideal compensation and perfect model knowledge, the system achieves asymptotic convergence to the desired trajectory in flat space.

4. Experiments

4.1. Platform Preparations

In this work, all the algorithms we proposed were developed and integrated into generic autopilot firmware, enabling full migration and independent operation on almost all types of FCU hardware.
Flybbit was developed to be manually controlled in basic “Position/Altitude Mode” using RC sticks or by being connected to an extra computer for autonomous flight under “Offboard/Mission Mode”.
We also built a software-in-the-loop (SITL) and hardware-in-the-loop (HITL) experimental platform, as shown in Figure 8a. The stability, feasibility, and performance of Flybbit were first validated on this simulation platform to ensure real flight safety. All experiments were also conducted on both the simulation platform and the real-world platform to ensure reproducibility.

4.2. SITL and HITL Simulation Experiments

4.2.1. Five-DOF Manual Control Test

The primary difference between Flybbit and conventional multirotors lies in its decoupling of pitch control from the translational motion along the body frame’s forward direction. Therefore, we mapped an additional channel on the RC for independent control of the pitch angle. For RCs with auxiliary joysticks, one axis is used to smoothly control the vehicle’s pitch degree of freedom, as illustrated in Figure 8a. A “switch” or “button” can also be mapped to control this extra DOF. In Figure 8b–e, we demonstrate the manual control of Flybbit using an RC to control translational, yaw, and pitch movements. Further demonstrations of manual control using an RC under the “Position Mode” in the HITL simulation can be viewed in the video.

4.2.2. Circular Motion Trajectory Tracking Simulation

We designed two types of circular motion trajectories that shared identical position paths but differed in their attitude. These trajectories were tracked separately using an underactuated conventional quadrotor and our proposed platform in the SITL simulation environment in order to compare and demonstrate the unique 5-DOF capability of Flybbit. The circular motion trajectory function is predefined as follows:
Flybbit : 5 - DOFs x ( t ) = R cos ( ω t + π ) y ( t ) = R sin ( ω t + π ) z ( t ) = z 0 ( t ) ψ ( t ) = atan 2 ( y ( t ) , x ( t ) ) θ ( t ) = θ 0 ( t ) x ( t ) = R cos ( ω t + π ) y ( t ) = R sin ( ω t + π ) z ( t ) = z 0 ( t ) ψ ( t ) = atan 2 ( y ( t ) , x ( t ) ) Quadrotor : 4 - DOFs
Unlike the normal 4-DOF circular trajectory tracked by a quadrotor, the specific trajectory designed for Flybbit incorporates an additional independent pitch angle θ ( t ) , as shown in Equation (19). We defined a circular trajectory with a radius of R = 5 m and an altitude of z 0 ( t ) = 2 m while maintaining the yaw angle ψ ( t ) as constantly oriented toward the center of the circle. Specifically, for the Flybbit platform, several sets of fixed pitch angles θ ( t ) = 10 / 0 / 20 were periodically switched during flight to conduct the 5-DOF controllable validation, as illustrated in Figure 9.
As shown in Figure 9a, only the yaw angle of the quadrotor can be independently controllable, while its pitch angle is calculated using the local acceleration, as demonstrated in [17]. For the proposed Flybbit platform, the additional rotational degree of freedom has been decoupled, enabling the vehicle to maintain an arbitrary desired pitch angle during motion, as illustrated in Figure 9b,c. Figure 9d,e further demonstrates the performance of Flybbit in tracking trajectories under varying desired pitch angles, with the maximum horizontal velocity reaching 2.3 m/s. Owing to the presence of tiltable “Ears”, Flybbit achieved more saturated and precise yaw control compared with a conventional quadrotor. A more detailed presentation of the simulation results can be found in the accompanying video.

4.3. Tiltable “Ears” Performance Test

To better demonstrate the control performance enabled by the tiltable “Ears”, we define two operating modes of Flybbit: (1) Flybbit with tiltable Ears and (2) Flybbit without Ears (i.e., a conventional quadrotor equipped with two fixed “Ears”.) Based on the circular trajectory tracking task described in the previous section, we designed a mode-switch experiment to compare the trajectory tracking performance under these two configurations, thereby highlighting the advantages and value of incorporating tiltable Ears into the Flybbit design.
Figure 10a,b Visualizations of the corresponding force and torque sets. Compared with the configuration without Ears (i.e., a conventional quadrotor with fixed Ears), Flybbit with tiltable Ears achieved a higher-dimensional force set in the ZOX plane, demonstrating improved controllability and highlighting the benefits of the proposed design.
To further illustrate the impact of the tiltable “Ears” on flight control performance, we set the desired pitch angle to vary sinusoidally within the range of [ 10 , 10 ] . It can be clearly observed that in the mode with tiltable “Ears”, Flybbit attained fully controllable pitch dynamics. Moreover, the vehicle consistently maintained thrust allocation along the real-time body frame + x axis (i.e., the radial direction of the circular trajectory), which arose from the ability of the tiltable servos to effectively decompose thrust in the desired direction.
However, after switching to the fixed “Ears” mode, Flybbit lost the pitch DOF control of the desired circular trajectory, and the two ear motors ( f 1 , f 2 ) were only used to generate hovering thrust along the z axis and roll torque τ x . Figure 11b presents the time histories of the individual components of the actuator vector u during the process of switching between the two operating modes. It can be clearly observed that upon switching to the fixed “Ears” configuration, the ear servo output was constrained to θ 1 , θ 2 = 0 , while the ear rotors maintained constant values f 1 , f 2 = 2.5 N to sustain the vehicle’s hover thrust.
However, under identical controller gain settings, as shown by the root mean square error (RMSE) in Table 4, even with the additional controllable pitch DOF and mode switching, Flybbit equipped with tiltable “Ears” maintained trajectory tracking performance that was essentially consistent with the fixed “Ears” configuration, demonstrating that the proposed design does not compromise control effectiveness despite the added complexity. This highlights the robustness and versatility of the Flybbit control system.

4.4. Real Flight Trajectory Tracking Task

We preplanned an -shaped five-DOF smooth trajectory in a five-dimension flat space to validate the effectiveness of our proposed controller. As shown in Figure 12a, we mounted an optical flow sensor on Flybbit to provide accurate external position estimates. The planned trajectory points, precomputed on the ground computer, were sampled at a frequency of 20 Hz and wirelessly transmitted to the vehicle using a high-bandwidth, low-latency WiFi link during flight.
To comprehensively validate the effectiveness and robustness of our proposed control strategy, we designed and implemented a set of comparative experiments using three different controllers: a baseline PD controller, a cascaded P-PID controller, and our proposed nonlinear inverse dynamics controller.
All controllers were tested under identical reference trajectories, with the desired yaw angle fixed at 0 and the pitch angle set to 0 . As shown in Figure 12d and Table 5, our proposed controller achieved superior attitude stabilization, with maximum deviations of only 0 . 3129 in yaw and 1 . 0006 in pitch during the entire flight. This result highlights the strong orientation regulation capability of the Flybbit five-DOF control system.
The corresponding position tracking performance is illustrated in Figure 12c and Table 5. Our controller achieved a final RMSE of 0.2549 m, significantly outperforming the other two baselines in the trajectory tracking tasks. From Figure 12c, it can also be seen that the proposed controller exhibited a stronger disturbance rejection capability and maintained a higher tracking accuracy under gust disturbances.

5. Conclusions and Future Work

In this study, we presented the design, modeling, and control of a novel rabbit-inspired flying robot named “Flybbit”, featuring a composite structure with two tiltable “Ear” propellers and four fixed “Body” propellers. This configuration provides five controllable degrees of freedom, allowing independent control of the pitch and field-of-view decoupling during flight. To fully exploit the actuation capability, we developed a dynamic control allocation strategy with adaptive adjustment to mitigate actuator saturation, and we designed a nonlinear inverse dynamics controller enhanced by external wrench estimation for accurate five-DOF trajectory tracking. The proposed framework was validated through both simulations and real-world flight experiments.
In addition to its novelty in configuration and control design, “Flybbit” has promising applications in tasks requiring agile maneuverability and compact form factors, such as indoor inspection, human–robot interaction, and cooperative swarm operations in cluttered environments. In future work, we plan to enhance its onboard autonomy with vision-based perception and motion planning, enabling it to perform autonomous navigation and collaborative missions in real-world scenarios. As mentioned in Section 2.1, since the size of the “Ears” is configurable, we also plan to conduct further comparative and quantitative experiments to analyze their impact on the system’s dynamic response, energy efficiency, and maneuverability. We believe that these insights will guide further refinements to the control strategy, ultimately enhancing the system’s flight endurance and dynamic performance.

Author Contributions

Conceptualization, C.S.; Methodology, C.S.; Software, C.S.; Validation, C.S.; Writing—original draft preparation, C.S.; Writing—review and editing, R.S., Y.L., J.Z., F.G. and Q.Z.; Visualization, C.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Acknowledgments

The authors are grateful for the assistance of the Shanghai Artificial Intelligence Laboratory in China.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Korigodskii, A.A.; Kalachev, O.D.; Vasiunik, A.E.; Urvantsev, M.V.; Bondar, G.E. Flying Robotics Art: ROS-based Drone Draws the Record-Breaking Mural. In Proceedings of the 2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Abu Dhabi, United Arab Emirates, 14–18 October 2024; pp. 5964–5969. [Google Scholar]
  2. Susbielle, P.; Dumon, J.; Hably, A. Pointillism Wall Painting Drone Using Bouncing Frequency Control. IEEE Robot. Autom. Lett. 2025, 10, 4802–4809. [Google Scholar] [CrossRef]
  3. Mellinger, D.; Lindsey, Q.; Shomin, M.; Kumar, V. Design, modeling, estimation and control for aerial grasping and manipulation. In Proceedings of the 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems, San Francisco, CA, USA, 25–30 September 2011; pp. 2668–2673. [Google Scholar]
  4. Cao, H.; Shen, J.; Liu, C.; Zhu, B.; Zhao, S. Motion planning for aerial pick-and-place with geometric feasibility constraints. IEEE Trans. Autom. Sci. Eng. 2024, 22, 2577–2594. [Google Scholar] [CrossRef]
  5. Bodie, K.; Brunner, M.; Pantic, M.; Walser, S.; Pfändler, P.; Angst, U.; Siegwart, R.; Nieto, J. Active interaction force control for contact-based inspection with a fully actuated aerial vehicle. IEEE Trans. Robot. 2020, 37, 709–722. [Google Scholar] [CrossRef]
  6. D’Angelo, S.; Marcellini, S.; De Crescenzo, A.; Marolla, M.; Lippiello, V.; Siciliano, B. A Semi-Autonomous Aerial Platform Enhancing Non-Destructive Tests. Drones 2025, 9, 516. [Google Scholar] [CrossRef]
  7. Sehgal, A.; Mahammad, Z.; Sasank, P.; Badhwar, A.; Govindan, N. WireFlie: A Novel Obstacle-Overcoming Mechanism for Autonomous Transmission Line Inspection Drones. IEEE Robot. Autom. Lett. 2025, 10, 6528–6535. [Google Scholar] [CrossRef]
  8. Ollero, A.; Tognon, M.; Suarez, A.; Lee, D.; Franchi, A. Past, present, and future of aerial robotic manipulators. IEEE Trans. Robot. 2021, 38, 626–645. [Google Scholar] [CrossRef]
  9. Welde, J.; Paulos, J.; Kumar, V. Dynamically feasible task space planning for underactuated aerial manipulators. IEEE Robot. Autom. Lett. 2021, 6, 3232–3239. [Google Scholar] [CrossRef]
  10. Welde, J.; Kumar, V. Coordinate-free dynamics and differential flatness of a class of 6DOF aerial manipulators. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; pp. 4307–4313. [Google Scholar]
  11. Brescianini, D.; D’Andrea, R. Design, modeling and control of an omni-directional aerial vehicle. In Proceedings of the 2016 IEEE international conference on robotics and automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 3261–3266. [Google Scholar]
  12. Brescianini, D.; D’Andrea, R. Computationally efficient trajectory generation for fully actuated multirotor vehicles. IEEE Trans. Robot. 2018, 34, 555–571. [Google Scholar] [CrossRef]
  13. Bodie, K.; Brunner, M.; Pantic, M.; Walser, S.; Pfändler, P.; Angst, U.; Siegwart, R.; Nieto, J. An Omnidirectional Aerial Manipulation Platform for Contact-Based Inspection. Robot. Sci. Syst. XV 2019, 15. [Google Scholar] [CrossRef]
  14. Cuniato, E.; Geckeler, C.; Brunner, M.; Strübin, D.; Bähler, E.; Ospelt, F.; Tognon, M.; Mintchev, S.; Siegwart, R. Design and control of a micro overactuated aerial robot with an origami delta manipulator. In Proceedings of the 2023 IEEE International Conference on Robotics and Automation (ICRA), London, UK, 29 May–2 June 2023; pp. 5352–5358. [Google Scholar]
  15. Mellet, J.; Berra, A.; Marcellini, S.; Soto, M.Á.T.; Heredia, G.; Ruggiero, F.; Lippiello, V. Design and Control of an Omnidirectional Aerial Robot with a Miniaturized Haptic Joystick for Physical Interaction. In Proceedings of the 2025 International Conference on Unmanned Aircraft Systems (ICUAS), Charlotte, NC, USA, 14–17 May 2025; pp. 340–346. [Google Scholar]
  16. Guo, L.; Gongye, Z.; Xu, Z.; Wang, Y.; Zhou, X.; Zhou, J.; Gao, F. Preserving Relative Localization of FoV-Limited Drone Swarm via Active Mutual Observation. In Proceedings of the 2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Abu Dhabi, United Arab Emirates, 4–18 October 2024; pp. 10423–10430. [Google Scholar]
  17. Mellinger, D.; Kumar, V. Minimum snap trajectory generation and control for quadrotors. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 2520–2525. [Google Scholar]
  18. Tomić, T.; Ott, C.; Haddadin, S. External wrench estimation, collision detection, and reflex reaction for flying robots. IEEE Trans. Robot. 2017, 33, 1467–1482. [Google Scholar] [CrossRef]
  19. Ruggiero, F.; Cacace, J.; Sadeghian, H.; Lippiello, V. Impedance control of VToL UAVs with a momentum-based external generalized forces estimator. In Proceedings of the 2014 IEEE international conference on robotics and automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 2093–2099. [Google Scholar]
  20. Ryll, M.; Muscio, G.; Pierri, F.; Cataldi, E.; Antonelli, G.; Caccavale, F.; Bicego, D.; Franchi, A. 6D interaction control with aerial robots: The flying end-effector paradigm. Int. J. Robot. Res. 2019, 38, 1045–1062. [Google Scholar] [CrossRef]
  21. Ryll, M.; Muscio, G.; Pierri, F.; Cataldi, E.; Antonelli, G.; Caccavale, F.; Franchi, A. 6D physical interaction with a fully actuated aerial robot. In Proceedings of the 2017 IEEE International Conference on Robotics and Automation (ICRA), Singapore, 29 May–3 June 2017; pp. 5190–5195. [Google Scholar]
  22. Kamel, M.; Verling, S.; Elkhatib, O.; Sprecher, C.; Wulkop, P.; Taylor, Z.; Siegwart, R.; Gilitschenski, I. The voliro omniorientational hexacopter: An agile and maneuverable tiltable-rotor aerial vehicle. IEEE Robot. Autom. Mag. 2018, 25, 34–44. [Google Scholar] [CrossRef]
  23. Allenspach, M.; Bodie, K.; Brunner, M.; Rinsoz, L.; Taylor, Z.; Kamel, M.; Siegwart, R.; Nieto, J. Design and optimal control of a tiltrotor micro-aerial vehicle for efficient omnidirectional flight. Int. J. Robot. Res. 2020, 39, 1305–1325. [Google Scholar] [CrossRef]
  24. D’Angelo, S.; Selvaggio, M.; Lippiello, V.; Ruggiero, F. Semi-autonomous unmanned aerial manipulator teleoperation for push-and-slide inspection using parallel force/vision control. Robot. Auton. Syst. 2025, 186, 104912. [Google Scholar] [CrossRef]
  25. Faessler, M.; Franchi, A.; Scaramuzza, D. Differential flatness of quadrotor dynamics subject to rotor drag for accurate tracking of high-speed trajectories. IEEE Robot. Autom. Lett. 2017, 3, 620–626. [Google Scholar] [CrossRef]
  26. He, X.; Wang, Y. Design and trajectory tracking control of a new bi-copter UAV. IEEE Robot. Autom. Lett. 2022, 7, 9191–9198. [Google Scholar] [CrossRef]
  27. Fliess, M.; Lévine, J.; Martin, P.; Rouchon, P. Flatness and defect of non-linear systems: Introductory theory and examples. Int. J. Control 1995, 61, 1327–1361. [Google Scholar] [CrossRef]
Figure 1. Overall structure of the proposed Flybbit. A high-resolution video is available at https://youtu.be/YSZzlCcosdU (accessed on 10 August 2025).
Figure 1. Overall structure of the proposed Flybbit. A high-resolution video is available at https://youtu.be/YSZzlCcosdU (accessed on 10 August 2025).
Drones 09 00609 g001
Figure 2. Representative images for different types of multirotors. (a) Markus Ryll et al.’s [20,21] fixed-tilt hexarotor. (b) Mina Kamel et al.’s [22] tiltable hexarotor. (c) Dario Brescianini et al.’s [11,12] fixed-tilt omnicopter. (d) Mike Allenspach et al.’s [13,23] tiltable hexarotor coaxial. (e) Eugenio Cuniato et al.’s [14] hybrid tricopter. (f) Simone D’Angelo et al.’s [6,24] tiltable quadrotor.
Figure 2. Representative images for different types of multirotors. (a) Markus Ryll et al.’s [20,21] fixed-tilt hexarotor. (b) Mina Kamel et al.’s [22] tiltable hexarotor. (c) Dario Brescianini et al.’s [11,12] fixed-tilt omnicopter. (d) Mike Allenspach et al.’s [13,23] tiltable hexarotor coaxial. (e) Eugenio Cuniato et al.’s [14] hybrid tricopter. (f) Simone D’Angelo et al.’s [6,24] tiltable quadrotor.
Drones 09 00609 g002
Figure 3. Hardware details for the proposed system.
Figure 3. Hardware details for the proposed system.
Drones 09 00609 g003
Figure 4. Coordinate frames definitions of Flybbit. R i also represents the rotation matrix that describes the orientation of the motors’ frames relative to the body frame at the current time. Rotors 1, 3, and 4 rotate counterclockwise (CCW), while rotors 2, 5, and 6 rotate clockwise (CW).
Figure 4. Coordinate frames definitions of Flybbit. R i also represents the rotation matrix that describes the orientation of the motors’ frames relative to the body frame at the current time. Rotors 1, 3, and 4 rotate counterclockwise (CCW), while rotors 2, 5, and 6 rotate clockwise (CW).
Drones 09 00609 g004
Figure 5. Tiltable servo motors decompose the unidirectional thrust f i generated by the vertical component f i sin ( θ i ) and the horizontal component f i cos ( θ i ) .
Figure 5. Tiltable servo motors decompose the unidirectional thrust f i generated by the vertical component f i sin ( θ i ) and the horizontal component f i cos ( θ i ) .
Drones 09 00609 g005
Figure 6. The Euler angle Z Y X can be decomposed into two rotations, and the thrust vector B f a is constrained to lie in the XOZ plane, where the vector B f a , x and B f a , z express horizontal and vertical components seperately.
Figure 6. The Euler angle Z Y X can be decomposed into two rotations, and the thrust vector B f a is constrained to lie in the XOZ plane, where the vector B f a , x and B f a , z express horizontal and vertical components seperately.
Drones 09 00609 g006
Figure 7. The control architecture of Flybbit. A five-DOF trajectory will be directly provided to the controller modules as the desired input, and the vehicle states are estimated through the fusion of data from a series of sensors using the EKF2. Finally, the desired forces and moments output will be converted into actuator commands for the motors and servos through adaptive nonlinear control allocation.
Figure 7. The control architecture of Flybbit. A five-DOF trajectory will be directly provided to the controller modules as the desired input, and the vehicle states are estimated through the fusion of data from a series of sensors using the EKF2. Finally, the desired forces and moments output will be converted into actuator commands for the motors and servos through adaptive nonlinear control allocation.
Drones 09 00609 g007
Figure 8. SITL and HITL platforms of Flybbit. (a) Additional auxiliary stick (as orange arrow) is used to control the pitch angle separately. (b) Vehicle moves forward with a velocity greater than 0 m/s. (c) Vehicle moves in the horizontal direction with a velocity greater than 0 m/s. (d) Vehicle keeps yaw = 45 and hovers. (e) Vehicle keeps pitch = 20 and hovers.
Figure 8. SITL and HITL platforms of Flybbit. (a) Additional auxiliary stick (as orange arrow) is used to control the pitch angle separately. (b) Vehicle moves forward with a velocity greater than 0 m/s. (c) Vehicle moves in the horizontal direction with a velocity greater than 0 m/s. (d) Vehicle keeps yaw = 45 and hovers. (e) Vehicle keeps pitch = 20 and hovers.
Drones 09 00609 g008
Figure 9. Automatic circular motion trajectory following tasks, compared between 4-DOF quadrotor and 5-DOF Flybbit separately. (a) The desired pitch angle of the quadrotor is determined as a function of acceleration via differential flatness, while for Flybbit, the pitch angle is set arbitrarily, as illustrated in (b,c). (d,e) The tracking performance of Flybbit under switching of different desired pitch angles.
Figure 9. Automatic circular motion trajectory following tasks, compared between 4-DOF quadrotor and 5-DOF Flybbit separately. (a) The desired pitch angle of the quadrotor is determined as a function of acceleration via differential flatness, while for Flybbit, the pitch angle is set arbitrarily, as illustrated in (b,c). (d,e) The tracking performance of Flybbit under switching of different desired pitch angles.
Drones 09 00609 g009
Figure 10. Visualization of Flybbit’s wrench set. (a) Force set with no torque. (b) Torque set while hovering in the air.
Figure 10. Visualization of Flybbit’s wrench set. (a) Force set with no torque. (b) Torque set while hovering in the air.
Drones 09 00609 g010
Figure 11. Mode-switch experiment between the tiltable “Ears” and fixed “Ears” configurations. (a) The motion trajectory, where the red line represents the tiltable “Ears” mode and the blue line corresponds to the fixed “Ears” mode after switching. (b) The attitude tracking performance under different modes, along with the time evolution of each variable in the actuator vector u .
Figure 11. Mode-switch experiment between the tiltable “Ears” and fixed “Ears” configurations. (a) The motion trajectory, where the red line represents the tiltable “Ears” mode and the blue line corresponds to the fixed “Ears” mode after switching. (b) The attitude tracking performance under different modes, along with the time evolution of each variable in the actuator vector u .
Drones 09 00609 g011
Figure 12. Automatic 5-DOF smooth trajectory following in 20 Hz. (a,b) Demonstration that Flybbit can keep the pitch angle decoupled when flying forward. (c,d) Records of the five controllable variables, including the position, pitch, and yaw angle, as well as the tracking performance under different controllers.
Figure 12. Automatic 5-DOF smooth trajectory following in 20 Hz. (a,b) Demonstration that Flybbit can keep the pitch angle decoupled when flying forward. (c,d) Records of the five controllable variables, including the position, pitch, and yaw angle, as well as the tracking performance under different controllers.
Drones 09 00609 g012
Table 1. Comparison of structural designs and performance characteristics of different multirotors, where admittance control (=AC), impedance control (=IC), and nonlinear inverse dynamics control (=NIDC). The design (a–f) correspond to vehicles expressed in Figure 2.
Table 1. Comparison of structural designs and performance characteristics of different multirotors, where admittance control (=AC), impedance control (=IC), and nonlinear inverse dynamics control (=NIDC). The design (a–f) correspond to vehicles expressed in Figure 2.
DesignDOFsControllerConfigurationActuatabilityExperiment
Generic Quadrotor4-Planar FixedUnderactuated-
Generic Bicopter4-Fully TiltableUnderactuated-
Fixed-Tilt Hexarotor (a)6ACAngle FixedFully ActuatedReal world only
Tiltable Hexarotor (b)6PIDFully TiltableFully ActuatedSITL and real world
Omnicopter (c)6PIDAngle FixedOveractuatedReal-world only
Tiltable Hexarotor Coaxial (d)6ICFully TiltableOveractuatedReal world only
Hybrid Tricopter (e)5PIDHybridOveractuatedReal world only
Tiltable Quadrotor (f)6PIDFully TiltableOveractuatedSITL and real world
Flybbit (Ours)5NIDCHybridOveractuatedSITL, HITL, and real world
Table 2. Weight distribution of key components.
Table 2. Weight distribution of key components.
ComponentQtyUnit Weight (kg)Total Weight (kg)
Pixhawk FCU10.040.04
Servo Motor20.040.08
Brushless Motor60.03/0.0150.15
Basic ESC20.010.02
4-in-1 ESC10.020.02
5 V or 12 V UBEC10.020.02
Battery10.200.20
Overall Frame10.610.61
Assembled Vehicle1-0.89
Table 3. Notation for system modeling.
Table 3. Notation for system modeling.
SymbolMeaning
{ W } World frame
{ B } Body frame fixed to the vehicle’s COM
f a Control forces generated by the vehicle’s actuators expressed in the body frame B , f a = [ f a , x , f a , y , f a , z ] T
τ a Control torques generated by the vehicle’s actuators expressed in the body frame B , τ a = [ τ a , x , τ a , y , τ a , z ] T
f e External forces exerted on the vehicle and expressed in the body frame B , f e = [ f e , x , f e , y , f e , z ] T
τ e External torques exerted on the vehicle and expressed in the body frame B , τ e = [ τ e , x , τ e , y , τ e , z ] T
Θ Z Y X Euler angles of the body frame B relative to the world frame W , Θ = { ψ , θ , ϕ }
R Rotation matrix of the body frame B relative to the world frame W
R i Rotation matrix of each rotor frame relative to the body frame B , i = 1 6
p Position of the vehicle’s COM expressed in the world frame W , p = [ p x , p y , p z ] T
v Velocity of the vehicle expressed in the world frame W , v = [ v x , v y , v z ] T
ω Angular velocity of the vehicle expressed in the body frame B , ω = [ ω x , ω y , ω z ] T
p i Geometry position of each ith rotor relative to the vehicle’s COM expressed in the body frame p i = [ p x i , p y i , p z i ] T , i = 1 6
f i Thrust generated by each ith rotor, i = 1 6
θ i Tilt angle of two tiltable rotors in the vehicle’s “Ears”, i = 1 2
k m i Torque coefficient of each ith rotor, indicating the proportionality between its aerodynamic drag torque and generated thrust f i , i = 1 6
C T i Thurst coefficient of each ith rotor, relating its aerodynamic drag force to the square of the rotor speed, i = 1 6
Table 4. Comparison of control performance under different “Ears” modes.
Table 4. Comparison of control performance under different “Ears” modes.
ModeRMSEx (m)RMSEy (m)RMSEz (m)
Tiltable Ears Mode0.7560.8260.060
Fixed Ears Mode0.8300.8210.029
Table 5. Comparison of trajectory tracking performance under different controllers.
Table 5. Comparison of trajectory tracking performance under different controllers.
ControllerRMSE (m)Max Yaw (Degree)Max Pitch (Degree)
Ours0.25490.31291.0006
PD (Baseline)0.33690.26771.2855
P-PID0.31240.20321.5425
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

Sun, C.; Shen, R.; Liu, Y.; Zhang, J.; Guo, F.; Zhan, Q. Flybbit: Design and Control of a Novel Rabbit-like Flying Robot. Drones 2025, 9, 609. https://doi.org/10.3390/drones9090609

AMA Style

Sun C, Shen R, Liu Y, Zhang J, Guo F, Zhan Q. Flybbit: Design and Control of a Novel Rabbit-like Flying Robot. Drones. 2025; 9(9):609. https://doi.org/10.3390/drones9090609

Chicago/Turabian Style

Sun, Chenyang, Runjie Shen, Yifan Liu, Junrui Zhang, Fenghe Guo, and Quanxi Zhan. 2025. "Flybbit: Design and Control of a Novel Rabbit-like Flying Robot" Drones 9, no. 9: 609. https://doi.org/10.3390/drones9090609

APA Style

Sun, C., Shen, R., Liu, Y., Zhang, J., Guo, F., & Zhan, Q. (2025). Flybbit: Design and Control of a Novel Rabbit-like Flying Robot. Drones, 9(9), 609. https://doi.org/10.3390/drones9090609

Article Metrics

Back to TopTop