Open access peer-reviewed chapter

Induced Force Hovering of Spherical Robot by Under-Actuated Control of Dual Rotor

Written By

G. Santos-Medina, K.Y. Heras-Gaytán, E.A. Martínez-García, R. Torres-Córdoba and V. Carrillo-Saucedo

Submitted: 22 November 2015 Reviewed: 11 April 2016 Published: 19 October 2016

DOI: 10.5772/63548

From the Edited Volume

Robot Control

Edited by Efren Gorrostieta Hurtado

Chapter metrics overview

2,099 Chapter Downloads

View Full Metrics

Abstract

This chapter discusses the design and modelling of a spherical flying robot. The main objective is to control its hovering and omnidirectional mobility by controlling the air mass differential pressure between two asynchronous coaxial rotors that are aligned collinearly. The spherical robot design has embedded a gyroscopic mechanism of three rings that allow the rotors’ under-actuated mobility with 3DOF. The main objective of this study is to maintain the thrust force with nearly vertical direction. The change in pressure between rotors allows to vary the rotors’ tilt and pitch. The system uses special design propellers to improve the laminar air mass flux. A nonlinear fitting model automatically calibrates the rotors’ angular speed as a function of digital values. This model is the functional form that represents the reference input to control the rotors’ speed, validated by three types controllers: P, PI, and PID. The robot’s thrust and induced forces and flight mechanics are proposed and analysed. The simulation results show the feasibility of the approach.

Keywords

  • flight mechanics
  • flying control
  • robot modelling
  • thrust force
  • UAV
  • under-actuation

1. Introduction

Nowadays, unmanned aerial vehicle (UAV) robots are being deployed at an increased rate for numerous applications falling into a variety of engineering fields. There exist numerous kinds of rotary-wing-based robotic technologies in particular with active devices. Robots with rotating wings are capable to self-control over lift, propulsion, landing, hovering And take-off tasks [14]. Overcoming vertical flight (with minimum energy cost) is fundamental to accomplish autonomous precise tasks. One fundamental aspect in controlling and designing rotary-wing-based intelligent machines is to consider under-actuated issues to reduce the number of actuators. Under-actuated flying robots perform motion tasks more naturally, taking advantage of the inertial and gravitational forces, consequently, reducing the use of electrical energy. Biological flying birds are instances of extremely efficient under-actuated bodies. Therefore, in order to design flying machines with a reduced number of actuators, it is essential to model and understand the mechanical nature of the robot mechanics, the fluids and their physics-based relationship.

The present work has foundations on the prototype of a home-made spherical aerial robot. Some experiments can be viewed at https://www.youtube.com/watch?v=rrGH1Oh_beM. Nevertheless, the purpose of this chapter is not on showing and discussing experimental results, but on mathematically sustaining the hypothesis of the robot’s flight mechanics and control. Unlike, known spherical design approaches [57], rather than deploying aileron-like propellers, we proposed yaw, pitch and roll changes through under-actuation exerting an inner gyroscopic mechanism. In the present chapter, the authors are particularly interested in disclosing the physical model of a dual rotary-wing spherical robot with an under-actuated gyroscopic mechanism. The model has been divided into four major areas: the robot’s flight mechanics with direct and inverse solution, the thrusting or induced force model, the rotors control model and a proportional integral derivative (PID) based control with non-stationary reference values.

This chapter is organised as follows. In Section 2, the design and mechanical aspects of the aerial robot are presented. Section 3 presents the kinematic direct and inverse solutions of the flight mechanics. In Section 4, the acceleration components and forces involved in the robot’s aerodynamics are discussed. Section 5 presents the robot’s thrusting force model that involves two collinear induced forces. Section 6 presents the rotors’ actuator speed models that are proposed from empirical measurements, and subsequently, the analytical solution is obtained. In Section 7, the actuators’ feedback linear control is described. Finally, in Section 8, conclusions are drawn.

Advertisement

2. Spherical gyroscopic robot

Unlike other reported approaches [813], in this study, the authors have proposed an omnidirectional spherical design with two rotors vertically collinear (see Figure 1, right, and Figure 2).

Figure 1.

Left: Aerial robot real prototype. Right: Robot’s main actuated and under-actuated mechanical elements.

