分享

JMSE | An Open-Source Benchmark Simulator: Control of a BlueROV2 Underwater Robot

 netouch 2023-08-11 发布于北京

1. Introduction

The area of remotely operated vehicles (ROVs) and autonomous underwater vehicles (AUVs) has rapidly developed, with several decades of experience, both in research (see, for example, the study described in [1]) and industrial applications of increasing complexity, both in terms of missions and levels of automation (see for example [2] on cooperative navigation). Regarding the latter, many control algorithms have been proposed, both for simulated and actual vehicles. However, it is generally not immediate to compare control algorithms between them. Indeed, while some articles comparing newly-proposed control laws for ROV stabilization to previous algorithms can easily be found [3,4,5,6,7,8], it is primarily based on simulation models for which the actual physical replica is not easily accessible or affordable, thereby limiting the comparability between control algorithms and the extent of the benchmarking attempt.
More recently, the industry has also evolved towards more affordable products meant for researchers, students, or hobbyists, several of which are proposed under the open-source paradigm (see, for example, OpenROV, OpenROV Trident, BlueROV2) [9]. The advantages of open software and hardware solutions lie in their cost-effectiveness compared to conventional solutions and that they allow increasingly faster development, modifications, and improvements. Among these solutions, the widely-popular BlueROV2 [10] combines an open-source architecture with components of sufficiently good quality, allowing relatively advanced missions (see, for example, [11,12,13]).
Several robot simulators have previously been developed, some of which are specific for underwater robots [14,15,16]. However, the simulators for underwater robots are generally based on a user-defined model, such as the UUV Simulator [14] package for Gazebo or the Simu2VITA [15] block for Simulink™, which makes it challenging to use as a benchmark for control algorithms. Furthermore, these simulators neglect the tether force many underwater robots use for top-site communications or power [17]. The present paper aims at bridging the gap between simulation for control systems and experimental testing by proposing a MATLAB™ and Simulink™ open-source package of the tethered BlueROV2 for the control community as a benchmark in simulation toward full deployment on the same well-known platform. MATLAB™ and Simulink™ have been chosen as they are well-known to the control community and offer various toolboxes to implement advanced control and missions. These missions could be measuring reefs [18], monitoring and removal of marine growth on offshore structures [3,19,20], water quality and ecology monitoring [21], detection of oil plumes [22], fish farm net monitoring [23], etc.
Section 2 will be dedicated to the presentation of the BlueROV2 platform in terms of hardware (frame, thrusters, sensors). In Section 3, we recall the dynamic equations of motions of underwater vehicles propelled by thrusters using the well-known 𝛈- 𝛎 Fossen notation [24]. The parameters of this model are then identified for the particular case of the BlueROV2 in Section 4, and the model is then validated using experimental data. Since the tether attached to the ROV has a significant impact on the dynamics, it is included in the overall model, see Section 6. Section 7 proposes a sliding-mode controller meant as a benchmark for the community to compare against subsequent controllers. Section 8 then starts with the presentation of a modular simulator fully implemented in MATLAB™ and Simulink™ and based on the model from Section 3 and the parameters from Section 4. Appendix B provides a detailed guide to using the simulator. Section 9 examines a case study on offshore monopile inspection to demonstrate the use of the proposed simulator. Finally, a few concluding remarks end the paper. The proposed simulator can be found at Github in Supplementary Materials, accessed on 1 October 2022.

2. BlueROV2: An Open-Source Underwater Vehicle

