Abstract
This paper presents a robust method for controlling the terrestrial motion of a bimodal multirotor vehicle that can roll and fly. Factors influencing the mobility and controllability of the vehicle are explored and compared to strictly flying multirotor vehicles; the differences motivate novel control and control allocation strategies that leverage the non-standard configuration of the bimodal design. A fifth-order dynamic model of the vehicle subject to kinematic rolling constraints is the basis for a nonlinear, multi-input, multi-output, sliding mode controller. Constrained optimization techniques are used to develop a novel control allocation strategy that minimizes power consumption while rolling. Simulations of the vehicle under closed-loop control are presented. A functional hardware embodiment of the vehicle is constructed onto which the controllers and control allocation algorithm are deployed. Experimental data of the vehicle under closed-loop control demonstrate good performance and robustness to parameter uncertainty. Data collected also demonstrate that the control allocation algorithm correctly determines a thrust-minimizing solution in real-time.
1 Introduction
Bimodal vehicles continue to draw the attention of researchers because of their potential for autonomous operations in unknown environments [1–5]. Bimodal vehicles can adapt to their environment by combining complementary locomotion mechanisms in a single vehicle or by altering the operation of locomotion mechanisms in accordance with the terrain. Additionally, bimodality promises superior efficiency, as different locomotion mechanisms often present a tradeoff in energetic cost. Aerial bimodal vehicles have been the focus of research efforts due to their unmatched mobility in uncertain and changing environments. As a result, several classes of aerial bimodal vehicles have emerged, including rolling–flying [6–10], walking–flying [11,12], and swimming–flying ([13–15]). Each of these classes utilizes various mechanisms for propulsion and lift.
Figure 1 illustrates an embodiment of a rolling–flying vehicle (RFV) that utilizes rotary wings for both rolling locomotion and lift generation. This class of vehicles was first conceived by Ref. [6] when they created a Hybrid Terrestrial/Aerial Quadrotor (HyTAQ), consisting of a quadrotor suspended within a single rolling cage that may roll along the ground and fly. A successful commercial embodiment of this vehicle architecture is the Parrot Rolling Spider (Parrot Drones sas). Here, rolling is accomplished via two independent, passive wheels on either side of the vehicle. The pitch angle of the rotor plane is independent of the wheels’ angular orientation so that the wheels are freely towed by the rotors. This configuration combines the efficiency of rolling locomotion with the mobility and maneuverability of rotary-wing flight; the energetic efficiency of the RFV compared to a conventional flying multirotor vehicle (CFMV) has been established by Ref. [16].