Figure 2.

Left: Robot’s global and local spherical coordinates. Centre: Robot’s flying space (Eqs. (1)–(3)). Right: recursive trajectory generation (Texto) and (Texto).

Advertisement

3. Flight mechanics model

Flight mechanics refers to the study of geometry of flight of a heavier-than-air aircraft, considering aerodynamic aspects. Expressions (1)–(3) model the three-dimension robot’s Cartesian kinematic components that describe its motion. The components, namely, x, y and z, are the space positions w.r.t. the location of the robot’s starting flight. The proposed kinematic model is constrained with initial posture as the inertial frame origin, where d is the distance between the robot’s instantaneous 3D position and its Cartesian origin. Azimuth angle ϕ0 is w.r.t. the plane XY, and the elevation angle ϕ1 is w.r.t. the Y-axis:

x=dcos(ϕ1)sin(ϕ0)E1

The y component (vertical) is expressed as

y=dsin(ϕ1)E2

And, the z component is expressed as

z=dcos(ϕ1)cos(ϕ0)E3

For further purpose, the inverse solution is obtained by an algebraic arrangement of derivatives. The first-order derivatives of Eqs. (1)–(3) are obtained and shown in Eqs.(4)–(6),

x˙=d˙cos(ϕ1)sin(ϕ0)+dcos(ϕ1)cos(ϕ0)ϕ˙0dsin(ϕ1)sin(ϕ0)ϕ˙1E4

The vertical component is expressed as

y˙=d˙sin(ϕ1)+dcos(ϕ1)φ˙E5

And, the z component is expressed as

z˙=d˙cos(ϕ1)cos(ϕ0)+dcos(ϕ1)cos(ϕ0)ϕ˙0E6

Figure 2 centre depicts the robot’s flying space, which is spherical with the Cartesian origin at robot’s starting flying task.

Expressing in the matrix form, the first-order derivative dp/dt w.r.t. time is

p˙=(x˙y˙z˙)=(dC1C0dS1S0C1S00dC1S1dC1C0dS1C0C1C0)(ϕ˙0ϕ˙1d˙)E7

By simplifying, the linear equation of direct kinematic is denoted by the Jacobian matrix J and the first-order vector of independent variables,

p˙=JΦ˙E8

In order to obtain a recursive functional form equivalent to previous state variables, the derivatives are expressed in the following manner:

ddtp=JddtΦE9

Time differentials are eliminated, and the integration operators complete the remaining differentials dp and :

p˙1p˙2dp=Jϕ˙1ϕ˙2dΦE10

Thus, to solve for the robot’s Cartesian position a recursive form is obtained by algebraically reordering. Next, robot’s position pt+1 is obtained by successive approximations of ϕt until ϕf:

pt+1=pt+J(ϕfϕt)E11

In addition, the kinematic inverse solution requires the inverse-squared Jacobian matrix, assuming that it is an invertible and non-singular matrix, with non-zero determinant:

J1=1d2C1([ C1C0 ]2+[ S0S1 ])(dC00dS0dC1S0S1dC12dC1C0S1(dC1)2S0dC1C0S1(dC1)2C0)E12

Therefore, the first-order inverse kinematic is obtained by an algebraic approach:

Φ˙=J1p˙E13

As described earlier, we complete the differentials dp and :

Φ˙1Φ˙2dΦ=J1p˙1p˙2dpE14

By integrating both sides of the equality, respectively, a recursive inverse solution in terms of the rotor’s angular speed is obtained,

Φ˙t+1=Φ˙t+J1(p˙fp˙t)E15

where pt is the actual robot 3D position and pf represents the final desired position in space. To achieve such location, the robot recursively approximates the next desired rotor’s controlled velocity. The next figure depicts a simulation result where the aerial robot successively approached the final desired position, staring from the Cartesian origin.

Advertisement

4. Aerodynamic robot’s model

The aerodynamic robot’s model refers to the application of the Newton’s second law of motion in three dimensions to infer the thrusting force T and other involved forces that produce the Cartesian accelerations:

x¨=d¨c1s0d˙s1s0ϕ˙1+d˙c1c0ϕ˙0+d˙c1c0ϕ1ds1c0ϕ˙0ϕ˙1dc1c0ϕ˙02dc1c0ϕ¨0d˙s1s0ϕ˙1dc1s0ϕ˙12ds1c0ϕ˙1ϕ˙0ds1s0ϕ˙1E16
y¨=d¨s1+dc1ϕ˙1+d˙c1ϕ1ds1ϕ˙12+dc1ϕ¨1E17
z¨=d¨c1c0d˙s1c0ϕ˙1d˙c1s0ϕ˙0ds1c0ϕ1dc1c0ϕ˙12+ds1s0ϕ˙0ϕ˙1ds1c0ϕ¨1d˙c1s0ϕ˙0+d˙s1s0ϕ˙0ϕ˙1dc1c0ϕ˙02dc1s0ϕ¨0E18

In the matrix form, the following equation represents the direct kinematic solution for the Cartesian accelerations:

p¨=(dc1c0ds1s0c1s00dc1s1dc1c0ds1c0c1s0)(ϕ˙0ϕ˙1d˙)+(dc1c0dc1c02dc1c02dc1c02ds1s00ds1002c1dc1c0dc1c02ds1s02dc1s02ds1c0)(ϕ˙02ϕ˙12ϕ˙0ϕ˙1d˙ϕ˙0d˙ϕ˙1)E19
or
p¨=J1Φ˙+J2Φ¨

From the previous expression, the vector acceleration is substituted into the Newton’s second law of motion,

f=mp¨E20

where the Cartesian force components defined in robot’s local inertial frame are expressed as follows:

fx=Tcos(θ1)sin(θ0)E21

The force component along the robot’s local y component is expressed as

fy=Tsin(θ1)E22

And, the force component along the robot’s local Z component is expressed as

fz=Tcos(θ1)cos(θ0)E23

By simplifying the Cartesian force components in the matrix form

f=T(c1s0s1c1c0)E24

And, by substituting the functional form of the vector force f into the Newton’s second law,

mp¨=T(c1s0s1c1c0)E25

Thus, by reordering the previous equation, we substitute the vector constraints wT =(C1S0, S1, C1C0). The acceleration vector d2p/dt2 is a function of the next position pt+1 and the rotors variables:

Tw=mp¨(pt+1,Φf,Φ˙t)E26

By dropping off the induced robot’s force T,

T=w1mp¨(pt+1,Φf,Φ˙t)E27

So far, in this expression, the total thrusting induced force T represents the robot’s global flying force. Thus, T is an arithmetic result produced by the sum of the top rotor’s induced force T1 and the below rotor’s induced force T2 according to the following governing constraints:

  1. For T1 = T2, the inflow air mass is same throughout both rotors, hence T = T1 + T2.

  2. For T1 > T2, speed and air mass below rotor 1 are greater than rotor 2 inflow, T = T1 + α2 T2.

  3. For T1<T2, opposed to constraint (b), then T2 = α2T1 and T = T1(1+α2).

Here, the numerical factors α1,2 are gains denoting rotors’ speed-rate differences. For either constraint (b) or (c), the gyroscopic mechanism angles’ tilt and pitch are affected, consequently changing the robot’s azimuth and elevation angles.

Advertisement

5. Induced force model

According to the depictions of Figure 3, the rotors are continuously pushing the air down. As per Newton’s third law, an equal and opposite reaction force, denoted as rotor thrust, is acting on the rotor due to air. The induced force model refers to the thrusting force exerted to accelerate the robot. And at a constant velocity the quasi-static hovering is achieved [14].

Figure 3.

Rotors’ flow conditions in the slip streams.

The momentum conservation is obtained by relating the induced force T2 to the rate of momentum change. It is the mass rate and the far-field wake-induced velocity vw below rotor 2, where dm/dtAv2 and the rotor disk area A = πR2. Thus, the moment conservation

T=m˙vwE28

The energy conservation per unit time

Tv=12m˙vw2E29

To obtain a relationship between v and vw, let us substitute T and dm/dt,

m˙vwv=12m˙vw2E30

Algebraically simplifying,

v=12vw;vw=2vE31

Hence, substituting vw into T,

T=m˙vw=2m˙vE32

Then,

