Next Article in Journal
Real-Time Weight Optimization of a Nonlinear Model Predictive Controller Using a Genetic Algorithm for Ship Trajectory Tracking
Next Article in Special Issue
Dynamic Target Tracking of Autonomous Underwater Vehicle Based on Deep Reinforcement Learning
Previous Article in Journal
Technical and Economic Feasibility Analysis of a Conceptual Subsea Freight Glider for CO2 Transportation
Previous Article in Special Issue
Occupancy Grid-Based AUV SLAM Method with Forward-Looking Sonar
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Robust Optimization Design for Path Planning of Bionic Robotic Fish in the Presence of Ocean Currents

1
College of Mechanical and Electronic Engineering, Shandong University of Science and Technology, Qingdao 266590, China
2
College of Intelligent Systems Science and Engineering, Harbin Engineering University, Harbin 150001, China
3
Harbin Engineering University Qingdao Ship Science and Technology Co., Ltd., Qingdao 266400, China
4
College of Mechanical and Electronic Engineering, China University of Petroleum (East China), Qingdao 266580, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2022, 10(8), 1109; https://0-doi-org.brum.beds.ac.uk/10.3390/jmse10081109
Submission received: 22 July 2022 / Revised: 9 August 2022 / Accepted: 9 August 2022 / Published: 12 August 2022

Abstract

:
The bionic robotic fish is one of the special autonomous underwater vehicles (AUV), whose path planning is crucial for many applications including underwater environment detection, archaeology, pipeline leak detection, and so on. However, the uncertain ocean currents increase the difficulty of path planning for bionic robotic fish in practice. In this paper, the path energy consumption is selected as the objective function for path planning, path safety factor, and smoothness are considered as the constraint conditions. The kinematic model is established for bionic robotic fish and, considering the uncertainty of ocean currents, a “min-max” robust optimization problem is proposed in the light of the normal optimization model of path planning for bionic robotic fish. The co-evolutionary genetic algorithm is presented to solve the robust optimization problem with two populations; one population represents the solutions and the other represents the uncertain ocean currents. The objective of the proposed algorithm is to find a robust solution that has the best worst-case performance over a set of possible ocean currents. Multiple experiments indicate that the proposed algorithm is very effective for path planning for bionic robotic fish with ocean currents.

1. Introduction

As one of the special autonomous underwater vehicles (AUV), the bionic robotic fish has a broad application in the development of marine resources due to its good performance of propulsion efficiency, mobility, and concealment [1,2,3]. In the complex underwater environment, path planning is the key for the bionic robotic fish to arrive at the designated location [4,5]. However, there are many obstacles and uncertain ocean currents in the underwater environment, which increase the difficulty to find an optimal path for improving the path planning performance of the bionic robotic fish.
A lot of research has been conducted based on deterministic methods for solving AUV path planning, including particle swarm optimization (PSO) algorithm, ant colony optimization (ACO) algorithm, A* algorithm, genetic algorithm, and so on. For shortening path length, reducing travel time, smoothing trajectory and keeping navigation safety, the PSO algorithm is used to obtain the optimal path based on the obstacles detection by a multi-beam forward looking sonars [6]. A multi-objective genetic algorithm is presented for the evaluation of an optimal path and the work gives the designer the freedom to choose one desirable path from a set of Pareto-optimal solutions [7]. An improved quantum particle swarm optimization (IQPSO) algorithm is proposed to satisfy the three factors of path safety, path length, and angle change of the path point [8]. Combining PSO and Legendre pseudo spectral method (LPM), it presents an efficient path-planner based on the hybrid PSO-LPM algorithm to obtain an optimal path with minimum travelling time [9]. In order to find an energy-efficient path, a distance evolution nonlinear PSO algorithm is presented in the three-dimensional underwater acoustic sensor networks [10]; an efficient gain-based dynamic green ACO metaheuristic is proposed to reduce the total energy consumption during path planning [11]; an AUV traversal path is proposed for communication with the underwater wireless sensor networks [12]. To solve the target traveling problem in densely obstructive environments, the ACO-A* algorithm is proposed to obtain an optimal path, ACO is used to determine a traveling order of targets, A* performs pairwise path planning based on a search graph [13]. In order to find the global optimal solution with the shortest path in light of the elite opposition-based learning strategy and the simplex method, an enhanced water wave optimization is used to solve the optimization problem [14]. However, there inevitably exists uncertain ocean currents and all the above deterministic methods [6,7,8,9,10,11,12,13,14] are difficult to be used in the environment with ocean currents for path planning directly and effectively.
The uncertain ocean currents exist in the complex underwater environment, which increases the difficulty of the path planning for bionic robotic fish. To realize the AUV path planning with time-varying ocean currents, the velocity synthesis algorithm is used to adjust the moving direction of AUV to counteract the current influence [15,16]. Although the velocity synthesis algorithm can make the designer obtain a non-collision path in theory, it is difficult to realize the real time accurate measurement of the value and direction of time-varying ocean currents in complex environment. Based on the forecast of the ocean currents, a genetic algorithm is proposed for AUV path planning to find a safe path for minimizing the energy consumption in an ocean environment characterized by strong currents [17]. A quantum particle swarm optimization (QPSO) algorithm is proposed to solve the AUV path planning problem in ocean currents environment [18]. It assumes that the currents remain static in direction and strength over the course of the mission, however, the strong uncertain ocean current or dynamic flow not only reduces the path planning performance index, but even leads the AUV to collide with the obstacles. Recently, fundamental level-set Partial Differential Equations (PDEs) have been developed for AUV time-optimal [19,20,21] and energy-optimal [22,23] path planning in strong and dynamic ocean currents. It can directly utilize a forecast of the dynamic environment to plan collision-free optimal paths that intelligently utilize favorable flows and avoid adverse currents. In these works, the PDEs are used for path planning based on the forecast of the environmental flows, the accuracy of the forecast of the ocean currents determines the effectiveness of the path planning. In summary, in order to obtain an optimal path, the above studies are focused on the forecast of ocean currents [17,19,20,21,22,23], simplifying the ocean currents environments [18] or detecting the currents [15,16] in real time. However, environments simplifying or forecast based on modelling may not match with the real complex underwater environment with strong currents; the ocean current detecting takes up a lot of computing resources and it is difficult to obtain accurate real-time values. Therefore, it needs a new method for path planning for bionic robotic fish in the complex environment with ocean currents.
Ocean currents are one of the prominent disturbances for bionic robotic fish in the underwater environment, which can help and hinder the mission for bionic robotic fish [24]. In other words, the bionic robotic fish may save the energy and shorten the path length by allowing it to ride the current, or use more energy and increase the path length through the opposing motion of the ocean forcing. Therefore, the uncertain ocean currents cannot to be ignored for bionic robotic fish path planning in practice. In this paper, in order to solve the path planning for bionic robotic fish with ocean currents, based on the established Kinematic model for bionic robotic fish, an optimization problem is proposed with the objective function of the path energy consumption. Considering the uncertainty of ocean currents, based on the upper and lower limits of ocean currents, it forms a “min-max” robust optimization problem for the path planning for bionic robotic fish, which is solved by the proposed co-evolutionary genetic algorithm. The proposed algorithm can obtain a robust path that has the best worst-case performance over a set of possible ocean currents.
The rest of this paper is organized as follows. Section 2 proposes the problem description of the path planning for bionic robotic fish; Section 3 establishes the mathematical models for the path planning; Section 4 presents the robust optimization problem and the corresponding co-evolutionary genetic algorithm; the simulation results are given and analyzed in Section 5; finally, the paper is concluded in Section 6.