A rolling–flying vehicle (RFV). During terrestrial operation, the wheels are passively towed by the rotary wings, which provide thrust, steering, and pitch control. Wheel velocities and vehicle orientation are measured with encoders and an inertial navigation system, respectively.
For example, the cost-of-transport (COT) of the RFV is less than 15% of the COT of a CFMV of comparable mass at low velocities (<5 m/s), while the operating times of the RFV are an order of magnitude higher.
As with nearly any exploratory mobile robot, closed-loop control of the RFV’s heading is necessary for basic operation. In contrast to other mobile robots, however, control of the pitch angle is critical to realizing the energetic benefits of the RFV. CFMVs and their control have been studied extensively [17–20], along with effective methods for control allocation [21–23]. However, the methods and assumptions used to develop controllers for CFMVs are not valid for an RFV, despite the RFV utilizing the same multirotor mechanism for both rolling and flying. Atay et al. [24] reveal that the dynamic model, flat outputs, and exogenous forces associated with the RFV’s rolling mode differ substantially from those of a CFMV due to the presence of kinematic constraints on the RFV. Furthermore, the RFV’s pitch angle range is considerably greater than that of a CFMV, invalidating any small-angle assumptions based on near-horizontal nominal operating conditions. Such assumptions are common in the CFMV literature as they permit significant simplification of the dynamic models used to design control systems [17,18].
Furthermore, the ability to roll permits the RFV to operate with small rotor thrusts compared to a CFMV because the RFV’s weight is partially supported by the ground when rolling. While this results in reduced power consumption, this also precludes the use of traditional control allocation methods which typically do not constrain the rotor thrusts to be positive. Because the RFV body forces are so small, synthesizing even modest body torques causes traditional control allocation methods to prescribe negative thrusts. However, negative thrusts cannot be efficiently produced by standard rotors, which are designed to always rotate in a single direction. Producing negative thrusts requires either variable pitch propellers, such as those used by Ref. [10], or symmetric (and therefore less efficient) propellers paired with motor drivers capable of reversing direction. Therefore, to avoid prescribing negative thrusts, the RFV requires control allocation methods that cope with actuator constraints and that can be executed rapidly on a real-time microprocessor. As will be shown, constrained control allocation is critical to realizing the energy efficiency of the RFV’s rolling mode of locomotion due to intermittent coupling that exists between the RFV pitch angle and forward velocity.
Kalantari and Spenko [6] invented and patented HyTAQ, consisting of a quadrotor suspended within a single rolling cage. The RFV presented here is one of the many embodiments covered by their patent [25]; specifically, the RFV uses two independently passive rotating wheels rather than a single monolithic cage. In Ref. [6], a model of a single-wheeled vehicle is developed, though the model is not used to design a control system. Takahashi et al. [7] developed the All-Round Two-Wheeled unmanned aerial vehicle (UAV) that contains hemispherical wheels that envelop a UAV suspended along the wheels’ axle. They design a position tracking controller based on a simplified dynamic model wherein the rotational dynamics and nonholonomic constraints are ignored. Mizutani et al. [26] develop a spherical shell permitting a quadrotor placed within to roll. Here, an off-the-shelf quadrotor is used, so no control system nor control allocation design is attempted. Takahashi et al. [7] do not address control allocation, while Ref. [6] uses an open-source multirotor embedded system to control their vehicle (Arduino Arducopter) which uses proportional-integral-derivative (PID) controllers and traditional unconstrained control allocation methods, which are suboptimal for the RFV.
This paper builds on the work of Refs. [6] and [7] by developing model-based control systems and a control allocation strategy for the RFV of Fig. 1. The controller design is based upon the dynamic model developed by Ref. [24], which takes into consideration the various constraints imposed upon the vehicle while in contact with the ground, and does not make any small-angle assumptions. The implications of the constraints as they relate to differential flatness, controllability, and control allocation are explored. This reveals limitations in the extent to which the system outputs can be decoupled and independently controlled. RFV and CFMV characteristics that influence control system development are discussed, and key differences are identified. Consideration of these differences motivates the development of novel closed-loop control systems for the RFV. A model-based, nonlinear, multi-input, multi-output (MIMO), sliding mode controller is designed. The controller’s robustness to bounded parameter uncertainties is proven using Lyapunov’s direct method. A novel constrained control allocation method is developed which determines the required rotor thrusts that will synthesize the desired input forces and moments while minimizing the total thrust produced and ensuring that all thrusts are positive. The solution is proved to be minimal. A hardware embodiment of the RFV is developed, including a custom real-time controller, permitting novel control and control allocation methods to be deployed and tested. The mechanical, electrical, and software subsystems of the RFV prototype are briefly discussed, and empirical results from the hardware are presented alongside simulation results.
This paper is organized as follows: First, the dynamic model of an RFV is briefly presented. Second, the RFV and CFMVs are compared in the context of control system development. Third, a procedure for designing closed-loop controllers for the RFV’s flat outputs is presented. Fourth, a method for control allocation is developed. Fifth, a hardware embodiment of the RFV is described. Sixth, simulation and experimental results are presented. Lastly, the results are discussed along with opportunities for future work.
2 Methods
2.1 Dynamic Model of the Rolling–Flying Vehicle.
Figure 2 shows a schematic illustration of the RFV that identifies the generalized coordinates, constraints, impressed forces and moments, and various frames of reference which define the model. Point b is located at the center of the RFV body B, midway between two wheels W1 and W2, and is the origin of body reference frame which is rigidly fixed in B. Point i is located at the origin of an inertially fixed reference frame . Referring to Fig. 2(c), an intermediate reference frame is defined with respect to , the origin of which is collocated with the origin of frame at point b. As a result, the -axes of and are parallel, and is free to rotate about the -axis of . Wheels W1 and W2 contact the ground at points c1 and c2, respectively. 1 and 2 are free to rotate about the -axis of . Referring to Fig. 2(b), the control inputs to the system are a force in the frame -direction and three moments , and resolved in the frame -, - and -directions, respectively.
![Schematic representations of the RFV illustrating (a) the generalized coordinates, (b) the impressed forces, and constraints and (c) the various frames of reference. Point G is the center of mass, which is offset in the B frame z^-direction. Image taken from Ref. [24].](https://asmedc.silverchair-cdn.com/asmedc/content_public/journal/mechanismsrobotics/13/5/10.1115_1.4050998/1/m_jmr_13_5_050904_f002.png?Expires=1742298562&Signature=YATv2h6IbamCY4W~IpAnDjRCavmjxGLaCbML-BERZY4N1rvqUI1qv8BraBLdwDQKaoTr9dSrqO4G4MERkp3QZm2XdGtbjwitmHbnRRnw10R44ggg8NeUrvueSiEoEIan4o8X32YBAa5wtkKNnEnR0AsxcH8uOn2~5lXNfGijXK0z~dnIJwiioELiImpzJ6IAHjL90GrDjE5ERjhIliw-iyCCDHDIQs6nJ08tXM65O2x1y1v7i~4U4W8ZpkNyYtsMkvoLA1RAAFyIFKa6UKUm3e5f75h8NfXEMjO3sN0KlDvxB9s5bQpV-2PQqf~ZdgZOguWWlt3muPIDk8MzYaLhQg__&Key-Pair-Id=APKAIE5G5CRDK6RD3PGA)
Schematic representations of the RFV illustrating (a) the generalized coordinates, (b) the impressed forces, and constraints and (c) the various frames of reference. Point G is the center of mass, which is offset in the frame -direction. Image taken from Ref. [24].
![Schematic representations of the RFV illustrating (a) the generalized coordinates, (b) the impressed forces, and constraints and (c) the various frames of reference. Point G is the center of mass, which is offset in the B frame z^-direction. Image taken from Ref. [24].](https://asmedc.silverchair-cdn.com/asmedc/content_public/journal/mechanismsrobotics/13/5/10.1115_1.4050998/1/m_jmr_13_5_050904_f002.png?Expires=1742298562&Signature=YATv2h6IbamCY4W~IpAnDjRCavmjxGLaCbML-BERZY4N1rvqUI1qv8BraBLdwDQKaoTr9dSrqO4G4MERkp3QZm2XdGtbjwitmHbnRRnw10R44ggg8NeUrvueSiEoEIan4o8X32YBAa5wtkKNnEnR0AsxcH8uOn2~5lXNfGijXK0z~dnIJwiioELiImpzJ6IAHjL90GrDjE5ERjhIliw-iyCCDHDIQs6nJ08tXM65O2x1y1v7i~4U4W8ZpkNyYtsMkvoLA1RAAFyIFKa6UKUm3e5f75h8NfXEMjO3sN0KlDvxB9s5bQpV-2PQqf~ZdgZOguWWlt3muPIDk8MzYaLhQg__&Key-Pair-Id=APKAIE5G5CRDK6RD3PGA)
Schematic representations of the RFV illustrating (a) the generalized coordinates, (b) the impressed forces, and constraints and (c) the various frames of reference. Point G is the center of mass, which is offset in the frame -direction. Image taken from Ref. [24].
2.2 Comparison of the Rolling–Flying Vehicle and CFMV.
The RFV described in this paper differs substantially from a CFMV, and these differences warrant new approaches to control and control allocation. First, the constraints imposed upon the RFV and CFMV differ. Several constraints occur where the RFV’s wheels contact the ground. This contrasts with a CFMV which is subject to no constraints; the six degrees-of-freedom that describe a CMFV (three position coordinates and three Euler angles) are independent of one another. Constraints influence what subset of generalized coordinates can be independently prescribed and therefore controlled.
To see this, consider the CFMV shown in Fig. 3(a), which can produce a positive horizontal force Fy by operating at a pitch angle α < 0, where Fy is the horizontal component of the net thrust T. To maintain a constant altitude in the -direction, the vertical component of thrust must always exactly counteract the weight of the vehicle W. This has the effect of coupling α and Fy. Since Fy is the control for the forward velocity , there exists a coupling between α and . As a result, one cannot specify α independently of .

(a) A CFMV’s pitch angle α is coupled to the horizontal force Fy generated by the rotor thrust T because the vertical component of T must offset the vehicle weight W. (b) The RFV’s pitch angle can vary while producing a given because the vertical component of T does not have to support the weight of the vehicle. Instead, the normal force FN partially supports the vehicle’s weight.

(a) A CFMV’s pitch angle α is coupled to the horizontal force Fy generated by the rotor thrust T because the vertical component of T must offset the vehicle weight W. (b) The RFV’s pitch angle can vary while producing a given because the vertical component of T does not have to support the weight of the vehicle. Instead, the normal force FN partially supports the vehicle’s weight.
This intuitive explanation can be rigorously demonstrated using the notion of differential flatness. If a dynamic system’s states and inputs can be written as a function of the system’s outputs and their derivatives, then the system is said to be differentially flat and the outputs are referred to as flat outputs [27]. A consequence of being differentially flat is that any trajectory specified in terms of the flat outputs can be directly mapped to the inputs and thus used to specify feasible motion trajectories. Several researchers [28,29] demonstrate that the flat outputs of a CFMV are (velocity normal to the page), (vertical velocity), and the yaw angle σ (not shown); in particular, the pitch angle α is not a flat output. This contrasts with the RFV, whose flat outputs are σ, α, and [24]. Referring to Fig. 3(b), the difference in flat outputs is due to the normal constraints on the RFV’s wheels, which result in normal forces that partially support the vehicle’s weight. As a result, the vertical component of the thrust force is not required to support the vehicle’s weight, meaning that T, and therefore , can be prescribed independently of α. The difference in flat outputs reveals that CFMV control algorithms are not ideal for controlling the RFV, as they will simultaneously inhibit independent control of the flat output α while attempting to control non-flat outputs and and the non-output . Rather, RFV control algorithms should be based on the dynamic model of Eqs. (1)–(3), which permits control of the flat outputs σ, α, and . In general, the independence of α and can be leveraged to optimize the RFV operation for maximum range, while control of α alone enables optimization for minimum power consumption [16]. This occurs because control of α permits control of wheel normal force, and therefore wheel rolling resistance. This in turn influences power consumption and range. The optimal α at which to operate depends on terrain, highlighting the importance of a broad range for α control.
Furthermore, the difference in flat outputs reveals that the RFV is over-actuated while rolling; the RFV’s four rotors, which are capable of controlling the four flat outputs of a CFMV (i.e., and σ), only need to control three flat outputs while rolling: σ, α, and . As a consequence, the rolling operation may require fewer than four rotors to operate at a time. This is accomplished via a thrust-minimizing control allocation method described further in Secs. 2.4 and 3.2.2.
Another difference between the RFV and CFMVs is the exogenous dissipative forces acting upon the vehicles. In addition to aerodynamic drag forces, the RFV must overcome rolling resistance due to unmodeled terrain and viscous friction present in the wheel bearings. These dissipative forces and the outputs which they affect are captured by , and . Additionally, the proximity of the rotors to the ground at low α creates uncertain ground effect disturbances which the α control system must reject.
Finally, CFMVs and the RFV admit different simplifying assumptions. The nominal operating condition of a CFMV is typically horizontal. As a result, many attitude control systems are developed by linearizing the system dynamics about the horizontal configuration and making a small-angle assumption [18,28,30]. Linearization and/or small-angle strategies are unsuitable for the RFV as α is unrestricted and may assume values far from horizontal for extended periods. One consequence of large α values is the inertial cross-coupling that occurs due to the sin(α) and sin(2α) terms appearing in Eqs. (1)–(3). These terms create significant inertial torques that must be overcome by the controller. Large α values also mean that transforming forces and moments from the frame (in which the flat outputs are defined) to the frame (in which the actuators reside) depend on the value of α. As will be shown in Sec. 2.4, the frame moments required to achieve a given yawing torque are modulated by sinα and cosα.
Several researchers relax the small-angle assumption and develop model-based nonlinear controllers for CFMVs [17,18,20]. These controllers control orientation by generating moments about an arbitrary axis of a CFMV. This strategy is effective because the CFMV is unconstrained and so free to rotate about any axis. However, the RFV is constrained in multiple ways and so cannot rotate about an arbitrary axis. For example, the RFV cannot undergo lateral rolling (rotation about the frame -axis) without one or both wheels leaving the ground. Were the RFV’s attitude controlled in the same manner a CFMV’s then energy could be wasted trying to rotate the RFV against a constraint. In fact, it is unclear what the commanded lateral roll should be as the slope of the terrain may change. Instead, α and σ (which are flat outputs) are controlled to track a trajectory while lateral rolling can either be uncontrolled or suppressed using active damping (see Sec. 2.4).
2.3 Control System Development.
The control objective is to independently control zi for i = 1, 2 (i.e., σ and α) such that zi → ri as t → ∞, where ri is the reference trajectory to be tracked by the ith output and t is the time. This is accomplished using feedback linearization augmented with sliding mode control. Sliding mode control will ensure closed-loop stability in the presence of bounded modeling uncertainties provided that the uncertainties are matched [31,32]. Formulating the model as in (5) rather than in a more general form permits the uncertainty in the individual nonlinear terms to be bounded, which will result in a less conservative controller; i.e., the control action will be smaller [32].
Note that for the z1 subsystem, κ4 = c4 = 2(L2Ixw/R2 + Iyw + mWL2) + Iy sin 2α + Iz cos 2α + mB + 2mW, which is not constant, but varies with α. However, c4 is still bounded because min(Iy, Iz) ≤ Iy sin2α + Iz cos2α ≤ max(Iy, Iz).
2.4 Control Allocation.

Input force/moment block diagram. The desired frame force and moments are converted to frame force and moments before being input to the constrained control allocation algorithm. The outputs of the control allocation algorithm are the desired rotor thrusts. These in turn influence the dynamic behavior of the RFV.

Input force/moment block diagram. The desired frame force and moments are converted to frame force and moments before being input to the constrained control allocation algorithm. The outputs of the control allocation algorithm are the desired rotor thrusts. These in turn influence the dynamic behavior of the RFV.
This is a standard model used by many researchers [18,28–30] to map rotor thrusts to vehicle force and moments. Equation (25) can be written in a compact form as , where and . The process of inverting (25) to obtain the rotor thrusts that will synthesize the desired frame force and moments is called control allocation. Control allocation for CFMVs is typically accomplished [18] using matrix inversion so that , which has a simple, closed-form solution. However, this solution does not take into consideration any constraints imposed on the solution, e.g., that the thrusts be positive. This is typically not a concern for CFMVs because the nominal positive thrust required to support the weight of a CFMV is considerably greater than the perturbations in thrust required to change its orientation. That is, is “large” compared to . However, this is not true for the RFV because can be zero; the weight of the RFV can be supported by the ground rather than the rotor thrusts. If , inspection of (25) reveals that there is no solution wherein every element of is non-negative other than . Therefore, the standard approach to control allocation for CFMVs cannot be applied to the RFV. Rather, the constraint that every element of is non-negative must be taken into consideration.
Control allocation subject to constraints has been studied extensively [33,34]. Both Monteiro et al. [23] and Guillaume et al. [22] demonstrate how constrained optimization techniques can solve the control allocation problem for multirotor vehicles. This is typically in the context of over-actuated vehicles, or to design a fault-tolerant control allocation solution [21]. Analytical techniques include pseudo-inverse methods, which minimize the norm of , or weighted least squares methods, which allow individual penalties to be assigned to actuators. Numerical optimization techniques such as linear programming and quadratic programming can be used to solve the control allocation problem subject to constraints [33]. Reyhanolgu et al. [35] perform control allocation for a three-degree-of-freedom quadrotor hover system. Their method guarantees that all thrusts are greater than a minimum positive value, although they do not demonstrate whether their solution is minimal.
In addition to the coupling just described, two other forms of coupling exist: First, a singularity in (36) occurs when α is a multiple of π, and cannot be specified. Second, because the positive thrust constraint always results in , the sign of is determined exclusively by the sign of α. As a result, can only be synthesized if sinα < 0, and vice versa. This coupling between and α is unavoidable if the rotor thrusts are constrained to be positive.
3 Hardware Embodiment
A hardware embodiment of the RFV is built to demonstrate the efficacy of the control and control allocation algorithms. This permits the evaluation of the control system performance while ensuring that the algorithms are computationally suitable for implementation on a real-time embedded system. A photograph of the hardware RFV hardware is shown in Fig. 1. A carbon fiber rod serves as the RFV axle, onto which a 3D-printed boom is attached. The boom supports four rotors and all avionics. Also attached to the axle are two quadrature encoder sensors used to resolve the angular position and angular rate of the two wheels. The avionics consist of a battery, a central processing unit (CPU), a power measurement printed circuit board (PCB), two 2.4 GHz radio transceivers, four brushless direct current (DC) (BLDC) motor drivers, and an inertial measurement system (INS) for obtaining the orientation of the RFV. The CPU is an ARM cortex-M7 microcontroller programmed to the following:
Communicate serially with both radio transceivers, including receiving commands from a base station and transmitting real-time telemetry data.
Communicate serially with the INS to obtain orientation and angular rate information.
Measure the position and speed of the wheels via the quadrature encoders.
Sample the voltage of and current from the battery via the power measurement PCB.
Execute the α and σ control algorithms described in Sec. 2.3.
Execute the control allocation algorithm described in Sec. 2.4.
Compute the required voltage for each of the four BLDC motors and generates pulse-width modulated (PWM) signals to control the voltage applied by each BLDC motor driver.
All σ and α commands are transmitted wirelessly from a base station to the RFV every 100 ms. The base station consists of an Xbox 360 handset (Microsoft Xbox 360), a laptop computer executing a custom WinForms GUI, and two 2.4 GHz radio transceivers. Telemetry data (including , and ) are transmitted wirelessly from the RFV to the base station every 2 ms. The interconnections between the various avionic subsystems of the RFV are illustrated in Fig. 5. The avionics components and RFV dimensions are recorded in Tables 1 and 2, respectively.

RFV avionics block diagram. Closed-loop commands are transmitted from a base station. Commands can be generated by either the Xbox360 handset or via a custom WinForms program executing on the laptop. Motion data are sent from the RFV to the base station via two sets of radio transceivers. The main CPU provides PWM signals to the motor drivers, receives and transmits data over the radio transceivers, and reads the INS, wheel quadrature encoders, and power sensors. Power is provided via a three-cell (11.4 V) lithium-polymer battery.

RFV avionics block diagram. Closed-loop commands are transmitted from a base station. Commands can be generated by either the Xbox360 handset or via a custom WinForms program executing on the laptop. Motion data are sent from the RFV to the base station via two sets of radio transceivers. The main CPU provides PWM signals to the motor drivers, receives and transmits data over the radio transceivers, and reads the INS, wheel quadrature encoders, and power sensors. Power is provided via a three-cell (11.4 V) lithium-polymer battery.
RFV components
Component | Manufacturer and part name |
---|---|
CPU | ST Microelectronics STM32F767ZIT6U (Nucleo F767ZI) |
Encoders (2x) | US Digital E3-500-984-NE-H-D-B |
Radios (2x) | Digi International XBee-PRO S2C (XBP24CDMWIT-001) |
Inertial sensor | VectorNav VN-100 Rugged |
BLDC drivers (4x) | Crazepony BL Heli 32 |
Current sensor | Analog Devices AD8210 |
Battery | Turnigy 2200 mAh 2S 25C Lipo Pack |
Motors (4x) | EMax RS2206 |
Rotors (4x) | EMax Avan-R |
Component | Manufacturer and part name |
---|---|
CPU | ST Microelectronics STM32F767ZIT6U (Nucleo F767ZI) |
Encoders (2x) | US Digital E3-500-984-NE-H-D-B |
Radios (2x) | Digi International XBee-PRO S2C (XBP24CDMWIT-001) |
Inertial sensor | VectorNav VN-100 Rugged |
BLDC drivers (4x) | Crazepony BL Heli 32 |
Current sensor | Analog Devices AD8210 |
Battery | Turnigy 2200 mAh 2S 25C Lipo Pack |
Motors (4x) | EMax RS2206 |
Rotors (4x) | EMax Avan-R |
RFV parameters
Parameter | Actual value | Simulated value |
---|---|---|
L (m) | 0.262 | 0.3275 |
R (m) | 0.3480 | 0.261 |
mB (kg) | 1.5 | 1.875 |
mW (kg) | 0.5 | 0.375 |
Ix (kg-m2) | 0.0181 | 0.0226 |
Iy (kg-m2) | 0.0181 | 0.0136 |
Iz (kg-m2) | 0.0217 | 0.0271 |
Ixw (kg-m2) | 0.0303 | 0.0096 |
Iyw (kg-m2) | 0.0151 | 0.008 |
g (m/s2) | 9.81 | 9.81 |
h (m) | −0.01 | −0.0125 |
μrr | – | 0.05 |
μvisc (N-m-s) | – | 0.005 |
CD (kg/m) | – | 0.01 |
Lr (m) | 0.14 | 0.14 |
kT (N/(rad/s)2) | 1.6351 × 10−5 | 1.6351 × 10−5 |
kQ (Nm/(rad/s)2) | 2.7033 × 10−7 | 2.7033 × 10−7 |
Parameter | Actual value | Simulated value |
---|---|---|
L (m) | 0.262 | 0.3275 |
R (m) | 0.3480 | 0.261 |
mB (kg) | 1.5 | 1.875 |
mW (kg) | 0.5 | 0.375 |
Ix (kg-m2) | 0.0181 | 0.0226 |
Iy (kg-m2) | 0.0181 | 0.0136 |
Iz (kg-m2) | 0.0217 | 0.0271 |
Ixw (kg-m2) | 0.0303 | 0.0096 |
Iyw (kg-m2) | 0.0151 | 0.008 |
g (m/s2) | 9.81 | 9.81 |
h (m) | −0.01 | −0.0125 |
μrr | – | 0.05 |
μvisc (N-m-s) | – | 0.005 |
CD (kg/m) | – | 0.01 |
Lr (m) | 0.14 | 0.14 |
kT (N/(rad/s)2) | 1.6351 × 10−5 | 1.6351 × 10−5 |
kQ (Nm/(rad/s)2) | 2.7033 × 10−7 | 2.7033 × 10−7 |
Equation (40) is used to compute the voltage required to rotate the pth motor at an angular velocity of Ωp. The desired Ωp are calculated based on the desired Tp from (24). The rotor parameters kT and kQ are determined empirically by measuring the thrust force and reaction torque on a motor driving a rotor while operating at different angular velocities. The motor parameters Re, ke, and Inl are obtained from the manufacturer’s data.
4 Results and Discussion
4.1 Numerical Simulation Results.

RFV control system block diagram. σ and α are controlled in a closed-loop. The desired frame moments that are output from the controllers are rotated into the frame before being mapped to rotor thrusts by the constrained control allocation algorithm. , and are fed back to both controllers to execute the control law developed in Sec. 2.3

RFV control system block diagram. σ and α are controlled in a closed-loop. The desired frame moments that are output from the controllers are rotated into the frame before being mapped to rotor thrusts by the constrained control allocation algorithm. , and are fed back to both controllers to execute the control law developed in Sec. 2.3
Simulation parameters are displayed in Table 2. μrr, μvisc, and CD are coefficients of rolling resistance, viscous damping, and aerodynamic drag, respectively, which are manifested in , and [24].
To demonstrate the robustness of the sliding mode control system to parameter uncertainty, the model parameters used to simulate the RFV system are intentionally varied from those used to design the α and σ controllers, the latter being based on the actual hardware RFV parameters. Specifically, the simulated values are varied by plus or minus 25%.
The sliding mode controller parameters are listed in Table 3. The state feedback gains are obtained via pole placement, and the uncertainty bounds are based on parameter estimates. a is chosen based on empirical observations of chattering and response time.
Control parameters
Parameter | σ Controller | α Controller |
---|---|---|
η (s−2) | 1 | 1 |
K0 (s−2) | 0 | 5.25 |
K1 (s−1) | 4 | 5 |
a | 1.5 | 1 |
|Δκ1|max | 0.0054 (kg-m2) | 0.0027 (kg-m2) |
|Δκ2|max | 0.05 (kg-m) | 0.3 (N-m) |
|Δκ3|max | 0.2 (N-m) | 0.15 (N-m) |
3 | 1.73 | |
|Δδ|max | 0 | 1 |
Parameter | σ Controller | α Controller |
---|---|---|
η (s−2) | 1 | 1 |
K0 (s−2) | 0 | 5.25 |
K1 (s−1) | 4 | 5 |
a | 1.5 | 1 |
|Δκ1|max | 0.0054 (kg-m2) | 0.0027 (kg-m2) |
|Δκ2|max | 0.05 (kg-m) | 0.3 (N-m) |
|Δκ3|max | 0.2 (N-m) | 0.15 (N-m) |
3 | 1.73 | |
|Δδ|max | 0 | 1 |
Figure 7 shows the simulated response of the α control system to a step command. The desired value of α is αdes = − π/4, . Shown also are the switching gain and sliding variable . Figure 7(a) illustrates that α converges to αdes despite the modeling uncertainty. Figure 7(c) shows that the control is initially positive to drive α to αdes, but rapidly decreases while approaches zero. Once is sufficiently close to zero, begins to increase according to the sliding mode dynamics of (12) and the estimated nonlinear dynamics appearing in the last three terms of (20). The estimated nonlinear dynamics are also primarily responsible for the positive steady-state value of required to support the offset center of mass (because h ≠ 0). However, the uncertainty in the model means that these terms cannot exactly compensate for the offset center of mass, and the difference is made up by the K0e1 term in (20). The net result is a control law that rapidly accelerates and then rapidly decelerates α to achieve the desired orientation. Figure 7(b) shows that is initially driven toward zero, at which point the dynamics prescribed by (12) drive the error system of (8) toward zero.

α control system simulation in response to a step input αdes = π/4. (a) step response, (b) sliding manifold , (c) control output, and (d) switching gain . Model parameters used for simulating the RFV (Table 2, Simulated Value) are intentionally varied from those used to design the control system (Table 2, Actual Value).

α control system simulation in response to a step input αdes = π/4. (a) step response, (b) sliding manifold , (c) control output, and (d) switching gain . Model parameters used for simulating the RFV (Table 2, Simulated Value) are intentionally varied from those used to design the control system (Table 2, Actual Value).
As discussed in Sec. 2.3, the steady-state value of s is nonzero due to the transition region introduced by the hyperbolic tangent function in (20). Figure 7(d) illustrates how the value of the switching gain changes during the step response. The transient behavior of is dominated by the magnitude of the velocity error .
Figure 8 shows the time responses of , and to a step command. The desired value of σ is σdes = π/2, , which behaves similarly to the α control system with the exception that no steady-state value of is necessary to maintain σ = σdes. The error integrator is unused (K0 = 0), resulting in no overshoot.

σ control system simulation in response to a step input σdes = π/2. (a) step response, (b) sliding manifold , (c) control output, and (d) switching gain . Model parameters used for simulating the RFV (Table 2, simulated value) are intentionally varied from those used to design the control system (Table 2, actual value).

σ control system simulation in response to a step input σdes = π/2. (a) step response, (b) sliding manifold , (c) control output, and (d) switching gain . Model parameters used for simulating the RFV (Table 2, simulated value) are intentionally varied from those used to design the control system (Table 2, actual value).
4.2 Empirical Results.
The α and σ controllers and control allocation algorithm described in Secs. 2.3 and 2.4, respectively, are deployed onto the hardware embodiment of the RFV described in Sec. 3. As with the simulations, the block diagram of Fig. 6 illustrates the entire closed-loop system. Experimental data are collected while operating under closed-loop α and σ control. In all cases, and is controlled manually.
4.2.1 Empirical Control System Results.
Figure 9(a) shows the α response to a step command αdes = π/4 for both the actual and simulated RFVs while Fig. 9(b) shows the associated value of . Less aggressive control parameters are chosen compared to the simulation from Sec. 4.1 (K0 = 1.75, K1 = 4), because the simulation assumes that can be generated instantaneously via the rotor thrusts, but in reality, this is not possible; the rotors produce thrust approximately proportional to Ω2, and Ω is governed by the motor/rotor electromechanical dynamics. This introduces lag into the control system, which when combined with an aggressive switching gain β can result in undesirable ringing. Additionally, the dynamics of the motors are uncontrolled; an open-loop voltage is applied to the motors according to (40), rather than controlling Ω in closed-loop. Therefore, uncertainty in the motor parameters and kQ also affect the ability to accurately sythesize . Nonetheless, stability of the actual RFV is achieved with an acceptable tradeoff between response time and ringing. Differences between the actual and simulated plots of α and are attributed to the uncertainty in synthesizing and the uncertainty in the model parameters. For example, the difference in the steady-state values of for the actual and simulated cases in Fig. 9(b) could be due to uncertain vehicle mass, uncertain center of mass location, the inability to accurately synthesize , or any combination of the three. However, stability and performance are demonstrated despite uncertainty in both the model and parameters.

Empirical data illustrating the α control system: (a) step response and (b) control output. The simulation behaves differently due to parameter uncertainty. However, the robustness properties of the sliding mode controller ensure stability.
Figure 10(a) illustrates the α control system tracking a sine wave (π/4 radians amplitude, 0.4 Hz frequency) with . The sliding mode controller exhibits good tracking performance despite uncertainty in the RFV parameters and demonstrates close agreement with simulation results.

Empirical and simulated data illustrating (a) the α control system tracking a sine wave and (b) the σ control system tracking a series of ramp commands
Figure 10(b) shows the σ controller’s ability to track a time-varying trajectory on flat ground while the α controller is simultaneously active with αdes = 0 (α data not shown). The control parameters used are those listed in Table 3. Changes in the rolling resistance of each wheel (which are not accounted for in the model) are observed during operation. However, the controller is able to track the commanded σ angle despite the modeling uncertainty.
4.2.2 Empirical Control Allocation Results.
Efficacy of the control allocation algorithm is demonstrated on the prototype RFV by commanding a sinusoidal while controlling α in closed-loop at varying angles.
These configurations force the control allocation solution to be constrained while also varying which rotors are subject to the constraint. For this test, is the output of the α control system, and , where fsine = 0.25 Hz. The desired is transformed to using (21). Additionally, , which guarantees that the control allocation solution is always constrained.
and are input to the control allocation algorithm with Tmin = 0. The outputs of the control allocation algorithm are the commanded rotor thrusts, each of which are recorded over a complete cycle of for each α value. The results are shown in Fig. 11. The time series plots on the left (Figs. 11(a), 11(c), and 11(e)) show the commanded (dotted line) and the resulting rotor thrusts as a function of time. The graphics to the right of each plot (Figs. 11(b), 11(d), and 11(f)) indicate the physical configuration of the RFV and the relative magnitude of the commanded rotor thrusts at the time denoted by the dashed vertical line on the corresponding plot.

Constrained control allocation. Plots (a), (c), and (e) illustrate the desired thrust forces as a function of time at α = 0, −π/4, and −π/2 radians, respectively, while a sinusoidal is prescribed. This forces the control allocation solution to be constrained. The result is that at least one rotor thrust will always be equal to Tmin, which is zero in this case. Images (b), (d), and (f) illustrate the physical configuration of the RFV and the control allocation solution at the instant in time denoted by the dashed vertical line in the corresponding plot to the left of the image.

Constrained control allocation. Plots (a), (c), and (e) illustrate the desired thrust forces as a function of time at α = 0, −π/4, and −π/2 radians, respectively, while a sinusoidal is prescribed. This forces the control allocation solution to be constrained. The result is that at least one rotor thrust will always be equal to Tmin, which is zero in this case. Images (b), (d), and (f) illustrate the physical configuration of the RFV and the control allocation solution at the instant in time denoted by the dashed vertical line in the corresponding plot to the left of the image.
Figure 11(a) shows the RFV when α = 0. First note that when (at approximately t = 1.3 s and 3.3 s), T1 = T2 = 0 while T3 = T4 ≈ 0.2 N. At these points, the only nonzero body force is , which is determined exclusively by the α control system. The value of T3 and T4 are nonzero because the RFV center of mass is slightly behind point b, as indicated in Fig. 11(b). As a result, the α controller determines that a negative must be applied to maintain α = 0, leading to T3 = T4 > 0. This explains why the T3 and T4 curves appear somewhat noisy, while the T1 and T2 curves are smooth; T3 and T4 are responding to the closed-loop α controller, whereas T1 and T2 are only needed to enforce the command, which is prescribed to be a smooth sinusoid. Alternatively, were the center of mass in front of point b, then the situation would be reversed; the control allocation algorithm would determine that T1 and T2 should be driven primarily by the α controller and T3 and T4 would appear smooth.
Second, a large, positive is commanded at the time indicated by the dashed vertical line, producing large T2 and T4 thrusts. This creates a moment about the z axis, which happens to coincide with the z axis when α = 0. The relative thrusts at this instant are illustrated in Fig. 11(b). Here, the control allocation algorithm has determined that T1 = 0, as the commanded moments , and can be synthesized using just T2, T3, and T4. In fact, an inspection of Fig. 11(a) reveals that at all times one rotor produces zero thrusts. Notice that T4 − T2 ≈ T3 always, indicating that the α controller is still generating the required to maintain α = 0.
In Figs. 11(c) and 11(d), α = −π/4, which moves the center of mass even further behind b, requiring increased thrusts (T3 = T4 ≈ 0.4 N) when . Additionally, the frame and frame are no longer aligned, so is synthesized by generating moments about both the z and y axes. At the dashed line (where is large and positive), T4 and T2 increase to generate . In contrast to the α = 0 case, here T4 − T2 > T3, indicating that there is a nonzero (see Eq. (25)). This explains the slight dip in T3 at the dashed line; T3 decreases beyond its value at to help generate .
Lastly, in Figs. 11(e) and 11(f), α = −π/2. As before, the center of mass is moved further from point b so that T3 = T4 ≈ 0.45 N when . Now, is synthesized solely by generating . T1 is nonzero at the time indicated by the dashed line on Fig. 11(e), though its value is relatively small compared to the other thrusts required to generate when α = 0 or −π/4 (compare to Figs. 11(b) and 11(d)). In fact, all the thrusts appear smaller when α = − π/2. This is ultimately because kTLr ≫ kQ, indicating that moments generated via rotor thrust (i.e., and ) are much greater than moments generated via rotor drag (i.e., ) for a given Ω (see Eqs. (24) and (25)). Therefore, the thrusts generated as a byproduct of producing or are much less than those required to produce an identical . So, if is synthesized primarily via and , as it is when α = −π/2, then the thrusts will be smaller than if were synthesized via
As described in Sec. 2.4, will only be realized if , indicating that the constraints are inactive. Otherwise, the constraints are active and will be set equal to . Figure 12 illustrates the control allocation algorithm transitioning between constrained and unconstrained operation while α = 0. Plotted is for two cases: (solid line) and (dash-dotted line). As before, is the output of the α control system, and , where fsine = 0.25 Hz. As changes (dashed line), so changes , which influences the constraint activeness.

Constrained control allocation when α = 0 while a sinusoidal is prescribed. The plot shows for two different values of . When , the control allocation solution is always constrained. Therefore, . When , the solution is intermittently constrained so that alternates between and .
For the case, the solution is always constrained, and so always. Note that even when . This is because , which is the output of the α controller, is never zero (due to the offset location of the center of mass), and so while may be zero, is not. For the case, the solution is constrained approximately half of the time. While constrained, and the solid and dash-dotted lines lie atop one another. However, as decreases, so does to the point where . During these periods the solution is unconstrained and , indicated by the sudden flattening of the dash-dotted line at a value of 1.57 N. The dashed vertical lines indicate where the algorithm transitions between constrained and unconstrained operation for the case.
5 Conclusion
The RFV’s design merits a controller tailored to its unique nonlinear dynamics and flat outputs. Furthermore, the number of difficult-to-measure parameters governing the RFV’s behavior dictates that such a controller be robust to uncertainty. As such, the controller presented herein is both model-based and robust. The efficacy of the controller has been demonstrated through numerical simulations and empirical experiments using custom hardware and software. The novel control allocation algorithm provides a means for actuating the RFV that respects the vehicle constraints while simultaneously minimizing thrust. Indeed, Figs. 11(a), 11(c), and 11(e) illustrate that at all times at least one rotor is producing zero thrust. Such a thrust-minimizing solution is unique to the RFV.
Additionally, this algorithm is computationally lightweight and thus easily integrated into an embedded system. There are several opportunities to improve the performance of the RFV control systems. First, as mentioned in Sec. 4.2.1, closed-loop rotor velocity controllers could improve the response time and reduce ringing in α. Second, RFV velocity control requires a controller that respects the intermittent coupling of α and . Based on constraint activity (Sec. 2.4), such a controller would determine when independent control of and α is possible and adjust the control strategy accordingly. This permits optimizing RFV operation for maximum range [16]. Lastly, could be used for active γ damping as described in (22), which could improve stability on uneven terrain and prevent rolling during aggressive maneuvering.
Acknowledgment
The authors would like to thank Shaphan Jernigan for his work in supporting the hardware development of the RFV.
Conflict of Interest
There are no conflicts of interest.
Data Availability Statement
The data sets generated and supporting the findings of this article are obtainable from the corresponding author upon reasonable request.
Declarations
Ethical Approval: not applicable.
Consent to Participate: not applicable.
Consent to Publish: The coauthors confirm that the work described has not been published before (except in the form of an abstract or as part of a published lecture, review, or thesis); that it is not under consideration for publication elsewhere; that its publication has been approved by all coauthors.
Authors Contributions: S. Atay modeled the rolling/flying vehicle dynamics, designed and simulated the controllers, and was the primary contributing author. M. Bryant and G. Buckner directed the modeling and simulation tasks, provided funding and resources for the work, and provided secondary editing and co-authorship.
Funding: provided by the U.S. Army Research Office and the U.S. Army Special Operations Command under Contract No. W911-NF-13-C-0045.
Competing Interests: not applicable
Availability of data and materials: all data and materials presented in this paper will be made available upon request.
Nomenclature
Variables
- a =
width of sliding mode transition region
- h =
location of RFV body center of mass (m)
- t =
time
- x =
position coordinate (m)
- y =
position coordinate (m)
- z =
position coordinate (m)
- G =
gravitational acceleration (m/s2)
- L =
RFV characteristic length (m)
- R =
wheel radius (m)
- V =
A Lyapunov function
- W =
vehicle weight
- =
inequality constraint function
- =
equality constraint function
- =
system input vector
- =
unit vector in x-direction
- =
unit vector in y-direction
- =
unit vector in z-direction
- fsine =
frequency of sine wave (Hz)
- ke =
motor back-EMF constant
- CD =
aerodynamic drag coefficient
- Fy =
horizontal force in the -direction (N)
- Inl =
motor no-load electrical current
- Ip =
motor electrical current
- I4x4 =
identity matrix
- Lr =
distance from point b to rotor
- Re =
motor winding resistance
- Vp =
motor voltage
- =
horizontal force in the frame -direction (N)
- c1, c2, …, c10 =
model parameters
- =
error states
- =
optimization objective function
- kT, kQ =
rotor constants
- mB, mW =
masses (kg)
- r, ri =
control system reference
- =
sliding manifold
- =
control system state vector
- =
velocity and acceleration in the frame -direction
- =
flat outputs
- =
control allocation matrix
- =
dissipation terms
- =
body force (N) in the frame z-direction (N)
- Ix, Iy, Iz =
RFV body principal moments of inertia of (kg · m2)
- Ixw, Iyw =
wheel principal moments of inertia of (kg · m2)
- =
state feedback gains
- =
body moments (N · m)
- =
frame moments (N · m)
- Qp, Q1, Q2, Q3, Q4 =
rotor torque loads
- =
minimum rotor thrust vector
- =
rotor thrusts
- α, αdes =
pitch Euler angle
- β, =
sliding mode switching gains
- γ =
tilt Euler angle
- |Δκj|max =
maximum uncertainty in κj
- |Δδ|max =
maximum uncertainty in δ
- Ωp =
rotor angular velocity (rad/s)
- δ, δ1, δ2 =
model uncertainties
- ζ =
generic error vector
- η =
a positive constant
- θ1, θ2 =
wheels angles (radians)
- κi, κ1, κ2, κ3, κ4 =
coefficients of nonlinearities
- =
maximum uncertainty in κ4
- =
Lagrange multipliers
- μvisc =
viscous damping coefficient (N · m · s)
- μrr =
rolling resistance coefficient
- ν =
a fictitious control input
- νx, νy, νz =
a variable proportional to desired body moments
- =
states of a generic second-order mechanical system
- ρ =
scalar output function
- σ, σdes =
Yaw Euler angle
- ψ1, ψ2 =
nonlinear terms
- ϕ =
a stabilizing control law