T=2ρAv2E33

Dropping off v, the following expression is obtained;

v=T2ρAE34

The propulsive power Pw is the thrusting force T capable to move the robot at a given velocity (distance over time):

Pw=Tv=TT2ρAE35

The induced power per unit thrust for a hovering rotor can be written as

PwT=v=T2ρAE36

The above expression indicates that, for a low inflow velocity, the efficiency is higher. This is possible if the rotor has a low disk loading (T/A). Note that the parameter determining the induced power is essentially T/(ϱA). Therefore, the effective disk loading increases with an increase in altitude and temperature.

From previous analysis, let us now precisely define the thrusting force for rotors 1 and 2, according to Figure 3 (left side). For rotor 1, the air mass flow is

m˙1=ρA1v1E37

Hence, considering only rotor 1, the induced force is

T1=m˙1v2E38

The energy conservation principle for rotor 1 is expressed as

T1v1=12m˙1v22E39

And finding a relationship between v1 and v2 in accordance with Figure 3 (left side),

v2=2v1E40

Thus,

T1=2ρ1A1v12E41

The induced air velocity induced by rotor 1 is modelled by

v1=T12ρ1A1E42

Similarly, modelling both the induced force T2 and velocity v2 for rotor 2, the following analysis is developed. The airflow rate,

m˙2=ρ2A2v3E43

And the induced force T2 considers the inflow air mass and the far-field wake-induced velocity vw,

T2=m˙2vwE44

The energy conservation for the second rotor is expressed as

T2v3=12m˙2vw2E45

The relationship between far-field wake-induced air velocity vw and v3 is given by vw=2v3, and

T2=2ρ2A2v32E46

Therefore, the second rotor’s air induced velocity is

v3=T22ρ2A2E47

From the three previous postulates of Figure 3, let us deduce the conditions when both rotors, although asynchronous, simultaneously induce the airflow equally, when v1=v3 (Figure 3a). For this case, the total robot’s thrusting force T=T1+T2,

T=2ρ1A1v12+2ρ2A2v32E48

For case 1, let us assume A1=A2 and v2=v3 through the second rotor’s disc area. And,

vw=2v3;likewise,v2=2v1;hencevw=2(2v1)=4v1E49

Rewriting total T as a function of v1, thus we have

ρ2=mcvcE50

The air mass variation is denoted as the mass derivative w.r.t. time,

m˙=ρ2AV2E51

Now, for the case v1>v3,

T=T1+α2T2E52

Let us substitute our T1 and T2 models previously analysed,

T=2ρ1A1v12+2ρ2A2v32E53

In addition, A1=A2, v2=2v1 and vw=2v3, but v2>v3 hence v32v2. Thus, vw=2(α2 2(2v1)), and we obtain the relationship between the far-field wake-induced velocity and v1:

vw=6α2v1E54

By substituting v1 into expression T, developing and factorising algebraically,

T=2Av12(ρ1+4α2ρ2)E55

Similarly, for the case when v1<v3, T=T1(1+α2),

T=2ρ1A1v12+2ρ2A2v32E56

for this case, A1=A2, v2=2v1 and vw=2v3. However, just above and below rotor 2, v2<v3, and therefore v22v3, then v3=2v22.

T=2ρ1Av12+2ρ2A(2v1α2)2E57

Factorizing and algebraically arranging,

T=2Av12(ρ1+8ρ2α22)E58

Solving the parameter α2 for each of the three cases,