2. Problem Description for the Path Planning

Bionic robotic fish works in the underwater environment, there inevitably exist some obstacles and ocean currents in the complex underwater environment. Ocean currents may lead the bionic robotic fish to deviate from its path, take more time or energy consumption to reach its target point and cause a collision. Therefore, the ocean currents increase the difficulty to obtain an optimal collision-free path for bionic robotic fish. In order to solve the path planning problem for bionic robotic fish easily, some assumptions are given as follows: (1) It ignores the roll motion, because the bionic robotic fish doesn’t easily roll in the underwater environment; (2) The irregular obstacle is represented by a spherical shape that wraps around its contour; and (3) It assumes that the values of ocean currents are in a given range, the range can be obtained based on the historical data. Figure 1 gives the roadmap of path planning for bionic robotic fish in this paper. It selects the path energy consumption as the objective function, combined with the decision variables and constraints in practice, based on the established kinematical model, a deterministic optimization problem is formed for path planning for bionic robotic fish. Considering the ocean currents, a “min-max” optimization problem is proposed for path planning, which is solved by the presented co-evolutionary algorithm; finally, it obtains an optimal path.

3. Mathematical Models for the Path Planning

3.1. Kinematic Model for the Bionic Robotic Fish

Figure 2 gives the workspace of the bionic robotic fish, which includes two coordinate systems of earth-fixed frame { O - X Y Z } and body-fixed frame { O 0 - X 0 Y 0 Z 0 } . The kinematic model of the bionic robotic fish can be given as follows [25,26,27]:
  η ˙ = [ J 1 0 3 × 3 0 3 × 3 J 2 ] V
