+ All Categories
Home > Documents > Sensor-Based Formation Control of Autonomous Robotic Vehicles

Sensor-Based Formation Control of Autonomous Robotic Vehicles

Date post: 11-Feb-2022
Category:
Upload: others
View: 3 times
Download: 0 times
Share this document with a friend
9
1 Sensor-Based Formation Control of Autonomous Robotic Vehicles Ana Cristina Resendes Maia Instituto Superior T´ ecnico - Institute for Systems and Robotics (IST-ISR) Lisbon 1049-001,Portugal November 2013 Abstract—This thesis objective is to produce controllers of both depth and altitude specially dedicated to navigate the subaquatic vehicle, Medusa, in the vertical plan. To fulfil this goal, first it was necessary to model the vehicle behaviour when moving vertically and identifying the parameters of this model. This was done resorting to physical models and empiric measurements. After, two types of controllers were designed and simulated: a simpler one based on a linearised version of the vehicle’s model and a more complex one that compensated all the non-linearity of the vehicle allowing precise following. These controllers were subjected to extensive simulation in computer environment and the first and simpler one was tested in sea water. Based on the results of both simulations and real tests, the controllers can successfully control the Medusa vertical movement and follow, in the second controller case, more complex references. Index Terms—Medusa, modelling, identification, depth, alti- tude, precise following I. I NTRODUCTION The purpose of this work, developed in the MORPH project environment, [3], is to obtain controllers that can navigate an under-water specific vehicle, Medusa, on the vertical plan. This includes finding a model that accurately describes the vehicle vertical movement and identifying all its parameters. Once the model is obtained, it serves as a foundation to build the controllers that shall follow references in altitude and depth. These references are the timed values of depth (or altitude) at which the vehicle should be at each time instant. Water covers an extensive parcel of the planet Earth. And what is under the surface is many times inaccessible to human divers, or at least dangerous to achieve, but may also present important resources to mankind. As, by the ONU Law of the Sea, [6], this underwater area is on the jurisdiction of each country, the research in subaquatic exploration has increased over the years. Through the use of Autonomous Under-water Vehicles, AUV’s, bigger depths are accessible and during more time at each dive. For instance, robots as the Medusa can be pro- grammed to scan an entire harbour at constant altitude, which would reduce costs in the operation while providing reliable data. However, this kind of procedure requires controllers as the ones explained on this paper. The altitude controller as well as the two depth controllers were designed and tested in simulation, and have proven to be efficient on the following of adequate references in that environment. This results can be used in practice to guide the vertical movement of the Medusa, as further explained in Section V. In order to design these controllers some modelling work was necessary. The vehicle model was done based on the findings of Fossen, [9] and the parameter identification on the work of Ridao, [5], which constitutes the state of the art in the subaquatic robots model and identification. An intermediate step was the attainment of the same work, but relatively to the Thrusters. In this area, the most recent developments were presented by Healey, [10], and Whitcomb, [11], which offer several models based on the physic param- eters of the system to model. The remainder of the paper is organized as follows: the frame system used and the initial problem formulation - vehicle used and existing forces - are described in Section II. In Section III, the physical model of the vehicle as well as the identification method and results of the model parameters is introduced. Section IV describes the design of each controller, including the final Simulink block diagrams. The results of both simulations and water tests are presented in Section V. Finally, the conclusions are stated in Section VI, which also refers the future work to be done. II. PROBLEM FORMULATION In order either to model the vehicle or to control it, first it is necessary to define the frames to use. In this case there are two important sets of frames: the Body Frame, whose origin is in the vehicle centre of mass, and the Inertial Frame, whose origin is at the water’s surface. The Body Frame has the: - X-coordinate pointing to the front of the vehicle (x B ); - Y-coordinate to the vehicle’s right (y B ); - Z-coordinate to the bottom of the vehicle (z B ). The Inertial frame, also known as the Universal frame, has the - X-coordinate pointing towards East (x U ); - Y-coordinate pointing towards North (y U ); - Z-coordinate pointing towards the ocean floor (z U ). This information can be easily visualized in figure 1. To further reference in the paper, the table I sums up all the denominations of the:
Transcript

1