The BlueROV2 is a tethered ROV. The tether is used for communication between the vehicle and a top-side unit. The vehicle can be powered either through the tether or by an onboard battery. The ROV comes with various onboard sensors, including a pressure transmitter, leak detection sensors, a power sense module, an Inertial Measurement Unit (IMU), and a magnetometer. The IMU consists of an accelerometer and a gyroscope. The IMU and magnetometer are integrated in a Pixhawk. The open-source software architecture allows adding additional sensors such as an Underwater Acoustic Positioning System (UAPS), Doppler Velocity Log (DVL), camera vision, sonar, lasers, etc. Software implementation of the sensors on the physical hardware can be done on the Pixhawk through ArduSub or on the Raspberry Pi using the MAVLink protocol. However, the simulator is based on MATLAB™and Simulink™, and therefore implementation on the physical hardware is not considered. A list of common sensors and their properties is shown in Table 1, where the associated state measurements are given according to the notation used in the model presented in the next section.
Table 1. List of common sensors used for the BlueROV2.
The main control board on the BlueROV2 is a Raspberry Pi 3, which is connected to a top-side computer through an Ethernet connection. Besides the Raspberry Pi 3, the electronic tube contains a Pixhawk. The Ethernet communication is transferred top-side through a Fathom-X Tether Interface, which provides a long-distance Ethernet connection over a single twisted pair of wires. The hardware and interfaces of the BlueROV2 is shown in Figure 1.
Figure 1. Hardware and interfaces on BlueROV2, green boxes represents sensors, black boxes represents processing units/control units, the yellows boxes represents actuators, and the dashed blue line illustrates the cut between onboard hardware and topside hardware.
Blue Robotics Inc.’s heavy configuration kit is installed as additional equipment on the BlueROV2, which includes two additional T200 thrusters, such that the thrusters can be paired to move in all degrees of freedom. This modification is illustrated in Figure 2. The difference in thruster allocation between the normal and the heavy configuration is shown in Figure 3 and Table 2, the most noticeable difference is that the heavy configuration is controllable in pitch. Tools can be installed for specific operations, such as a gripper (purchased together with the BlueROV2), a water jet [3], etc.
Figure 2. Two illustrations of the BlueROV2 with and without heavy configuration, respectively.
Figure 3. A comparison of the thruster configuration of the normal and heavy BlueROV2. The blue thrusters are the clockwise thrusters, and the green are the counterclockwise thrusters. The red arrow is the positive surge direction [25]. (a) BlueROV2 normal configuration. (b) BlueROV2 heavy configuration.
Table 2. Difference between thruster combination to motion on normal and heavy configuration.

3. Mathematical Modeling