α22={ 4,1,2,v1=v3v1>v3v1<v3|E59

Therefore, we synthesise the total thrusting force T for all cases by

T=2Av12(ρ1+α22ρ2)E60

Therefore, from Eq. (60), now we have a functional form for the thrusting force T. Thus, to reach a controlled rotors’ velocity, we must establish a relationship between the induced velocity v1 and the rotor angular velocity /dt using the tip speed of the rotor blade as reference. The rotor inflow is represented in non-dimensional form as

λ=v3ϕ˙R=CT2E61

where CT is the thrust coefficient modelled by

CT=Tρ2A(ϕ˙tR)2E62

Therefore, the following equality allow us to deduce CT with more

ϕ˙=v1RCT2E63

Thus, substituting (Texto) into v1,

v1=(ϕ˙RCT2)2E64

And subsequently, v12 is substituted into T,

T=A(ϕ˙2R2CT)(ρ1+α22ρ2)E65

Therefore, the induced force T arising from the fluid mechanics equation (65) is equated with the induced force of the flight mechanics equation (27), the following expression is obtained:

2A(ϕ˙2R2CT2)(ρ1+α22ρ2)=w1mp¨E66

Our objective is to find an analytical solution for the rotor speed required to reach the induced velocity v1 and the induced force T, which is governed by the flight mechanics law. The induced air mass velocity v1 can be expressed in terms of the rotor speed that is controlled to obtain the desired angular velocity,

ϕ˙=mw1p¨AR2CT(ρ1+α22ρ2)E67

This model represents the independent variable to control the motors’ Speed of Eq. (73) or Eq. (74):

Thus, it follows a set of empirical temperature measurements where some experimental hovering experiments were carried out. The plots in Figure 4 depict how the air pressure is affected as the temperature varies over time.

Figure 4.

Left: Thrusting force w.r.t. induced velocity. Right: Air mass density as temperature varies.

Advertisement

6. Actuators’ speed model

The actuators’ self-calibration speed model is discussed in this section. The real rotary velocity in a range from minimal to maximal values approached a logarithmic model. It considered the empirical set of angular speed measurements w.r.t. digital controls. The inherent physical variations, such as temperature, air pressure, density and air dust particles, affected the actuators’ performance. Since the angular speed value capable to hover the spherical robot’s body is disturbed, a self-calibration is required to maintain position control as accurate as possible. From experiments, the empirical models that obtained (Figure 5) φ vs. d are fitted according to the next model. The parameters A and β are unknown and must fit the speed measurements φ, w.r.t to digital word d,

ϕ˙=A+βln(d)E68

We temporally substitute d’=ln(d), and thus the rotary speed

ϕ˙=A=βd'E69

To estimate the unknown parameter β, a linear mean-squared method is applied,

β=n(d'ϕ˙(d')(ϕ˙))n(d'2)(d')2E70

Subsequently, the previous parameter solution is used in the next expression A,

A= ϕ˙nβd'nE71

By substituting the parameters numerical values, the rotary speed model is obtained as follows:

ϕ˙=10838.57637ln(d)46776.63059E72

In addition, in order to obtain the inverse solution, we algebraically drop off the variable d from Eq. (72),

d=eϕ˙AβE73

And numerical parametric values from Eq. (72) are substituted into (73) to obtain

d=eϕ˙46776.630610838.5764E74

In order to compare how our theoretical model fits the empirical model, both inverse and direct operation control modes are depicted in Figure 5.

Figure 5.

Actuator’s raw measurements. Left: Direct solution. Right: Inverse solution.

Advertisement

7. Rotor’s speed control

From the previous section, the actuators’ speed model is now used to formulate a feedback linear control. Let us assume that a rotor control variable (i.e., angle, velocity and acceleration) should ideally be equal to the real sensed control variable, as expressed by the next equality (75). Nevertheless, in a realistic scenario real and ideal control variables are different due to a number of factors, such as frictions, inertial and gravity forces, motor electromagnetic performance and so on. Thus, both variables are approached by a multiplicative gain or factor alpha, which approximates both numerical values according to the relation

φ=kφ˙^E75

Assuming an arbitrary actual derivative order, the equation is equivalently expressed as

ddtφ=kddtφ^E76

The time differentials are eliminated and the remaining differentials are obtained by solving the following definite integrals,

φ1φ2dφ=kφ^1φ^2dφ^E77

By solving the definite integrals,

φ2φ1=k(φ^2φ^1)E78

In this case, φ^2 is the expected or the reference value to be reached ideally, φ^2=φref. Thus, by adjusting the times sub-interval labels, and algebraically reordering, the next recursive numerical successive approximation equation is expressed as follows:

φt+1=φt+k(φrefφt)=φt+ketE79

From the previous expression, the error ket is spanned into the past (angular displacement), the actual (rotary speed) and the future (angular accelerations) errors in order to cover the whole error history. And the general constant gain k is proportional to kp, kI and kd. Thus,