Sensor-Based Formation Control of AutonomousRobotic Vehicles

Ana Cristina Resendes Maia

Instituto Superior Tecnico - Institute for Systems and Robotics (IST-ISR)Lisbon 1049-001,Portugal

November 2013

Abstract—This thesis objective is to produce controllers of bothdepth and altitude specially dedicated to navigate the subaquaticvehicle, Medusa, in the vertical plan.

To fulfil this goal, first it was necessary to model the vehiclebehaviour when moving vertically and identifying the parametersof this model. This was done resorting to physical models andempiric measurements.

After, two types of controllers were designed and simulated: asimpler one based on a linearised version of the vehicle’s modeland a more complex one that compensated all the non-linearityof the vehicle allowing precise following. These controllers weresubjected to extensive simulation in computer environment andthe first and simpler one was tested in sea water.

Based on the results of both simulations and real tests,the controllers can successfully control the Medusa verticalmovement and follow, in the second controller case, more complexreferences.

Index Terms—Medusa, modelling, identification, depth, alti-tude, precise following

I. INTRODUCTION

The purpose of this work, developed in the MORPH projectenvironment, [3], is to obtain controllers that can navigate anunder-water specific vehicle, Medusa, on the vertical plan. Thisincludes finding a model that accurately describes the vehiclevertical movement and identifying all its parameters.

Once the model is obtained, it serves as a foundation tobuild the controllers that shall follow references in altitudeand depth. These references are the timed values of depth (oraltitude) at which the vehicle should be at each time instant.

Water covers an extensive parcel of the planet Earth. Andwhat is under the surface is many times inaccessible to humandivers, or at least dangerous to achieve, but may also presentimportant resources to mankind. As, by the ONU Law of theSea, [6], this underwater area is on the jurisdiction of eachcountry, the research in subaquatic exploration has increasedover the years.

Through the use of Autonomous Under-water Vehicles,AUV’s, bigger depths are accessible and during more timeat each dive. For instance, robots as the Medusa can be pro-grammed to scan an entire harbour at constant altitude, whichwould reduce costs in the operation while providing reliabledata. However, this kind of procedure requires controllers asthe ones explained on this paper.

The altitude controller as well as the two depth controllerswere designed and tested in simulation, and have proven to

be efficient on the following of adequate references in thatenvironment. This results can be used in practice to guidethe vertical movement of the Medusa, as further explained inSection V.

In order to design these controllers some modelling workwas necessary. The vehicle model was done based on thefindings of Fossen, [9] and the parameter identification on thework of Ridao, [5], which constitutes the state of the art inthe subaquatic robots model and identification.

An intermediate step was the attainment of the same work,but relatively to the Thrusters. In this area, the most recentdevelopments were presented by Healey, [10], and Whitcomb,[11], which offer several models based on the physic param-eters of the system to model.

The remainder of the paper is organized as follows: theframe system used and the initial problem formulation -vehicle used and existing forces - are described in Section II.In Section III, the physical model of the vehicle as well as theidentification method and results of the model parameters isintroduced. Section IV describes the design of each controller,including the final Simulink block diagrams. The results ofboth simulations and water tests are presented in Section V.Finally, the conclusions are stated in Section VI, which alsorefers the future work to be done.

II. PROBLEM FORMULATION

In order either to model the vehicle or to control it, first itis necessary to define the frames to use. In this case there aretwo important sets of frames: the Body Frame, whose originis in the vehicle centre of mass, and the Inertial Frame, whoseorigin is at the water’s surface.

The Body Frame has the:- X-coordinate pointing to the front of the vehicle (xB);- Y-coordinate to the vehicle’s right (yB);- Z-coordinate to the bottom of the vehicle (zB).

The Inertial frame, also known as the Universal frame, hasthe

- X-coordinate pointing towards East (xU );- Y-coordinate pointing towards North (yU );- Z-coordinate pointing towards the ocean floor (zU ).

This information can be easily visualized in figure 1.To further reference in the paper, the table I sums up all the

denominations of the:

2

Fig. 1: Frames Definition, [4]

- movements of the Body frame in the Universal one -movement;

- forces along and around the axis of the Universal Frame- force;