In the following, we will distinguish between the body or b-frame and world or n-frame as illustrated in Figure 4, where the respective degrees of freedom are visualized in each frame.
Figure 4. The reference and world frame with all degrees of freedom in each respective frame.
In this section, we recall the standard mathematical model of an underwater vehicle, to which the BlueROV2 applies. This model is based on the following few assumptions:
Assumption 1.
The vehicle is assumed to be rigid, and 6 degrees of freedom are considered.
Assumption 2.
The ROV is assumed symmetric around the front-back, port-starboard and the top-bottom axes.
Assumption 3.
The body axes coincide with the principles axes of inertia.
Assumption 4.
The origin of the b-frame is located at the center of mass of the vehicle.
Remark 1.
The Assumptions 1–4 are common when modeling underwater vehicles [26].
Assumption 5.
The ocean current is modeled as a constant irrotational flow in the n-frame. The current is projected on the ROV as a change in velocity. Waves are neglected.
Remark 2.
The Assumption 5 is a simplified model of the current, as ocean currents are mainly caused by tidal movements and can be dependent on both the local climate and the geographic characteristics [27]. Furthermore, the current velocity varies both with space and time. However, from a control perspective where the current acts as a disturbance to the system, the time dependency can be neglected due to the relatively slowly varying current compared to the dynamics of the controlled system [26].
In the following, we will use the well-known compact 𝛈𝛎 Fossen notation (first proposed in [28]), itself gathering in a vectorial form elements of the SNAME nomenclature (see [29,30], and a list of the variables and parameters used hereafter summarized in Table 3). It is given by
𝛈˙=𝑱(𝜼)𝝂
𝑴𝝂˙+𝑪(𝝂)𝝂+𝑫(𝝂)𝝂+𝒈(𝜼)=𝝉+𝝉𝑡𝑒𝑡
where 𝝂=[𝑢,𝑣,𝑤,𝑝,𝑞,𝑟]𝑇 is the vector of body-fixed velocities (surge, sway, heave, roll, pitch and yaw) and 𝛈=[𝑥,𝑦,𝑧,𝜙,𝜃,𝜓]𝑇 is the vector combining the positions and Euler angles with respect to the n-frame. The vector 𝛕=[𝑋,𝑌,𝑍,𝐾,𝑀,𝑁]𝑇 contains the forces and moments applied to the vehicle.
Table 3. Definitions of variables.
Equation (1) represents the kinematic equations of motion, where
𝑱(𝜼)=[𝑱1(𝜼)03×303×3𝑱2(𝜼)],
and
𝑱1(𝜼)=cos𝜓cos𝜃sin𝜓cos𝜃sin𝜃sin𝜓cos𝜙+cos𝜓sin𝜃sin𝜙cos𝜓cos𝜙+sin𝜙sin𝜃sin𝜓cos𝜃sin𝜙sin𝜓sin𝜙+cos𝜓cos𝜙sin𝜃cos𝜓sin𝜙+sin𝜃sin𝜓cos𝜙cos𝜃cos𝜙
𝑱2(𝜼)=100sin𝜙tan𝜃cos𝜙sin𝜙/cos𝜃cos𝜙tan𝜃sin𝜙cos𝜙/cos𝜃,
where let us recall that 𝑱2(𝜼) is not defined when 𝜃={𝜋,𝜋}[2𝜋].
The constant, symmetric and strictly positive definite inertia matrix 𝑴=𝑴𝑅𝐵+𝑴𝐴 combines the rigid-body inertia matrix 𝑴𝑅𝐵 given by
𝑴𝑅𝐵=[𝑚𝑰3×303×303×3𝑰𝑐]
with 𝑰𝑐=𝑑𝑖𝑎𝑔{𝐼𝑥,𝐼𝑦,𝐼𝑧}, and the added-mass and inertia matrix, which we assume to be diagonal containing the added-mass coefficients, so that we have
Skew-symmetric Coriolis matrix also combines rigid-body and hydrodynamics effects, with
and
At low-speed, the hydrodynamic damping matrix is considered without coupling, so that we have the diagonal matrices containing the linear and nonlinear damping coefficients
and
the latter diagonal matrix representing quadratic damping.
Taking into account Assumption 4, the vector of restoring forces (gravitational and buoyancy forces) is expressed as
where and are the gravity and buoyancy forces, respectively ( the water density and ∇ the volume of fluid displaced by the vehicle), and are the coordinates of the center of buoyancy expressed in the b-frame.
An ROV like the BlueROV2 is typically actuated by a number r of fixed thrusters. In order to link the vector to the voltages applied to each thruster i ( ), we use the expression
with denoting thruster voltages in column vector . Matrix is the so-called thrust configuration matrix (see [24]):
thereby, we obtain the thruster mixing matrix, where each column vector links the force created by each thruster to vector :
where is a unit vector representing the orientation of thruster i and is the distance between the point of application of the force and the center of the b-frame.
The diagonal matrix contains unity DC-gain transfer functions accounting for the dynamic relation between and the force , i.e., we have

4. Parameter Identification and Model Validation

This section covers the identification procedure and validation of model parameters listed in Table A1. Table A1 specifies whether the parameter is determined from experiments, from a CAD-model, or obtained from other sources.

4.1. Thruster Model

The BlueROV2 in heavy configuration is built with eight T200 thrusters. The numbering and loci follow the definition of the manufacturer [31]. The thruster orientation, , location, , is given in Table A1. The thrusters are located in a circular pattern and the rotation matrix used is denoted
A nonlinear regression to normalized input voltages and measured force, , is obtained from experiments conducted in prior work [4]. The regression given for is
The thruster dynamics is described by the diagonal transfer function matrix . The diagonal elements are equal and obtained from system identification on experimental data published by MathWorks [32]. The following third order transfer function with unity DC-gain was identified
The maximum velocities and forces of each direction of motion are shown in Table 4.
Table 4. Maximum velocities and forces in b-frame.

4.2. Hydrodynamic Damping

The hydrodynamic damping coefficients given in Equations (10) and (11) are determined in a comparative study of the model output and from a series of experiments conducted in a 1.15 m deep 6.1 m diameter pool. The experiments are designed such that the ROV is actuated individually and in open-loop in all 6-DOF, one at a time, at an interval of several input voltages. Each experiment is conducted twice, where the first instance is used for estimating coefficients and the latter is used for validation. Rather than actuating the thrusters individually, the thrusters are actuated using the standard ArduSUB software allowing for actuating along the 6-DOF directly. The individual thruster input is logged during the experiments and used as input to the model.
The ROV is actuated in each direction of motion from just above the deadzone of the thrusters at 20% input to 100% input, with a step-wise increase of 10%. As an example of one of these tests, Figure 5 compares the experimental data and the model output given 50% input in the surge direction. Position feedback is obtained by using a UAPS Short BaseLine (SBL) location system. The disturbance from tether forces is reduced by manually maneuvering the tether in the direction of the ROV, but it has not been possible to eliminate this disturbance entirely. As a consequence, a proportional feedback controller is used for regulating to a constant depth to ensure that the ROV does not hit the pool bottom or water surface during the surge and sway-direction experiments.
Figure 5. Simulation model and experimental measurements for the surge-direction with positive 50% open-loop input. The error between these is shown as the blue bar at an input of 0.5 in Figure 6.
Figure 6. Model and experimental data comparison for surge, sway, and heave. Each of the bars represents a test similar to the one shown in Figure 5.
As seen in Figure 5, the thrusters are activated after 20 s. The quasi-static part of the motion is used for determining the velocity and consequently the difference between the simulation model and experimental measurements. Figure 6 shows the error for an interval of inputs from just above the deadzone of the thrusters to maximum input, from 20% to 100% input. The largest model discrepancy for both the surge and sway direction of motion is approximately 10%.
Hydrodynamic coefficients related to the heave motion are estimated and validated by performing an experiment where the ROV is submerged at the bottom of the pool and actuating thrusters in the negative heave direction. The heave motion is determined using the pressure sensor. Figure 6 shows that the heave motion model error for the thrust input of 20% is 15% and that the error reduces for larger inputs.
Rotational motion in pitch, roll, and yaw is validated using the integrated Inertial Measurement Unit (IMU) for angular velocity measurement. It is necessary to fully rotate the ROV during the rotational drag tests. This requires an input of more than 30%. Therefore, for the rotational motions, the input given is from 30% to 100% with a step-wise increase of 10%. The model discrepancy for pitch, roll, and yaw is seen in Figure 7. Roll motion error is seen to increase at higher inputs to approximately 10%. The largest discrepancy between the model and experiment for pitch and yaw rotation is 10% and 12%, respectively.
Figure 7. Model and experimental data comparison for roll, pitch, and yaw. Each of the bars represents a test similar to the one shown in Figure 5.
The error bars shown in Figure 6 and Figure 7 show the error between the corrected simulation model and the validation data. There is no clear pattern in the error to further optimize the second order polynomial model. If the hydrodynamic model should be further improved, this requires more precise measurements along with more tests to obtain knowledge about the tendency of the error. This has not been deemed necessary.

4.3. Added Mass

Added mass coefficients presented in Equation (7) are estimated from Eidsvik method [33], which builds upon the experimental work outlined by Det Norske Veritas (DNV) [34]. Eidsvik shows that the relative error of the empirical estimations in translational and rotational degrees of freedom are 10–20% and 30–100%, respectively. The method requires overall dimensions and projected areas of the ROV. The method also requires that the difference in overall dimensions is not larger than 10%. The BlueROV2 in heavy configuration violates this requirement as the width is 20% larger than the length, and the estimated added mass coefficients may be susceptible to further error than predicted by Eidsvik. This will lead to a difference between the model and the physical robot in the acceleration phase. The overall dimensions and projected areas are given in Table 5 and are found using a CAD model of the ROV. L, H, and W, denote the length, height, and width. The notation for the projected areas is given such that the subscript shows the normal direction to the area in the b-frame. The resulting added mass coefficients are found in Table A1.
Table 5. Overall dimensions and projected areas of the BlueROV2 heavy configuration.

5. Ocean Current

The current effect is implemented as an additional velocity term that does not change in the water column. The velocity term in the equations of motions given in Equation (2) is thereby transformed to be in terms of relative velocity shown in Equation (20),
where the relative velocity is given by . As it is assumed that the current is irrotational, the vector for the water particles velocity in b-frame becomes
where,
where is the n-frame water particle velocity in north, east and down direction, respectively. As the current is represented in n-frame, this velocity can be transformed into b-frame by the inverse rotation matrix such that it can be implemented in the model represented in b-frame.
From Equation (8), it is shown that is parameterized independent of linear velocity, and it is assumed that the current is slowly varying, so that the velocity can be assumed to be constant. Therefore, Equation (20) can be reduced to

6. Tether Model

In most underwater applications, the tether is used for communication and power from the top-side, therefore it is a necessity. However, the tether also disturbs the ROV due to the forces generated by the drag and underwater currents [35]. The proposed simulator also includes the dynamics of the tether linking the BlueROV2 underwater vehicle to the top-site base. In order to model the tether, we use a lumped-mass approach, whereby the cable is idealized as a set of lumped masses connected together by n weightless cylinders [36,37].
Let represent the position of node/lumped mass i in the n-frame, and the corresponding velocity vector. In this setting, is directly linked to the above-mentioned base, whose position is possibly time-varying, i.e., , while is attached to the ROV. Hence, regarding the tether dynamics, let us group the remaining s and s into the vectors
and
The dynamics associated with the tether position and velocity vectors and are summarized by the mass-spring-damper-like expression
where is a diagonal matrix of elements
where is the mass matrix of node i and is the added mass matrix of the corresponding cylinder. Similarly, the damping terms of diagonal matrix are given by
where , the internal damping of the tether, is expressed as
where is a damping constant, and is the vector between two consecutive nodes.
The tether being assumed to be neutrally buoyant, the external force acting on element i of the tether represents only hydrodynamic drag. Then, force is the sum of its normal and tangential components
where
and
where is the diameter of the tether, and are the normal and tangential components of the flow velocity of the i-th cylinder, while and are their respective drag coefficients. The normal and tangential velocity components are obtained through the expressions
with representing the water current velocity, expressed in the n-frame and
The term in (26) is given by
where the axial tension of the i-th node is given by
The force acting on the ROV is the end node of the axial tension.

Tether ROV Interaction

In the following, the ROV and tether interaction is demonstrated by letting the tethered ROV be free floating with a current velocity of in the n-frame and initialized at . The tether is 15 m in length and with the tether parameters from Table A1. In Figure 8, a 3D plot of the ROV and tether is shown. This shows that the tether is initially lagging behind the ROV, but straightens out after 30 s. After 100 s, the ROV is approximately at the surface, and after 150 s, the force in x,y,z is constant, which is shown in Figure 9. When comparing the forces from Figure 9 to the maximum thrust force of the ROV seen in Table 4, it is clear that the tether has a large effect on the ROV. The movement in the Down-North and Down-East directions are shown in Figure 10. The range from 100–150 s is left out due to the change in position being minor. From Figure 10, it can be seen that the ROV moves further East compared to North, which is due to the drag force being larger.
Figure 8. Free floating ROV and tether with a current velocity of in the n-frame. Initialized at [0,0,15] in x,y and z, respectively. The blue box represents the ROV at position [9.68,9.94,5.70]. The faded black lines shows the trajectory of the tether and ROV and the green lines show the future path.
Figure 9. Tether force in n-frame on the free floating ROV, current velocity of in the n-frame.
Figure 10. Cross-section of the tether and ROV in the North (b), East (a) and Down direction from time 0 to 100 s.
A video of the free floating ROV and tether with a constant current velocity of in the n-frame can be found in the attached video named “Tether-ROV interaction” or at Github in Supplementary Materials.

7. Control Algorithms for Benchmarking

7.1. Sliding Mode Control

Sliding mode control (SMC) is a popular choice for control of underwater vehicles due to its ability to deal with nonlinear systems subject to uncertainties and bounded disturbances [38]. Moreover, it requires relatively low computer power to compute. The objective, for the sliding-mode controllers implemented on the BlueROV2 (one for each DOF), is to follow a pre-defined reference path given as
where we assume that the time-derivatives of exist and are bounded.
In the following, we design 6 sliding-mode controllers, one for each DOF, where is the i-th component of earth-fixed vector . Then, we rewrite in component-form the system described by Equations (1) and (2) so that we have, for each component ,
where is an unknown but bounded time-varying nonlinear function, with the explicit time dependence representing the coupling between the different DOFs. Control input is the i-th component of vector , which is in turn given by . Defining now the tracking error of each of the 6 DOF as (with being the i-th component of vector in Equation (37)), the tracking error dynamics for each DOF is given by
From there, define first, for each DOF, the sliding variable
where is a strictly positive constant.
Computing the time-derivative of and using expression from Equation (39), we obtain
Choose then the following sliding-mode control law:
where the role of the so-called nominal control law is to cancel the known terms in Equation (41) and is given by
so that Equation (41) is transformed into
Finally, given the bound on unknown dynamics ,
where is a strictly positive constant, the discontinuous control law reads
where is a strictly positive tuning gain, and where is the signum function. Using standard Lyapunov analysis, the sliding-mode controller in Equations (40), (42), (43) and (46) can be proven to make the sliding variable converge to the so-called sliding surface in finite time as long as tuning gain is chosen such that . Note that having the bound is a mild but realistic assumption, as the vehicle is generally assumed to evolve in a constraint set of operations, with limited velocities.
To avoid the well-known chattering phenomenon caused by the use of the signum function in the discontinuous control law, one typically uses continuous approximations such as a sigmoid function, i.e., we have
where is a strictly positive tuning parameter. Note that the right-hand side term of Equation (47) approaches the signum function as parameter goes to 0. Whenever the signum function in Equation (46) is replaced by the sigmoid function of Equation (47), the sliding variable does not reach 0 in finite time, but a so-called boundary layer of thickness around 0, i.e., after a finite time , we have for all .

8. Simulator

The model of the BlueROV2 is found in Section 2, and together with the parameters found in Section 4 and the tether model found in Section 6 is implemented in a MATLAB™ and Simulink™ model. The controllers from Section 7 are also implemented for all six degrees of freedom. The behavior of the BlueROV2 is visualized with a simple 3D graphic environment, which is implemented in the simulator. The simulator will be demonstrated in a case study in Section 9. A simple block diagram of the simulator is shown in Figure 11, it shows how the equations of this paper are implemented in the simulator. A video of the simulator can be found in the attached files “Case study of simulator” or at Github in Supplementary Materials. The simulator will be updated occasionally. An implicit solver is recommended due to stiffness in the system of equations, e.g., ode15s in Simulink™. A detailed guide going through each step of setting up the simulator can be found in Appendix B.
Figure 11. A simple overview of the simulator as it is implemented in Simulink™.

9. Case Study-Offshore Mono Pile Inspection

In the this section, a case study will be carried out to demonstrate the simulator. Subsea inspections are a necessity in a variety of applications, such as in the oil and gas industry and the offshore wind industry. The case study will be based on an inspection of a monopile. The monopile is based on a realistic offshore wind turbine foundation of 6 m in diameter placed at depth of 25 m [39].
Offshore wind turbine operators have to account for a layer of marine growth when designing foundations for the offshore wind turbines, this increases the amount of steel used per installation [19]. An alternative to over-sizing the foundation is to remove the marine growth, so that it does not reach a thickness that is damaging to the structural integrity. The oil and gas operators to avoid an increase in surface area, which would decrease the fatigue life of the structure by cleaning the offshore structures periodically. However, cleaning requires annual inspections of the structure both before and after a cleaning job [40]. Before a cleaning job, inspections are needed to estimate the thickness of the marine growth to determine if it has reached a critical level, after a cleaning job inspections are carried out to verify that the marine growth has been removed and to inspect the structure for cracks to determine the structural integrity [19]. Wind turbine foundations that have been designed to withstand the marine growth layer must also be inspected for cracks, which in some cases also requires cleaning [40].

9.1. Design Criteria