φt+1=φt+(kpep+kIeI+kded)E80

Therefore, the next feedback proportional error ep (rad/s) with proportional gain kp (dimensionless) is obtained with the observation ϕt measured online. And the reference model (Texto) is established in terms of the instantaneous control word δt:

kpep=kp(ϕ˙refϕ˙t)=kp(aln(δ)bϕ˙t)E81

Figure 6.

Left: Measurement and reference proportional models. Right: Proportional error.

For illustrative purpose, an accelerative rotor’s task to exert robot’s propulsion was performed. Figure 6 (left) depicts both the reference model ϕref and the observation ϕ(t).

In addition, Figure 6 (right) shows the proportional error behaviour ϕref-ϕ(t) without kp. Furthermore, the feedback integral error eI (rad/s) with integral gain kI (dimensionless) is expressed by the time integration of the difference of (d2ϕ/dt2d2ϕ(t)/dt2).

kIeI=kI((ϕ¨refϕ¨t)dt)E82

The observation model d2ϕ/dt2 was obtained online by the numerical derivatives of the optical encoder according to the following relationship:

ϕ¨(t)=ϕ˙t2ϕ˙t1t2t1E83

In addition, since the observation model inherently poses perturbations, an analytical reference model d2ϕref/dt2 was obtained using a nonlinear regressive fitting process for parameters identification,

( ϕ¨i ϕ¨ti ϕ¨iti2)=(ntiti2titi2ti3ti2ti3ti4)(a0a1a2)E84

where the previous expression is similarly expressed as

y=AxE85

And by solving vector x,

x=A1yE86

Hence, the reference model is a theoretical nonlinear function of time,

ϕ¨ref(t)=34.79501.2832t+0.0145t2E87

Therefore, for the sake of the integral control uI (rad/s), the angular acceleration reference model (Texto) is substituted next in its general form:

uI=kI((a0a1t+a2t2)ϕ¨(t)dt)E88

Finally, in order to keep data homogeneity (numerical data subtraction), time integration is obtained by the trapezoid rule for numerical integration,

ϕ˙k=tft02n[ (ϕ¨0refϕ¨0(t))+2 (ϕ¨trefϕ¨t)+(ϕ¨tfref(t)ϕ¨tf(t)) ]E89

Figure 7.

Left: Measurement and reference integral models. Right: Integral error.

Figure 7 (left) depicts both reference and empirical models integrated with time. Figure 7 (right) shows the integral error behaviour.

In addition, the derivative control ud=kded (rad/s) with feedback derivative error ed, and with derivative gain kd (dimensionless), improves the closed-loop stability as follows:

kded=kd(ddtϕrefddtϕt)E90

In order to obtain the time derivative observation model, the rotor’s angle evolution ϕ(t) (rad) is observed online using an optical encoder during the time slot where velocity and acceleration are also measured. As the measurements are read with noise, the analytical reference model is fitted as a nonlinear polynomial of the following form:

ϕref(t)=3709.6273+2116.9484t+27.9289t2E91
where the derivative error general form is expressed as
kded=kdddt(b0+b1t+b2t2ϕ(t))E92

Figure 8 (left) depicts both reference ϕref(t) and observation ϕ(t) models together. Although both curves are apparently fitted, the vertical scale is provided in thousands of radians. Figure 8 (right) shows the derivative error scale.

Figure 8.

Left: Measurement and reference derivative models. Right: Derivative error.

Generally, the PID controller is expressed by the next expression

ut=kp((aln(d)b)ϕ˙i)+kI(t(a0a1t+a2t2ϕ¨t)dt)+kd(ddt(b0+b1t+b2t2ϕ(t)))E93

Therefore, the controlled rotor’s velocity that is recursively calculated by t+1/dt= dφt/dt + ut is applied, and we established the following controller choices: proportional (P), proportional integral (PI) and proportional-integral-derivative. Figure 9 (left) depicts the rotors’ angular speed without control and with three types of controllers. The constant parameters were adjusted accordingly to obtain such results. We can see that after 25 s the responses P and PI gradually converge w.r.t. the raw rotor’s speed (Figure 9, left).

Figure 9.

Controllers P, PI and PID. Left: Rotor’s angular speed. Right: Induced Cartesian forces.

In addition, with the controlled rotor’s speed output, the induced force is iteratively calculated by

T(φ˙t+1)=Aφ˙t+12R2CT(ρ1+α22ρ2)E94

Thus, Figure 9 (right) depicts the induced component forces that are produced using three types of controllers.

Advertisement

8. Conclusions

This work briefly introduced the design of an aerial spherical robot with under-actuated gyroscopic mechanism. Although the purpose of this study was not to describe the robot flying and physical capabilities, the main objective was to demonstrate the induced force model deploying dual collinear rotary wings with no steering actuators. This study describes the following four major areas: the robot flight mechanics, the model of the induced thrusting forces, the self-calibration actuators’ Speed model validated with three types of controllers (P, PI, PID) to drive the rotors’ motor speed. The proposed aerodynamic mechanism poses neither ailerons nor propellers for steering control. Although the platform is a home-made laboratory prototype with special arrangements, the main focus of this chapter is to model the hypothesis of controlling the robot’s directions by varying rotors’ asynchronous speed. To achieve this, the under-actuated gyroscopic mechanism provides the ability to control its inner yaw, pitch and roll angles. Until this stage, the robot development is under an early control capability. However, this study presents mathematical solutions and simulation results to demonstrate the proposed aerodynamic hypothesis.

References

  1. 1. Venkatesan C. Fundamentals of helicopter dynamics. CRC Press Taylor and Francis Group; 2015.
  2. 2. Stepniewski W, Keys C. Rotary-wing aerodynamics. New York: Dover Publications; 1984.
  3. 3. Johnson W. Helicopter theory. New York: Dover Publications; 1994.
  4. 4. Seddon J, Newman S. Basic helicopter aerodynamics. Chichester, England: Wiley; 2011.
  5. 5. Briod A, Kornatowski P, Zufferey J, Floreano DA. Collision-resilient flying robot. Journal of Field Robotics, 31(4), 496–509, 2013.
  6. 6. Dudley C, A Spherical Aerial Terrestrial Robot, MSc Thesis, University of Nevada, Reno, 2014.
  7. 7. Briod A, Klaptocz A, Zufferey J-C, Floreano D. The AirBurr: a flying robot that can exploit collisions. International Conference on Complex Medical Engineering, Japan, pp. 569–574, 2012.
  8. 8. Alkalla MG, Fanni MA, Mohamed M.A novel propeller-type climbing robot for vessels inspection. IEEE International Conference on Advanced Intelligent Mechatronics, South Korea, pp.1623–1628, 2015.
  9. 9. Mizutani S,Okada Y,Salaan CJ,Ishii T,Ohno K,Tadokoro S. Proposal and experimental validation of a design strategy for a UAV with a passive rotating spherical shell. IEEE/RSJ IROS, Germany, pp. 1271–1278, 2015.
  10. 10. Czyba R, Szafranski G, Janik M, Pampuch K, Hecel M, Development of co-axial Y6-Rotor UAV—design, mathematical modeling, rapid prototyping and experimental validation. International Conference on Unmanned Aircraft Systems, USA, pp. 1102–1111, 2015.
  11. 11. Kawasaki K, Zhao M, Okada K, Inaba M. MUWA: multi-field universal wheel for air-land vehicle with quad variable-pitch propellers. IEEE/RSJ IROS, Japan, pp. 1880–1885, 2013.
  12. 12. Ho-Joon L, Han-Woong A, Jae-Kwang L, Ju L, Sung-Hong W. Newly proposed hybrid type mutli-DOF operation motor for multi-copter UAV systems. IEEE Energy Conversion Congress and Exposition, Canada, pp. 2782–2790, 2015.
  13. 13. Zhang W, Fan N, Wang Z, Wu Y, Modeling and aerodynamic analysis of a ducted-fan micro aerial vehicle. International Conference on Modelling, Identification & Control, China, pp. 768–773, 2012.

Written By

G. Santos-Medina, K.Y. Heras-Gaytán, E.A. Martínez-García, R. Torres-Córdoba and V. Carrillo-Saucedo

Submitted: 22 November 2015 Reviewed: 11 April 2016 Published: 19 October 2016