- velocities in the movements directions - velocity;- position and orientation of the Body frame in the

Universal frame - position.

Movement Force Velocity Positionxdirection surge X u xydirection sway Y v yzdirection heave Z w zarroundx roll K p φarroundy pitch M q θarroundz yaw N r ψ

TABLE I: Coordinates and orientation of the Robot Frame inthe Inertial Frame

As observable in Figure 2, the Medusa robot is an assem-bling of two acrylic cylinders locked together in an aluminiumframe. Apart from the thrusters, echo-sound and mast, whichare outside the cylinders, and the depth cell, which is indirect contact with the water though from inside the extremityaluminium caps, all the remaining components are protectedin vacuum inside the tubes. This includes the PC in the uppercylinder and the battery sets on the bottom one.

The communications between the vehicle and the consoleare done through wi-fi. However, when the vehicle is sub-merged, this means that an antenna needs to be attached to anexternal float and connected to the vehicle through a cable.

Using the notation from Table I and adapting the circum-stances to the Medusa case, a model of the robot can becomputed as well as controllers to navigate it.

III. MODEL AND PARAMETER IDENTIFICATION

A fundamental physics law states that the sum of all forcesapplied to a body are equal to the total mass of that body timesits acceleration. Concerning the particular hydrodynamics ofthe vertical movement, the forces applied to a body are quitesimilar to what was accounted for in [1]:

- Weight (W) - downwards gravitic force;- Buoyancy (B) - upwards force from the fluid;- Thrust (T) - force applied by the thrusters;- Damping (D(η))- sum of the drag, lift and friction

between water and vehicle surface;

Fig. 2: Medusa Schematic with size information

- Coriolis (C) - force generated by the uniform rotationof a frame.

However, the Coriolis Force is negligible, once that, for thestudy case, the rotation of the frames are minimal. Moreover,also the damping force can be reduced to its vertical linearand quadratic drag terms (−Zwz and −Zw|w|z|z|), consideringthat this is the predominant effect.

Another important observation is that the total mass of thevehicle, in hydrodynamics, is the sum of its mass (m) withan added mass (Ma), resultant from the deflection of a certainvolume of fluid with the body movement in it.

An assumption accounted for, that was afterwards con-firmed, is that the pitch is nearly null. This means that thevelocity in heave w is equal to the first derivative of the depthin order to time z.

Assembling these statements in one unique equation thatdescribes the vertical movement of the vehicle, it results onEquation 1.

W +B + T + (−Zwz − Zw|w|z|z|) = (m+Ma)z (1)

Dividing all the previous equation by the total mass of thevehicle and assembling the Weight and Buoyancy as a resultantexternal force (W+B), it results on Expression 2 which can besimplified as shown in Equation 3.

−Zwz

m+Ma+−Zw|w|z|z|m+Ma

+1

m+MaT +

W +B

m+Ma= z (2)

αz + βz|z|+ γT + δ = z (3)

The equation 3 was then introduced in a Least Squaresalgorithm, [2], similarly to what was done in [5], in order toidentify the model parameters: α, β, γ and δ. These parameterswere assembled in a vector and the matricial expression 4 wasimplemented with data from real in-water trial, at EMEPC poolin February 15th, 2013.

3

y = Hθz1z2...zN

=

z1 z1|z1| T1 1z2 z2|z2| T2 1... ... ... ...zN zN |zN | TN 1

αβγθ

(4)

As the trial only produce the depth values and the rotationvelocity of the thrusters, some further computations wereneeded. For instance, the depth, sampled at 5 Hz, was derivatedonce to obtain the velocity, z, and twice for the acceleration,z. The thrust was computed inputting the rotation velocity, ωin the Equations 5.

These equations were obtained, fitting a quadratic curveto groups of collected data for the functioning points of thethrusters when the thrusters were pushing the vehicle up, fornegative commands, or down, for positive commands. All thedata was collected in Bollard Pool (the vehicle without surge,sway or rotational movement) and assumed to be similar tothe one verified when the vehicle was moving.

Tup = −8.9241× 10−3ω2 − 2.2773× 10−3ω[N ], ω < 0Tdown = 8.4661× 10−3ω2 + 18.9623× 10−3ω[N ], ω > 0

(5)These curves can be seen in image 3, being the blue curve

associated with the vehicle going upwards and the red onerepresenting the downwards movement.

Fig. 3: Command-to-Thrust transfer function - Vehiclemoving upwards is blue and downwards red

The results obtained from this procedure are shown in TableII, for the vehicle nominal mass of 30 kg.

Parameter Value Physical Parameter Valueα -0.1300 Zw -6.4369β -2.4338 Zw|w| -120.4854γ 0.0202 Ma -19.4311 [kg]δ -1.1173 W +B -1.0971 [N]

TABLE II: Results from the Least Square algorithm on theParameter Identification

The delta factor only refers to one specific trial, as this valuechanges with the type of water (salted or fresh), the watertemperature and the number and kind of sensors attached tothe vehicle. However, this parameter will be neglected on thecontroller design, as the integral part of the controller learnsand compensates its value.

IV. CONTROLLER DESIGN

Three controllers were developed in this project scope:a simple depth controller, based on the vehicle linearisedmodel, Subsection IV-A; a more complex depth controllerthat compensates the model non-linearities, allowing precisefollowing of complex references, Subsection IV-B; and analtitude controller, based on an adapted version of this lastdepth controller to altitude references, Subsection IV-C.

To implement this controller, some general blocks wererequired. These blocks performed general tasks necessary foreach one of the controllers.

The Kalman Filter, [8], is used in every implementation, asan observer, in order to remove the noise and outliers addedto the measurements by the sensors and estimate the verticalvelocity. It uses the Medusa’s dynamics in state space, inform of matrices A and B. For the precise following case,the matrix L is also used to compensate the non linearities,expression 6. This filter output is a weighted average betweenthe estimation of the vehicle’s position and the measurementsfrom the sensors.

Its states are the vertical position of the robot, its velocityin heave and the delta factor.

˙x = Ax+Bu+ L zz

δ

=

0 1 00 α 10 0 0

zzδ

+

00γ

T +

00βz|z|

(6)

So, as mentioned, the simpler depth controller uses only thematrices A and B, whereas the precise following uses also thenon linearities. This filter still needs to be discretized in orderto be used, as the data provided by the robot is not continuousin time. This discretization results on the equation 7, bellow.

xk+1 = Axk +Buk + L ˙zk+1

zk+1

δk+1

=

1 Ts 00 1 + αTs Ts0 0 1

zkzkδk

+

+

00γTs

Tk +

00βzk|zk|Ts

(7)

When adapting this filter to altitude control, some signalchanges are needed, due to the frame changes further explainedin subsectionIV-C. The drag factors remain, as its signalis always symmetric to the movement, and only the deltaand thrust signals change. This happens because upwardscommutes from being the negative direction to be the positiveone. The new equations system is reproduced in expression 8.

xk+1 = Axk +Buk + L ˙zk+1

zk+1

δk+1

=

1 Ts 00 1 + αTs −Ts0 0 1

zkzkδk

+

+

00−γTs

Tk +

00βzk|zk|Ts

(8)

4

Another essential block is the reference filter, whichsmooths the references given in depth and computes its firstand second derivatives. The smoothing of the depth referenceis specially important when it is originally a step, as no vehiclecan follow that kind of reference and change its positioninstantaneously. The results of this filter are presented onimage 4

The remaining signals are essential to the controller com-putation as further explained in each subsection bellow.

Fig. 4: Input and Outputs of the Reference FilterDark Blue - Raw mission [m];

Green - Filtered Altitude Reference [m];Red - Velocity Reference [m.s−1];

Blue - Acceleration Reference [m.s−2]

An Anti-Windup block was used to perform the integralpart of the controller. This block dismisses the Windup effect,allowing the integral part of the controller to decrease as soonas the error changes its signal, even in saturation cases.

This block uses a feedback loop to discount the saturationexcess from the input to the integral.

The Thrust-to-Command block was necessary due to thefact that the controller output was computed in thrust, butthe thrusters only received commands in rotations per minutepercentage (rpm %). This block is then an interface betweenthe controller and the vehicle.

The needed expression can be obtained solving the alreadycomputed function Command-to-Thrust, expression 5, in orderto the rotation velocities, resulting in 9.

Cup =2.2773×10−3+

√(−2.2773×10−3)2−4×8.9241×10−3×T2×−8.9241×10−3

Cdown =−18.9623×10−3+

√(18.9623×10−3)2+4×8.4661×10−3×T2×8.4661×10−3

(9)All these blocks only fully control the vertical movement

of the vehicle if assembled together as in image 5. With thisscheme, it is possible to control the vehicle vertical positionwith more or less precision, depending this on the controllerblock chosen and its gains.

The disturbance block shown in image 5 refers to simulatedexternal forces which are not accounted for in the controllerprojection. These disturbances are therefore added inside theModel block to the thrust it receives.

A. Simple Depth Controller

This controller is a PID (proportional integral and derivativecontroller) based on a linearised version of the Medusa modeldescribed previously, and whose architecture is shown inimage 6. This new version of the model discards its non lin-earities, more precisely the delta coefficient and the quadraticterm of the model, though the delta term is compensatedthrough the integral part of the controller.

The linearised vehicle model in state space, necessary tocompute the gains uses three states and an input, the thrust,as shown in expression 10

˙x = Ax+Bu zzz

=

0 1 00 0 10 0 α

∫z

zz

+

00γ

T (10)

The gains of this controller were computed through LQR,[7], with the error matrices being a normalization of the errors(by the maximum error admitted for each term) times a weightto calibrate the controller. The objective of this algorithm isto minimize both the state variations, stabilizing the vehiclebehaviour, and the actuation, allowing less consume of energy.

The maximum error allowed was 2.5 meters in distance, 0.5meters per second in velocity, 2.5 x 5 meters second in theintegral term and 1% in the command. After dividing the errorsby this normalization, the coefficients are then multiplied bythe weights which are tuned to allow more rapid and/or stableresponses. This tuning is done through simulation in idealconditions - without noise or disturbances, and using a step asreference.

The weights and resultant gains that were found to optimizethe controlling activity are presented in expression 11.

wi = 10 → ki = 3.3645wp = 4 → kp = 17.1174wd = 0.6 → kd = 48.2326

(11)

B. Precise Following Depth Controller

When facing the results from the previous depth controller,it was found that the discarding of the quadratic term hadundesirable and strong effects, related with the stability of thecontroller. Moreover, in complex references with several steps,the previous controller is unable to follow them.

To compensate these effects, a new controller was designed,based on all the vehicle model and the non-linear control,which allows precise following of the references. The firststep of this design was to define the error, equation 12.

e = z − re = z − re = z − r

(12)

After defining the error, the term z was substituted by theentire vehicle model. The second derivative of the error wasreplaced by its corresponding expression from the controllergains in the feedback loop, equation system 13.

5

e = αz + βz|z|+ γu+ δ − re = −K1e−K2e−K3

∫e

(13)

This equation system was then solved in order to theactuation variable, the thrust, and the delta factor. As donein the first controller, the delta factor was neglected, onceit is already compensated by the integral component of thecontroller. The resulting expression 14 was then implementedin the Simulink Block Diagram illustrated in image 7.

T =1

γ(K1(r−z)+K2(r−z)+K3(

∫r−

∫z)−αz−βz|z|+r)

(14)As it can be seen, the controller now includes the terms

from the non linearity and also the second derivative of thereference. Both these components enable the vehicle to havea smother and stable movement and to follow the referenceswith less error, even when dealing with complex references.

The gains, as done previously, were computed with the LQRalgorithm, but with some differences. The drag terms werenot seen as states, but instead as entries of the system. This

caused the system to be redefined in terms of state space asin expression 15.

˙x = Ax+Bu zzz

=

∫z

zz

0 1 00 0 10 0 0

+

0 0 00 0 01 1 1

αzβz|z|γT

(15)

Also the maximum errors allowed changed: the maximumdistance error changed to 1 meter, the maximum velocity error0.5 meters per second and the maximum integral error 0.5meters for 5 seconds.

After extensive tuning, again in ideal conditions, the result-ing weights and gains used are stated bellow, expression 16.The gains to the entries of the systems are all 10.

wi = 0.08 → ki = 0.0327wp = 0.3 → kp = 0.3015wd = 20 → kd = 1.2387

(16)

Fig. 5: Complete simulation assembled.

Fig. 6: Simple Depth Controller Schematic

6

C. Precise Following Altitude ControllerAs a result of the depth precise following controller good

performance, the same algorithm was applied to controlaltitude. This adaptation required a change of frame and,consequently, a new fit of both vehicle model (reflected on theModel block and the Kalman filter block) and the controller.

The new frame adopted for this controller design is shownin image 8. The new referential has its origin at the oceanbottom and the Z-axis pointing towards the surface.

Fig. 8: Frame for Altitude Control Design

From the schematic in image 8, the conclusions mathemati-cally expressed in expression 17 can be withdrawn, with someassumptions. The main assumption is that the ocean floor isapproximately plan, not having any kind of topography or thatit changes very slowly when the vehicle moves in surge. Ineither case the first and second derivatives of f(x, y) are nullall the time.

These expressions can then be replaced on the original vehi-cle model, creating a new description for the robot movementin this new frame, equation 18.

f = z + h↔ h = f − z0 = z + h↔ h = −z0 = z + h↔ h = −z

(17)

h = −(αz + βz|z + γT + δ) = αh+ βh|h| − γT − δ (18)

Similarly to what was done in the precise following depthcontrol, and establishing the error as shown in equation 19,the equalities from expression 20 surge.

e = h− r (19)

e = αz + βz|z|+ γu+ δ − re = −K1e−K2e−K3

∫e

(20)

When the two equations are equalled and solved in order tothe actuation T, the controlling expression to this new modelsurges as equation 21.

T = u = − 1

γ(r−αh−βh|h|+kp(r−h)+kd(r−h)+ki(

∫r−

∫h))

(21)This expression is then translated to a block diagram in

Simulink as done in the Precise Following Depth Controller.The resulting schematic is very similar to the one shown infigure 7

The gains of this controller are the same as the precisefollowing for depth control once they were obtained by thesame algorithms, using the same weights and similar matrices.The only change in this field was, similarly to what happenedin the Kalman filter case, was the inversion of the signal ofthe γ which is done directly in the input and not in the matrix,resulting in the expression 22

˙x = Ax+Bu zzz

=

∫z

zz

0 1 00 0 10 0 0

+

0 0 00 0 01 1 1

αzβz|z|−γT

(22)

V. SIMULATIONS AND TEST RESULTS

A. Simulations in MatlabAll the controllers were subjected to extensive simulation in

order to detect incorrect behaviours that may happen in reality.

Fig. 7: Implementation of the control function 14

7

These trials include references as steps or combinationsof steps changing in quick succession, performing each trialwith and without noise and with or without disturbances.These disturbances assumed step form, simulating a force thatsuddenly starts and maintains at constant value, or pulse form,as short duration forces such as pushes. Also a constant biason the buoyancy factor was simulated.

The simpler depth controller revealed to be slow to convergein case of disturbances, but eventually follows the referenceif it is a step. This happens due to the filters being tuned to along settling time, which provides more stable results.

On the other hand, if the depth reference is more complexthan a succession of steps, the controller is not quick enoughto keep up, and eventually diverges, as shown in picture 9.

Fig. 9: Result of simulations of the simpler controller withquickly changing steps

Dark Blue - Depth Reference [m];Green - Simulated Depth [m];

Red - Thrusters Commands x0.1[% rpm];Blue - Vertical Velocity [m.s−1]

The precise following however, is able to cope with thiskind of references as seen in image 10. Despite the fact thatthe oscillations when in steady state are bigger that in theprevious controller. Relevant oscillations in depth (more than10 cm of amplitude) are not registered.

Fig. 10: Result of simulations of the complex controller withquickly changing steps

Dark Blue - Depth Reference [m];Green - Simulated Depth [m];

Red - Thrusters Commands x0.1 [% rpm];Blue - Vertical Velocity [m.s−1]

It was also noticed that the settling time, that is, the timethe controller takes to stabilize at less than 5% of the final

value, was reduced to almost half of the one from the previouscontroller.

The response of this controller to disturbances is best seenin the case where the reference is a simple step, as reproducedon figure 11. There is a natural deviation from the referencedpath, but it is compensated in a short time span.

Fig. 11: Result of simulations of the complex controller witha step like disturbance

Dark Blue - Depth Reference [m];Green - Simulated Depth [m];

Red - Thrusters Commands x0.1 [% rpm];Blue - Vertical Velocity [m.s−1]

when inserting an external force it is noticeable that thefunctioning point of the vehicle changes, reducing the oscil-lation of the command when in steady state. This happensbecause, in the new functioning point , the slope of the func-tion Thrust-to-Command is less abrupt, so to small changes inthe trust correspond smaller fluctuations in the commands.

The simulations concerning the altitude controller presentedsimilar results and behaviours as the ones with this last depthcontroller, the precise following one. This was expected, as thealtitude controller follows the same logic used on the precisefollowing depth one, only applying a small change of frame.

So, in normal conditions, the altitude controller is able tofollow simple and complex altitude references, with reducederror and quick recover from disturbances.

The most relevant experience made with the altitude con-troller was the test to see how it would respond to smallchanges on the terrain morphology, as in practice the oceanfloor is not plan, but irregular.

To perform this simulation, some smoothed steps of dif-ferent amplitudes were added in sequence, so to simulate apossible topological model, to the simulated depths that wouldbe read by the vehicle. These values were then entered onthe Kalman filter, were inserted on the feedback loop andperceived by the controller as changes on the altitude.

As seen in image 12, the controller deals with this circum-stances, even though it was projected for a plan ground, and itis capable of maintaining the altitude when such is required.

The gains presented on Section IV were tuned so that afluctuation of the model parameters was allowed, not compro-mising the normal behaviour of the controller. The maximumfluctuation considered acceptable was more or less 50% ofeach parameter.

8

Fig. 12: Result of simulations of the altitude controller withthe ocean floor with topology

Dark Blue - Altitude Reference [m];Green - Simulated Altitude [m];

Red - Thrusters Commands x0.1 [% rpm];Blue - Vertical Velocity [m.s−1]

In simulation, the worst case scenario happens when all theparameters are at 50% of what was estimated. Even for thishuge discrepancy between reality and estimation, the controllerwas able to react and behave, even though the oscillationsin steady state increased to their double. An example of thisbehaviour is presented in image 13.

Fig. 13: Result of simulations of the precise following depthcontrol with 50% mismatch between real parameters of the

robot model and the simulated ones.Dark Blue - Depth Reference [m];

Green - Simulated Depth [m];Red - Thrusters Commands x0.1 [% rpm];

Blue - Vertical Velocity [m.s−1]

B. Real Trial

Due to vehicle malfunctions, only the simpler depth con-troller could be tested in sea water. Some of the results fromthis trial are reproduced on figure 14, which consisted in twodives with a pause in between so that the robot may resurface.The vehicle when submerged, should maintain itself at 1 meterof depth, with or without horizontal movement. This trial wasexecuted at July 15th, at EXPO dock, in Lisbon.

The small oscillations, seconds after the robot stabilises atthe 1 meter depth, are the consequence of a pitch caused by theinitial acceleration of the horizontal movement. This behaviouris, however, quickly compensated, and the vehicle maintainsits referenced depth.

Fig. 14: Testes performed at EXPO dock with a MedusaDiver, July 15th

Dark Blue - Thrusters Commands x0.1 [% rpm];Red - Depth Readings [m]

The overshoot of 20 cm is a direct consequence of the non-existence of compensation of the non-linearities of the vehiclemodel, disregarded on the design of this controller.

Although the precise following controllers were unable to betested in real conditions, the similarities between the behaviourof the simulations and reality of the controller tested lead to theconclusion that these controllers should perform as expected.

VI. CONCLUSIONS

As seen from the results presented on the previous Section,the simpler controller works well with simple references assteps, but does not respond adequately when subjected toquickly changed references. To that kind of more complexreferences, it is necessary the precise following controllers,which also provide more quick reactions, specially in case ofdisturbances.

Although only the simpler controller was tested in water,due to vehicle malfunctions and time constraints. Its similaritywith the simulations suggest that the same pattern will beobserved on the remaining two controllers.

It was also observed that the chosen gains for the controllersallow a fluctuation of the model parameters until 50%, whichgives a certain degree of relaxation when doing minor updatesto the vehicle.

Another point to highlight is that, for the study case, thefunctioning point in steady state is at 10% of the total capacityof the thrusters. This means that, as in this area the slopeof the function Thrust-to-Command is very high, so thatsmall changes in the thrust correspond to big fluctuations ofcommand. This is the main reason why there are oscillationson the command when the vehicle maintains itself at constantdepth. However, due to the small amplitude of this oscillation,it does not represent a risk to the thrusters live span, reasonwhy it was considered acceptable.

There is still, work to be done. For instance, updatingsensors (a sensor that directly provides the velocity wouldbe helpful) or researching new algorithms that automaticallycalibrate the model parameters when detected inconsistencyof the controller. Also algorithms in case of the altitudecontroller that deal with the terrain geography and other ways

9

of communication between the submerged vehicle and theoperating console. It would also be advisable to test the precisefollowing designed controller in sea water, both for depth andaltitude.

ACKOWNLEDGEMENTS

I could not have written this thesis and accomplished thisresults without the help of many. Not wanting to minimize thecontribution of everyone, some names needed to be highlighteddue to their essential role in this process.

This thesis would not have happened without ProfessorAntonio Pascoal, whose vast expertise in the area guided methrough difficult situations, always directing me in the rightdirection. To the entire project team, specially to Joao Botelho,Jorge Ribeiro, Luıs Sebastiao, Manuel Rufino, Miguel Ribeiroand Filipe Morais, by their help and attentive suggestionsduring the work development as well as the dissertationwriting.

REFERENCES

[1] A. Pascoal and P. Aguiar, Vehicle Modeling, Presentation at GraduateSchool on Control, Supelec, Feb 21-25,2011

[2] Takeaki Kariya and Hiroshi Kurata. Generalized Least Squares, volume7 of Wiley Series in Probability and Statistics. John Wiley & Sons, Lta,Chichester 2004.

[3] Project Morph. Marine robotic system of self-organizing, logicallylinked physical nodes, Project Morph News, March 2013, Avail-able: http://morph-project.eu/index.php/news/77-marine-robotic-system-of-self-organizing-logically-linked-physical-nodes [Accessed: July 16th,2013]

[4] J. Ribeiro. Motion Control of Single and Multiple Autonomous MarineVehicles. Master Thesis, Instituto Superior Tecnico - UniversidadeTecnica de Lisboa, Lisboa, October 2011.

[5] P. Ridao, A. Tiano, A. El-Fakdi, M. Carreras, and A. Zirilli. On theidentification of nonlinear models of unmanned underwater vehicles.Control Engineering Practice, 12(12):1483-1499, December 2004.

[6] ONU. Agreement Relating to the Implementation of Part XI of the UnitedNations Convention on the Law of the Sea, December 1982 Available:http://www.un.org/Depts/los/convention agreements/texts/unclos/closindx.html[Accessed: June 28th, 2013]

[7] B. Astrom, K. J. and Wittenmark. Computer Controlled Systems: Theoryand Design. Prentice Hall, 1997.

[8] Sebastian Thrun, Dieter Fox and Wolfram Bugard, ProbabilisticRobotics, Intelligent Robotics and Autonomous Agents series, MIT Press,2005.

[9] Thor I. Fossen, Marine Control Systems, Marine Cybernetics, Trond-heim, Norway, 2002.

[10] A. J. Healey, S.M. Rock, S. Cody, D. Miles, and J.P. Brown. Toward animproved understanding of thruster dynamics for underwater vehicles.IEEE Journal of Oceanic Engineering, 20(4):354-361,1995.

[11] L.L. Whitcomb and D.R. Yoerger. Comparative experiments in the dy-namics and model-based control of marine thrusters. ”Challenges of OurChanging Global Environment”. Conference Proceedings. OCEANS ’95MTS/IEEE, 2(5):1019-1028, 1995


Recommended