The criteria for a successful inspection is for the ROV to take a picture at steps of one meter along the depth of the monopile with a relative distance of one meter between the camera and the monopile. The camera will be mounted along the surge direction in the ROV’s b-frame. The control parameters for the SMC has been designed according to Section 7.1, and can be seen in Table 6. The control parameters has been tuned initially based on simulations and then re-tuned from experimental data [3]. The noise variances and time delays in the feedback of the simulation will based on a DVL (u,v,w), a laser and camera (x,y), an IMU ( ,p,q), a magnetometer ( ,r) and a pressure sensor (z), see Table 1. The thruster allocation matrix in Section 3 is implemented in the simulation, but has not been considered in the control design.
Table 6. Tuned control parameters for SMC.
The trajectory that the ROV will follow is shown in Figure 12. It is calculated based on Table 7. The initial conditions of the ROV, water current, and tether length can be seen in Table 8. Note that the trajectory is not optimally designed, thus the ROV will not follow the shortest path.
Figure 12. Trajectory of the inspection campaign. The vertical lines are the inspection trajectory and the horizontal lines are the reference change.
Table 7. Parameters for planning the campaign.
Table 8. Tether and ROV parameters.

9.2. Simulation Results

In this section, a brief overview of the simulation results from the case study will be presented. The pose, , of the ROV is seen in Figure 13 and Figure 14. The controller is able follow the trajectory with a low error, even though the ROV is influenced by the tether forces shown in Figure 15, the water current, a delay of 0.1 s in x and y from the DVL and the sensor noises. The ROV is initialized away from the trajectory to show that the controller is able to stabilize the ROV on the trajectory before it starts the mission. The starting point of the trajectory is at [ pi] with respect to the n-frame. The controller stabilizes the ROV at the reference within 20 s. Afterwards the ROV follows the trajectory, where it takes a picture at an interval of one meter in depth, from the bottom of the structure to 5 m below the surface. From Figure 13, it can be noted that the controller has a difficulty following the trajectory when the ROV is moving in the negative x and y directions, this is caused by the ocean current pushing the ROV and tether in the opposite direction. There is a similar helping effect when the ROV moves in the positive x and y direction. In Figure 15, the tether force is shown, and it should be noted that the force fluctuates due to the interaction between the actively controlled ROV and the tether. Similar fluctuations are not seen in Figure 9, where the ROV is only acting as a passive weight. In Table 9, an average of the absolute force and an average of the 5% largest forces are displayed. The impact from the tether is analyzed as statistical forces for each direction and given as a percentage of the maximum thrust force in that direction. For example, the ROV uses 38% of the thrust power to compensate for the 5% largest forces. It should be noted that this percentage is the ideal case since the ROV uses the same thrusters to surge and sway.
Figure 13. Position in x,y and z.
Figure 14. Orientation in and .
Figure 15. Tether force in x,y and z.
Table 9. Average and maximum tether forces during the inspection campaign. The number in parentheses is the percentage of the maximum thrust force.

10. Concluding Remarks

This paper presented a dynamic BlueROV2 Simulator including a model of the tether connecting the ROV to the surface. The simulator is published in a MATLAB™ and Simulink™ environment. The simulator is designed to be used by the control community as a digital platform to implement control algorithms on and benchmark control algorithms. The dynamic model of the BlueROV2 is built on Fossens equations for underwater vehicles, which are widely used to model similar robotic platforms. The parameters have been found and validated using a combination of CAD software and physical experiments. The tether has been modeled using a lumped-mass approach which is an approximation of the standard finite element method. The tether model is included as it has a large impact on the dynamics of the ROV and is a necessity to do missions requiring large data transmissions, such as video feedback. A case study is presented where the ROV is deployed to inspect a monopile structure, and sliding mode control is implemented in the simulator to fulfill the task. The case study demonstrates the usefulness of the BlueROV2 simulator and the results establish a benchmark for future control schemes for positioning and orientation trajectory tracking. The simulator has been designed to be general purpose and all parameters can be changed in the App in MATLAB™ to fit a specific vehicle. It is possible to add additional blocks in the simulator for more advanced missions such as obstacle avoidance, optimal trajectory tracing, etc. Furthermore, additional disturbances can be added by applying the force to Equation (2), this could be water waves for vehicles working close to the surface or a reaction force from a tool.

    本站是提供个人知识管理的网络存储空间,所有内容均由用户发布,不代表本站观点。请注意甄别内容中的联系方式、诱导购买等信息,谨防诈骗。如发现有害或侵权内容,请点击一键举报。
    转藏 分享 献花(0

    0条评论

    发表

    请遵守用户 评论公约

    类似文章 更多