[   x ˙ y ˙ z ˙ ϕ ˙ θ ˙ φ ˙ ] T = [ J 1 0 3 × 3 0 3 × 3 J 2 ] [ u v w p q r ] T
where η = [ x y z ϕ θ ψ ] T is the position and orientation of the bionic robotic fish with respect to the earth-fixed frame, x , y , z are the position for the bionic robotic fish with respect to the North, East, Down respectively, ϕ , θ , ψ are the roll angle, pitch angle, and yaw angle of bionic robotic fish respectively; V = [ u v w p q r ] is the linear and angular velocity vector in the body-fixed frame; p , q , r are roll rate, pitch rate and yaw rate respectively; u , v , w are the surge, sway and heave components of velocities respectively; J 1 and J 2 are the coordinate transformation matrix relating the two frames respectively, which are expressed as follows:
J 1 = [ cos ψ cos θ sin ψ cos ϕ + cos ψ sin θ sin ϕ sin ψ sin ϕ + cos ψ sin θ cos ϕ sin ψ cos θ cos ψ cos ϕ + sin ψ sin θ sin ϕ cos ψ sin ϕ + sin ψ sin θ cos ϕ sin θ cos θ sin ϕ cos θ cos ϕ ]
J 2 = [ 1 sin ϕ tan θ cos ϕ tan θ 0 cos ϕ sin ϕ 0 sin ϕ / cos θ cos ϕ / cos θ ]
In general, the bionic robotic fish do not easily roll in the underwater environment, so it is assumed that ϕ = 0 . In this paper, the Euler angle components of the bionic robotic fish are considered to only be in the XOY plane and the XOZ planes as follows:
ψ m = tan 1 ( | y m + 1 y m | | x m + 1 x m | )
θ m = tan 1 ( | z m + 1 z m | ( x m + 1 x m ) 2 + ( y m + 1 y m ) 2 )
where ( x m ,     y m ,     z m ) and ( x m + 1 ,     y m + 1 ,     z m + 1 ) are the two adjacent points on the path.
The components of ocean current vector ( u c , v c , w c ) in the body-frame is defined as follows:
{ u c = | V c | cos θ c cos ψ c v c = | V c | sin θ c cos ψ c w c = | V c | sin θ c
where | V c | is the magnitude of ocean current velocity V c ; ψ c and θ c denote the directions of current in horizontal and vertical planes, respectively. [ u c v c w c ] T is called the uncertainty of ocean current in this paper.
It assumes that the bionic robotic fish travels with a constant thrust power, in other words, it has a constant water-referenced velocity V , then u , v , w are calculated as follows:
{ u = | V | cos ϕ cos θ + u c v = | V | sin ϕ cos θ + v c w = | V | sin θ + w c

3.2. The Optimization Model for the Path Planning

In the three-dimensional environment, the path energy consumption is crucial for path planning for bionic robotic fish, which determines the endurance time to accomplish the missions for bionic robotic fish [7,8]. Therefore, it selected as the objective function of path planning for bionic robotic fish.
min f E ( A ) s.t. x min x m x max y min y m y max z min z m z max f S ( A ) = 1 f R ( A ) = 1 η ˙ = [ J 1 0 3 × 3 0 3 × 3 J 2 ] V
where x m , y m , z m are the decision variables of the path optimization problem; A = ( x 1 ,     y 1 ,     z 1 ;     ;     x m ,     y m ,     z m ;     ;     x M ,     y M ,     z M ) are the points on the path, f E ( A ) , f S ( A ) , f R ( A ) are the path energy consumption, smoothness and safety factor, respectively; ( x min , y min , z min ) and ( x m a x , y m a x , z m a x ) are the minimum and maximum coordinate position points, respectively.
It gives the mathematical models of path energy consumption, smoothness, safety factor as follows.
(1) The path energy consumption
In this paper, the path for bionic robotic is made up of the orderly connected points p m = ( x m ,     y m ,     z m ) , where m = 1 , 2 , , M , M denotes the total number of the path points, the adjacent points are connected by a straight line, the path is given as follows:
Π s , g =   p 1 p 2 , p 2 p 3 , p M 1 p M
where p 1 and p M are the start and goal path points, respectively.
Based on the distance between two adjacent points in the path of three-dimensional space, the total path length of bionic robotic fish can be given as follows:
f L ( A ) = m = 1 M 1 d (   p m p m + 1 )
d (   p m p m + 1 ) = ( x m x m 1 ) 2 + ( y m y m 1 ) 2 + ( z m z m 1 ) 2
where f L ( A ) is the total path length; d (   p m p m + 1 ) is the distance between the two adjacent points p m and p m + 1 .
The energy consumption of path planning for bionic robotic fish is calculated as follows [10,24]:
f E ( A ) = m = 1 M 1 c d v m 3 t m = m = 1 M 1 c d v m 3 ( d (   p m p m + 1 ) | v g , m | )
  v g , m = v m + V c
where f E ( A ) is the path energy consumption, c d is the bionic robotic fish drag coefficient, v m is the velocity of the bionic robotic fish; t m is the travel time for the path   p m p m + 1 ;   v g , m is the velocity of bionic robotic fish relative to the seabed;   V c is the synthesis of u c , v c , w c in the path   p m p m + 1 . Equation (13) means the total path energy consumption can be obtained by the sum of the energy consumptions of paths combined by the adjacent points.
(2) The path smoothness
In the process of path planning for bionic robotic fish, the path smoothness should be considered to avoid sudden direction change, the main reasons are given as follows [7]: (1) A sharp change in direction may increase energy consumption and (2) Bionic robotic fish may not be able to track the path with sharp direction changes and pass through unsafe areas. Therefore, the planned path should be gentle and smooth as far as possible. The cosine function has the performance of monotonically decreasing in the interval [ 0 , π ] , based on the cosine theorem, it can calculate the cosine of the angle between two vectors easily, whose value can be used to calculate the corner angle in this paper. It assumes that the virtual triangle is constituted from the three adjacent points p m 1 , p m , p m + 1 (as shown in Figure 3), the cosine function is given to calculate the intersection angle for path planning for bionic robotic fish as follows.
cos α = b 2 + c 2 a 2 2 b c
    f S ( A ) = { 1 ,                             α m i n < α r < α m a x 0 ,                               e l s e
where α is the intersection angle with the corner vertex of p m ; β is the intersection angle with the corner vertex of p m - 1 ; γ is the intersection angle with the corner vertex of p m + 1 ; a , b , c are the lengths of triangle sides with the corresponding angle of α , γ , β , respectively; r = 1 , 2 , , R , R is the number of the corner at each turning point; α r is one of the corner angle, which is obtained based on Equation (15). α min and α max are the minimum and maximum intersection angles respectively, which satisfy π 2 < α min < α max < π .
(3) The path safety factor
The obstacle avoidance is the premise of path planning for bionic robotic fish, which can be evaluated by the safety factor as follows [8].
f R ( A ) = { 1 ,                             d (   p m p m + 1 , O b j ) > d 0 + r o b s j 0 ,                               e l s e
d (   p m p m + 1 , O b j ) = p m p m + 1 × p m O b j d ( p m p m + 1 )
where f R ( A ) is the safety factor of the path planning for robotic fish; O b j is the centre of the virtual spherical obstacle, which envelops the actual irregular obstacle; r o b s j is the radius of the j - t h spherical obstacle, j is the serial number of the obstacle; d (   p m p m + 1 , O b j ) is the distance between   p m p m + 1 and O b j ; d 0 is a positive number. When the line between two adjacent path points does not pass through the obstacle, the value of f R ( A ) is 1, which represents the path safety. Otherwise, the path is danger of colliding with obstacles.

4. Robust Optimization Design for Path Planning

In this paper, the bionic robotic fish works in a complex underwater environment, it is a challenge problem of non-collision path planning with low energy consumption in the presence of ocean currents [16]. Robust optimization is the problem to find the best solution in the worst cases, it’s also called “min-max” problem, which is proposed to solve the path planning with the ocean currents. Considering the uncertain of ocean currents, Equation (9) is transformed into a “min-max” optimization problem as follows.
min ( x m , y m , z m )       max ( u c , ν c , w c ) f ( x m , y m , z m , u c , ν c , w c ) s . t .     x min x m x max y min y m y max z min z m z max f S ( A ) = 1 f R ( A ) = 1 η ˙ = [ J 1 0 3 × 3 0 3 × 3 J 2 ] V u minc u c u maxc v minc ν c v maxc w minc w c w maxc
where [ u m i n c ν m i n c w m i n c ]   and   [ u m a x c ν m a x c w m a x c ] are the minimum and maximum values of the components of ocean currents based on the historical data, which can be obtained based on Equation (7). Equation (19) is a “min-max” optimization problem for the path planning for bionic robotic fish, whose goal is to find the robust solution that the obtained path with the best performance in all the worst cases of ocean currents.
The robust optimization problem is more challenging to be solved than general ones due to its computational complexity [28,29], to make the robust optimization of path planning for bionic robotic fish feasible, a co-evolutionary genetic algorithm is developed and used in this section.
Genetic algorithm is widely used in engineering practice due to its good performance of simple principle, ease of implementation and good scalability, based on the performance of genetic algorithm, co-evolutionary genetic algorithm is formed to solve the robust optimization problem for path planning for bionic robotic fish. There are two populations for co-evolutionary genetic algorithm; individual fitness value depends not only on the individual of its own population, but also on the individual of another population [30]. In this paper, the individual of population P X denotes the solution of the optimization problem, the individual of population P U denotes the uncertain cases of ocean currents. Each population is evaluated separately, but they are combined by the evaluation of the fitness functions.
For each solution, the individual fitness function is given as follows:
G ( x m , y m , z m ) =             max ( u c , ν c , w c ) P U f ( x m , y m , z m , u c , ν c , w c )
the objective is to minimize Equation (20), which means that it ignores the larger values and keeps the smaller values of G ( x m , y m , z m ) , the evaluation result retains the minimum value in the worst case, that is, the smaller function value, the greater fitness of the individual.
For each uncertain case, the individual fitness function is given as follows:
H ( u c , ν c , w c ) =       min ( x m , y m , z m ) P X       f ( x m , y m , z m , u c , ν c , w c )
the objective is to maximize Equation (21), which means that it ignores the smaller function value H ( u c , ν c , w c ) and keeps the larger one, the evaluation result retains the worst case, that is, the larger function value, the greater fitness of the individual. Based on Equations (20) and (21), it can solve the robust path planning problem for bionic robotic fish.
Figure 4 gives the robust optimization design flowchart of the path planning for bionic robotic fish, algorithm 1 gives the corresponding steps in detail.
Algorithm 1: Robust optimization design for path planning
1: Modelling the environment for bionic robotic fish, establishing the two coordinate systems of the earth-fixed frame and the body-fixed frame;
2: Selecting the path energy consumption as the objective function of the path planning for bionic robotic fish;
3: Based on the established Kinematic model for bionic robotic fish, establishing path planning model (9) in the light of three basic elements of objective function, decision variables and constrains;
4: Considering the uncertainty of ocean currents, obtaining the robust optimization problem (19) for path planning of bionic robotic fish;
5: Initializing the parameters such as population size, the maximum number of iterations and so on;
6: Creating two populations P U and P X , obtaining multiple collision-free initial paths based on the fitness functions (20) and (21);
7: Evaluating P U after selection, crossover and mutation operations based on (21);
8: If g 1 is smaller than g max _ 1 , setting g 1 = g 1 + 1 , go to step 7; otherwise go to next step;
9: Evaluating P X after selection, crossover and mutation operations based on (20);
10: If g 2 is smaller than g max _ 2 , setting g 2 = g 2 + 1 , go to step 9; otherwise go to next step;
11: If g 3 is smaller than g max _ 3 , setting g 3 = g 3 + 1 , go to step 7; otherwise go to next step;
12: Obtaining the optimal path.

5. Simulation Results and Analysis

In this section, different scenarios are given to illustrate the performance of the proposed robust optimization design for the path planning of bionic robotic fish. Figure 5 shows the designed bionic robotic fish, the total length, width, and height are 0.617 m , 0.239 m , and 0.155 m respectively. It assumes that the population size is 100 and the maximum number of iterations is 200 for the co-evolutionary genetic algorithm.
To test the performance of the proposed algorithm for path planning of bionic robotic fish in the environment with obstacle and ocean currents, it assumes that the ocean current is in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. Figure 6 shows that the bionic robotic fish works in the three-dimensional environment with 10     m × 10     m × 10     m . The center position is ( 7   m ,     7   m ,     7   m ) and radius is 1.2 m for the spherical obstacle. The start and target points are ( 0   m ,   0   m ,   0   m ) and ( 10   m ,   10   m ,   10   m ) respectively, the velocity is 0.2 m / s for the bionic robotic fish. Figure 6 gives the obtained optimal path by the proposed algorithm, the corresponding path length is 17.89 m. It can be seen that the bionic robotic fish can obtain a non-collision path with the performance of short path length in the environment with the worst ocean currents. If the components of ocean currents u c , v c and w c are 0.05 m / s , 0.06 m / s , 0 m / s in practice, respectively. The energy consumption is 1.0619 J for the obtained optimal path by the proposed algorithm. The results show that the proposed algorithm can obtain a safety and smoothness path with low energy consumption in the presence of ocean currents.
In order to further test the performance of the proposed algorithm, it assumes that there are four obstacles in the environment, the ocean currents are in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. The bionic robotic fish works in the three-dimensional environment with 10   m × 10   m × 10   m , the basic parameters of the obstacles are given in Table 1. The start and target points are ( 0   m ,     0     m ,     0   m ) and ( 10   m ,   10     m ,   10     m ) respectively, the velocity of the bionic robotic fish is 0.2 m / s . Figure 7 gives the obtain optimal path by the proposed algorithm, the corresponding path length is 17.98 m . It can be seen that the proposed algorithm can obtain the safe path under the condition of multiple obstacles and ocean currents. Figure 8 also gives the optimal path by the traditional PSO algorithm without considering the ocean currents (the blue curve), the corresponding path length is 17.73 m. If the components of ocean currents u c , v c and w c are 0.071 m / s , 0.036 m / s , 0 m / s in practice respectively. The energy consumption is 1.079 J for following the obtained optimal path by the proposed algorithm, the energy consumption is 1.083 J for following the obtained optimal path by the traditional algorithm. It can be seen that the energy consumption is smaller by the proposed algorithm than the traditional method. The main reasons are given as follows: for the proposed algorithm in this paper, it obtains the best solution in the worst case by the proposed algorithm, if the ocean currents are in the range of the given cases, the path planning design can satisfy the requirements for reducing energy consumption. The results show that the proposed algorithm is robust enough to be used in complex environments and can saving energy when lacking real time data about the environment with ocean currents.
In order to further verify the proposed algorithm in the environment with ocean currents, some comparisons are given for the proposed algorithm and the existing algorithms. It assumes that the bionic robotic fish works in the three-dimensional environment with 50   m × 50   m × 50   m , the start and target points are ( 10   m ,   0   m ,   0   m ) and ( 40   m ,   50   m ,   50   m ) respectively, the velocity of the bionic robotic fish is 0.2 m / s . The ocean currents are in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. Table 2 gives the basic parameters of the obstacles of the path planning for bionic robotic fish. In practice, if the components of ocean currents u c is 0.03 m / s , v c is 0.07 m / s and w c is 0 m / s . Figure 8 shows the comparison results between the proposed and existing IQPSO algorithms [8]. It can be seen that it can obtain a non-collision path by the proposed algorithm, the corresponding path energy consumption is 4.68 J , path length is 80.88 m . By using the existing IQPSO algorithm, the corresponding path energy consumption is 4.85 J , path length is 79.3 m . Compared with the results of the existing IQPSO algorithm, although the length of the planed path is larger by the proposed algorithm, the energy consumption is smaller. This means that the obtained optimal path by the existing algorithm may consume more consumption without considering the effects of ocean currents.
It assumes that the bionic robotic fish works in the three-dimensional environment with 100   m × 100   m × 120   m , the ocean currents are in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. The start and target points are ( 10   m ,   0   m , 0   m ) and ( 100   m ,   90   m ,   100   m ) respectively. Table 3 gives the obstacles parameters for path planning for bionic robotic fish. For the existing QPSO algorithm [18] to design the path planning with fixed value of ocean currents. It sets the ocean current is 0.1 m / s , the angle is 180 between the ocean current direction and the Y-axis; the angle is 90 between the ocean current direction and X-axis; the angle is 90 between the ocean current direction and the Z-axis. In practice, if the components of ocean currents u c is 0.066 m / s , v c is 0.045 m / s and w c is 0 m / s . Figure 9 gives the optimal paths by the proposed and the existing QPSO algorithms [18] for the bionic robotic fish. By using the proposed algorithm, the corresponding energy consumption is 9.822 J . The energy consumption is 9.994 J by using the existing QPSO algorithm. Compared with the optimal results by the existing algorithm, the energy consumption is smaller by the proposed algorithm. It has good optimization performance of energy consumption by the proposed algorithm for the path planning. The main reason is given as follows, the existing algorithm designs the path planning based on the fixed ocean currents, however, it doesn’t consider the influence with the variable ocean currents in practice, which decrease the optimization performance of the obtained optimal path.
In practice, the bionic robotic fish may need to move from the start point to different targets for detection in sequence. It assumes that the bionic robotic fish works in the three-dimensional environment with 100   m × 100   m × 100   m and that the ocean currents are in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. There are multiple targets and obstacles, the bionic robotic fish must get through these target points according to the order Target 1 Target 2 Target 4 . The start point is ( 0   m ,   0   m ,   0   m ) and the target points are ( 50   m ,   50   m ,   50   m ) , ( 80   m ,   0   m ,   100   m ) , ( 100   m ,   100   m ,   0   m ) , ( 0   m ,   60   m ,   80   m ) for target1 to target4 respectively. The parameters for the obstacles are given in Table 4. The velocity for bionic robotic fish is 0.2 m / s . Figure 10 gives the path planning for the bionic robotic fish to arrive at different targets in sequence, the optimal path energy consumption is 22.75 J and path length is 457.09 m by the proposed algorithm. One can see that the proposed algorithm can deal with the path planning problem for bionic robotic fish through the targets in sequence in the environment with ocean currents effectively.
It assumes that the bionic robotic fish works in the three-dimensional environment with 100   m × 100   m × 100   m and that the ocean currents are in the range of [ 0 ,   0.1 ]   m / s , whose direction is stochastic. The start and target points are ( 0   m ,   0   m , 0   m ) and ( 100   m ,   100   m ,   100   m ) . In practice, if the components of ocean currents u c is 0.06 m / s , v c is 0.04 m / s and w c is 0 m / s . Figure 11 shows the comparison results between the proposed and conventional genetic algorithms, it can be seen that it can obtain a non-collision path by the proposed algorithm, the corresponding path energy consumption is 10.81 J , path length is 179.86 m . By using the conventional genetic algorithm, the corresponding path energy consumption is 10.99 J , path length is 179.02 m . Compared with the conventional genetic algorithm, it can be seen that the path length and energy consumption are smaller by the proposed algorithm. The main reason is given as follows, the conventional genetic algorithm designs the path planning without considering the effect of ocean currents, which decreases the optimization performance of the obtained optimal path. Ocean currents affect the energy consumption of the path planning in practice. Table 5 gives the energy consumption with different ocean currents. It assumes that the design conditions are given as follows: the magnitude of ocean current velocity | V c | = [ 0 ,     0.2 ]   m / s , the velocity is v f = 0.3   m / s for the bionic robotic fish. The optimal path length is 188.72 m by the proposed algorithm. In practice, with the increasing of the values of ocean currents, the energy consumption increases. For example, if the components of ocean currents u c is 0.05 m / s , v c is 0.05 m / s and w c is 0 m / s ; the path energy consumption is 20.96 J . If the components of ocean currents u c is 0.1 m / s , v c is 0.1 m / s and w c is 0 m / s ; the path energy consumption is 28.53 J , which is larger.
In order to test the effectiveness of the proposed algorithm in practice, the proposed algorithm is used for our designed bionic robotic fish in the river of our university. Based on the distance measuring equipment, Figure 12 gives the map for the path planning of the bionic robotic fish. Figure 12 shows the real bionic robotic fish moving in the river, Table 6 shows the basic parameters of the obstacles, the start and goal points are ( 1   m ,   1   m ,   0   m ) and ( 7   m ,   17   m ,   0   m ) respectively. It assumes that the design consideration of ocean currents is in the range of [ 0 ,   0.05 ]   m / s , the direction of ocean currents is stochastic. In order to better illustrate the effectiveness of the proposed algorithm, it sets that the designed bionic robotic fish works in a plane without up and down motion. In Figure 12, based on the optimal path planning with the worst ocean currents, it obtains a non-collision path in practice, the corresponding path length is 17.27 m , the energy consumption is 0.83 J . In practice, the energy is 0.69 without the ocean currents. Without the real time value of ocean currents, the bionic robotic fish can obtain a non-collision path with low energy consumption.

6. Conclusions

Path planning is the premise for bionic robotic fish to accomplish missions in the three-dimensional environment. In the complex underwater environment, the uncertain ocean currents are inevitable in practice, whose influence cannot be ignored on path planning for bionic robotic fish. In this paper, in order to solve the path planning problem for bionic robotic fish with ocean currents, it selects energy consumption as the object function; smoothness and safety factor are selected as constraint conditions. A general path planning problem is formed in the light of the three basic elements of decision variables, objective functions, and constraint conditions. Considering the uncertainty of ocean currents, it presents a robust optimization problem, which is solved by the proposed co-evolutionary genetic algorithm, an optimal path can be obtained by finding the best solution in the worst cases. Different scenarios illustrate that it can obtain the optimal path with strong robustness by the proposed robust optimization design algorithm for the path planning for bionic robotic fish in the environment with ocean currents. Compared with the results by existing methods, it obtains optimal paths with better optimization performance by the proposed algorithm. In this paper, the proposed algorithm cannot deal with the path planning with moving obstacles effectively. Therefore, we will propose a dynamic programming algorithm to solve this problem in the future work. We will also plan to use the back propagation neural network to establish the energy consumption model. Because the input and output data are obtained from the engineering practice, the established model is more realistic.

Author Contributions

Conceptualization, Q.T. and T.W.; methodology, Q.T.; software, T.W.; validation, Q.T., Y.W., C.L. and B.L.; formal analysis, Q.T.; investigation, Q.T. and T.W.; resources, Y.W.; data curation, C.L.; writing—original draft preparation, Q.T.; writing—review and editing, Y.W.; visualization, C.L.; supervision, B.L.; project administration, B.L.; funding acquisition, Y.W. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the China Postdoctoral Science Foundation (2022M710934), Postdoctoral Applied Research Project of Qingdao City, Project of Shandong Province Higher Educational Young Innovative Talent Introduction and Cultivation Team (Intelligent Transportation Team of Offshore Products).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Wang, M.; Dong, H.; Li, X.; Zhang, Y.; Yu, J. Control and Optimization of a Bionic Robotic Fish Through a Combination of CPG model and PSO. Neurocomputing 2019, 337, 144–152. [Google Scholar] [CrossRef]
  2. Li, K.; Jiang, H.; Wang, S.; Yu, J. A Soft Robotic Fish with Variable-stiffness Decoupled Mechanisms. J. Bionic Eng. 2018, 15, 599–609. [Google Scholar] [CrossRef]
  3. Tian, Q.; Wang, T.; Liu, B.; Ran, G. Thruster Fault Diagnostics and Fault Tolerant Control for Autonomous Underwater Vehicle with Ocean Currents. Machines 2022, 10, 582. [Google Scholar] [CrossRef]
  4. Chen, J.; Zhu, H.; Zhang, L.; Sun, Y. Research on fuzzy control of path tracking for underwater vehicle based on genetic algo-rithm optimization. Ocean Eng. 2018, 156, 217–223. [Google Scholar] [CrossRef]
  5. Patle, B.K.; Pandey, A.; Jagadeesh, A.; Parhi, D.R. Path planning in uncertain environment by using firefly algorithm. Def. Technol. 2018, 14, 691–701. [Google Scholar] [CrossRef]
  6. Yan, Z.; Li, J.; Wu, Y.; Zhang, G. A Real-Time Path Planning Algorithm for AUV in Unknown Underwater Environment Based on Combining PSO and Waypoint Guidance. Sensors 2018, 19, 20. [Google Scholar] [CrossRef]
  7. Ataei, M.; Yousefi-Koma, A. Three-dimensional optimal path planning for waypoint guidance of an autonomous underwater vehicle. Robot. Auton. Syst. 2015, 67, 23–32. [Google Scholar] [CrossRef]
  8. Wang, L.; Liu, L.; Qi, J.; Peng, W. Improved Quantum Particle Swarm Optimization Algorithm for Offline Path Planning in AUVs. IEEE Access 2020, 8, 143397–143411. [Google Scholar] [CrossRef]
  9. Zhuang, Y.; Sharma, S.; Subudhi, B.; Huang, H.; Wan, J. Efficient collision-free path planning for autonomous underwater ve-hicles in dynamic environments with a hybrid optimization algorithm. Ocean Eng. 2016, 127, 190–199. [Google Scholar]
  10. Wu, J.; Song, C.; Fan, C.; Hawbani, A.; Zhao, L.; Sun, X. DENPSO: A Distance Evolution Nonlinear PSO Algorithm for Ener-gy-Efficient Path Planning in 3D UASNs. IEEE Access 2019, 7, 105514–105530. [Google Scholar] [CrossRef]
  11. Sangeetha, V.; Krishankumar, R.; Ravichandran, K.S.; Kar, S. Energy-efficient green ant colony optimization for path planning in dynamic 3D environments. Soft Comput. 2021, 25, 4749–4769. [Google Scholar] [CrossRef]
  12. Khan, M.T.R.; Ahmed, S.H.; Jembre, Y.Z.; Kim, D. An energy-efficient data collection protocol with AUV path planning in the Internet of Underwater Things. J. Netw. Comput. Appl. 2019, 135, 20–31. [Google Scholar] [CrossRef]
  13. Yu, X.; Chen, W.-N.; Gu, T.; Yuan, H.; Zhang, H.; Zhang, J. ACO-A*: Ant Colony Optimization Plus A* for 3-D Traveling in Environments With Dense Obstacles. IEEE Trans. Evol. Comput. 2019, 23, 617–631. [Google Scholar] [CrossRef]
  14. Yan, Z.; Zhang, J.; Tang, J. Path planning for autonomous underwater vehicle based on an enhanced water wave optimization algorithm. Math. Comput. Simul. 2021, 181, 192–241. [Google Scholar] [CrossRef]
  15. Cao, X.; Zhu, D.; Yang, S.X. Multi-AUV target searching under ocean current based on PPSO and velocity synthesis algorithm. Underw. Technol. 2015, 33, 31–39. [Google Scholar] [CrossRef]
  16. Cao, X.; Sun, C.-Y.; Chen, M.-Z. Path planning for autonomous underwater vehicle in time-varying current. IET Intell. Transp. Syst. 2019, 13, 1265–1271. [Google Scholar] [CrossRef]
  17. Alvarez, A.; Caiti, A.; Onken, R. Evolutionary Path Planning for Autonomous Underwater Vehicles in a Variable Ocean. IEEE J. Ocean. Eng. 2004, 29, 418–429. [Google Scholar] [CrossRef]
  18. Zeng, Z.; Sammut, K.; Lian, L.; He, F.; Lammas, A.; Tang, Y. A comparison of optimization techniques for AUV path planning in environments with ocean currents. Robot. Auton. Syst. 2016, 82, 61–72. [Google Scholar] [CrossRef]
  19. Subramani, D.N.L.; Pierre, F.J. Risk-optimal path planning in stochastic dynamic environments. Comput. Methods Appl. Mech. Eng. 2019, 353, 391–415. [Google Scholar] [CrossRef]
  20. Lolla, T.; Haley, P.J., Jr.; Lermusiaux, P.F.J. Path planning in multi-scale ocean flows: Coordination and dynamic obstacles. Ocean Model. 2015, 94, 46–66. [Google Scholar] [CrossRef]
  21. Subramani, D.N.; Wei, Q.J.; Lermusiaux, P.F.J. Stochastic time-optimal path-planning in uncertain, strong, and dynamic flows. Comput. Methods Appl. Mech. Eng. 2018, 333, 218–237. [Google Scholar] [CrossRef]
  22. Subramani, D.N.; Haley, P.J.; Lermusiaux, P.F.J. Energy-optimal path planning in the coastal ocean. J. Geophys. Res. Oceans 2017, 122, 3981–4003. [Google Scholar] [CrossRef]
  23. Subramani, D.N.; Lermusiaux, P.F.J. Energy-optimal path planning by stochastic dynamically orthogonal level-set optimization. Ocean Model. 2016, 100, 57–77. [Google Scholar]
  24. Jones, D.; Hollinger, G.A. Planning Energy-Efficient Trajectories in Strong Disturbances. IEEE Robot. Autom. Lett. 2017, 2, 2080–2087. [Google Scholar] [CrossRef]
  25. Cao, X.; Sun, H.; Jan, G.E. Multi-AUV cooperative target search and tracking in unknown underwater environment. Ocean Eng. 2018, 150, 1–11. [Google Scholar] [CrossRef]
  26. Taheri, E.; Ferdowsi, M.H.; Danesh, M. Closed-loop randomized kinodynamic path planning for an autonomous underwater vehicle. Appl. Ocean Res. 2019, 83, 48–64. [Google Scholar] [CrossRef]
  27. Mahmoudzadeh, S.; Yazdani, A.M.; Sammut, K.; Powers, D.M.W. Online path planning for AUV rendezvous in dynamic cluttered undersea environment using evolutionary algorithms. Appl. Soft Comput. 2018, 70, 929–945. [Google Scholar] [CrossRef]
  28. Cramer, A.M.; Sudhoff, S.D.; Zivi, E.L. Evolutionary Algorithms for Minimax Problems in Robust Design. IEEE Trans. Evol. Comput. 2009, 13, 444–453. [Google Scholar] [CrossRef]
  29. Tian, Q.; Zhao, D.; Li, Z.; Zhu, Q. A two-step co-evolutionary particle swarm optimization approach for CO2 pipeline design with multiple uncertainties. Carbon Manag. 2018, 9, 333–346. [Google Scholar] [CrossRef]
  30. Vejdannik, M.; Sadr, A. Channel power optimization in WDM systems using co-evolutionary genetic algorithm. Opt. Switch. Netw. 2022, 43, 100637. [Google Scholar] [CrossRef]
Figure 1. The roadmap of path planning for bionic robotic fish.
Figure 1. The roadmap of path planning for bionic robotic fish.
Jmse 10 01109 g001
Figure 2. Coordinate systems for the bionic robotic fish.
Figure 2. Coordinate systems for the bionic robotic fish.
Jmse 10 01109 g002
Figure 3. Corner angle of the path for bionic robotic fish.
Figure 3. Corner angle of the path for bionic robotic fish.
Jmse 10 01109 g003
Figure 4. Robust optimization design for path planning of the bionic robotic fish.
Figure 4. Robust optimization design for path planning of the bionic robotic fish.
Jmse 10 01109 g004
Figure 5. The designed bionic robotic fish.
Figure 5. The designed bionic robotic fish.
Jmse 10 01109 g005
Figure 6. The optimal path in the environment with obstacle and ocean currents.
Figure 6. The optimal path in the environment with obstacle and ocean currents.
Jmse 10 01109 g006
Figure 7. The optimal path in the environment with multiple obstacles.
Figure 7. The optimal path in the environment with multiple obstacles.
Jmse 10 01109 g007
Figure 8. Comparison results between the proposed and existing IQPSO algorithms.
Figure 8. Comparison results between the proposed and existing IQPSO algorithms.
Jmse 10 01109 g008
Figure 9. The comparison results between the proposed and existing QPSO algorithms.
Figure 9. The comparison results between the proposed and existing QPSO algorithms.
Jmse 10 01109 g009
Figure 10. Path planning for the bionic robotic fish to arrive at different targets.
Figure 10. Path planning for the bionic robotic fish to arrive at different targets.
Jmse 10 01109 g010
Figure 11. The comparison results between the proposed and conventional genetic algorithms.
Figure 11. The comparison results between the proposed and conventional genetic algorithms.
Jmse 10 01109 g011
Figure 12. The path planning of the bionic robotic fish in the river.
Figure 12. The path planning of the bionic robotic fish in the river.
Jmse 10 01109 g012
Table 1. Basic parameters of the obstacles in Figure 7.
Table 1. Basic parameters of the obstacles in Figure 7.
Serial NumberCoordinate Position of the
Obstacle Center ( m )
Radius ( m )
Obstacle1(4 m, 6 m, 1 m)1.2 m
Obstacle2(3 m, 2 m, 3 m)1 m
Obstacle3(7 m, 7 m, 7 m)1.2 m
Obstacle4(8 m, 3 m, 6 m)1 m
Table 2. The basic parameters of the obstacles in Figure 8.
Table 2. The basic parameters of the obstacles in Figure 8.
Serial NumberObstacle Center ( m ) Obstacle Radius ( m )
Obstacle1(15 m, 10 m, 15 m)5 m
Obstacle2(20 m, 30 m, 5 m)6 m
Obstacle3(40 m, 15 m, 30 m)5 m
Obstacle4(40 m, 7.5 m, 35 m)4.5 m
Obstacle5(35 m, 35 m, 35 m)6 m
Obstacle6(10 m, 40 m, 20 m)6.5 m
Table 3. The basic parameters of the obstacles in Figure 9.
Table 3. The basic parameters of the obstacles in Figure 9.
Serial NumberObstacle Center ( m ) Obstacle Radius ( m )
Obstacle1(30 m, 20 m, 30 m)10 m
Obstacle2(40 m, 60 m, 20 m)12 m
Obstacle3(80 m, 30 m, 60 m)10 m
Obstacle4(80 m, 15 m, 70 m)9 m
Obstacle5(70 m, 70 m, 70 m)12 m
Obstacle6(20 m, 80 m, 70 m)13 m
Obstacle7(60 m, 20 m, 50 m)10 m
Obstacle8(15 m, 85 m, 20 m)13 m
Table 4. The basic parameters of the obstacles in Figure 10.
Table 4. The basic parameters of the obstacles in Figure 10.
Serial NumberObstacle Center ( m ) Obstacle Radius ( m )
Obstacle1(30 m, 30 m, 30 m)11 m
Obstacle2(65 m, 25 m, 75 m)8 m
Obstacle3(90 m, 50 m, 50 m)8 m
Obstacle4(50 m, 80 m, 40 m)12 m
Table 5. Energy consumptions with different ocean currents.
Table 5. Energy consumptions with different ocean currents.
Considerations | V c | = [ 0 , 0.2 ] m / s , v f = 0.3 m / s
Actual Situations
Ocean current ( m / s )[0.05, 0.05, 0][0.1, 0.1, 0][0.12, 0.13, 0.09][0.08, 0.16, 0.08][0.18, 0.05, 0.09]
Energy consumption ( J )20.9628.5333.8134.2236.76
Table 6. The basic parameters of the obstacles in Figure 12.
Table 6. The basic parameters of the obstacles in Figure 12.
Serial NumberObstacle Center ( m ) Radius ( m )
Obstacle1(2 m, 3.3 m, 0 m)0.45 m
Obstacle2(2.5 m, 5.4 m, 0 m)0.45 m
Obstacle3(4 m, 2.9 m, 0 m)0.5 m
Obstacle4(5 m, 5.5 m, 0 m)0.5 m
Obstacle5(5.5 m, 4 m, 0 m)0.4 m
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Tian, Q.; Wang, T.; Wang, Y.; Li, C.; Liu, B. Robust Optimization Design for Path Planning of Bionic Robotic Fish in the Presence of Ocean Currents. J. Mar. Sci. Eng. 2022, 10, 1109. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse10081109

AMA Style

Tian Q, Wang T, Wang Y, Li C, Liu B. Robust Optimization Design for Path Planning of Bionic Robotic Fish in the Presence of Ocean Currents. Journal of Marine Science and Engineering. 2022; 10(8):1109. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse10081109

Chicago/Turabian Style

Tian, Qunhong, Tao Wang, Yunxia Wang, Changjiang Li, and Bing Liu. 2022. "Robust Optimization Design for Path Planning of Bionic Robotic Fish in the Presence of Ocean Currents" Journal of Marine Science and Engineering 10, no. 8: 1109. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse10081109

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop