Next Article in Journal
Preclinical Evaluation of an Innovative Bone Graft of Marine Origin for the Treatment of Critical-Sized Bone Defects in an Animal Model
Next Article in Special Issue
Incorporation of Potential Fields and Motion Primitives for the Collision Avoidance of Unmanned Aircraft
Previous Article in Journal
Sequential Extraction Analysis of Arsenic in Soil Samples Collected in an Agricultural Area of Brindisi, Apulia (Italy), in the Proximity of a Coal-Burning Power Plant
Previous Article in Special Issue
Autonomous Underwater Vehicle Localization Using Sound Measurements of Passing Ships
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Improved Artificial Potential Field and Dynamic Window Method for Amphibious Robot Fish Path Planning

1
Guangzhou Institute of Advanced Technology, Chinese Academy of Sciences, Guangzhou 511458, China
2
College of Mechanical and Electronic Engineering, Shaanxi University of Science and Technology, Xi’an 710021, China
*
Authors to whom correspondence should be addressed.
Appl. Sci. 2021, 11(5), 2114; https://doi.org/10.3390/app11052114
Submission received: 16 January 2021 / Revised: 10 February 2021 / Accepted: 16 February 2021 / Published: 27 February 2021
(This article belongs to the Special Issue Advances in Robot Path Planning)

Abstract

:
Aiming at the problems of “local minimum” and “unreachable target” existing in the traditional artificial potential field method in path planning, an improved artificial potential field method was proposed after analyzing the fundamental causes of the above problems. The method solved the problem of local minimum by modifying the direction and influence range of the gravitational field, increasing the virtual target and evaluation function, and the problem of unreachable targets is solved by increasing gravity. In view of the change of motion state of robot fish in amphibious environments, the improved artificial potential field method was fused with a dynamic window algorithm, and a dynamic window evaluation function of the optimal path was designed on the basis of establishing the dynamic equations of land and underwater. Then, the simulation experiment was designed under the environment of Matlab2019a. Firstly, the improved and traditional artificial potential field methods were compared. The results showed that the improved artificial potential field method could solve the above two problems well, shorten the operation time and path length, and have high efficiency. Secondly, the influence of different motion modes on path planning is verified, and the result also reflects that the amphibious robot can avoid obstacles flexibly and reach the target point accurately according to its own motion ability. This paper provides a new way of path planning for the amphibious robot.

1. Introduction

Over the last few decades, mobile robots have been widely used in many circumstances, which improves the working efficiency and reduces the cost of work to a great extent, and these advantages show their great developmental potential [1,2,3]. Amphibious robotic fish in mobile robots are the object of this study. This is not only an underwater robot with the efficient propulsion function of fish, but also an overland robot adapted to complex terrestrial environments.
The tasks of a mobile robot can be divided into transport tasks and reconnaissance tasks in general. No matter which kinds of works are completed, mobile robots all require the capability of fulfilling their mission autonomously under the fast modern development pace [4], and path planning as one of the crucial techniques ensures that the mobile robot can achieve independence in its work without manual intervention [5].
Path planning requires considering the maneuverability of robots and environmental constraints to find a trajectory from the initial point to the target point, and avoid all obstacles [6]. In essence, it is a method to optimize a system with complex constraints. In order to achieve this goal, many scholars have done a lot of research and put forward many feasible algorithms. These algorithms can be divided into global path planning algorithms [7,8] and local path planning algorithms [9]. The grid algorithm [10], A* algorithm and D* algorithm [11,12,13] belong to the former, and the ant colony algorithm [14,15], artificial potential field method [16] and neural network method [17] belong to the latter. Each algorithm has its corresponding advantages and disadvantages in different scenarios, so it is necessary to apply the most appropriate algorithm in light of the actual conditions.
The purpose of this paper is to accomplish the reconnaissance task of amphibious robot fish. From the environmental point of view, it belongs to the completely unknown environment, and the obstacle avoidance problem in this kind of environment belongs to the local path planning problem, which has wider application range and more practical significance than global path planning. The reasons for choosing the artificial potential field method as the local path planning algorithm are listed as follows: (1) it made many achievements as a mature algorithm; (2) the algorithm is relatively simple and the planned path is comparatively smooth, so robots can identify the whole path much more easily; (3) it has a fast calculation speed, high efficiency, and is more suitable for practical application. However, this method has some problems, such as local minimum and unreachable target point [18]. Scholars have also proposed many solutions to solve these problems, such as the improved algorithm combined with an ant colony algorithm or simulated annealing [19], adding virtual obstacles [20] and modifying the force field potential function [21], etc.
In this paper, an improved method is proposed to solve the above two problems, and a more appropriate hybrid algorithm for amphibious robots is generated by combining the dynamic window method. The effectiveness of the proposed algorithm is validated through experiments. The rest of the paper is organized as follows. Section 2 introduces the kinetic analysis of the amphibious robot. We listed different dynamic equations and set parameters according to different environments of robotic fish, so as to improve the ability of various movements of robotic fish, so the content of the second chapter is to further examine to the real motion and provide a theoretical basis. Section 3 briefly reviews the existing artificial potential field method and the problem it faces. Section 4 provides a detailed description of the improved algorithm. In short, on a macro level, the purpose of treating the amphibian robot as a virtual mass point is to better show how the improved artificial potential field method can plan the general direction of motion and avoid problems. At the micro level, adding the environmental constraints and robot kinematics parameters (velocity, angular velocity, etc.) is necessary to better fit the actual situation. Section 5 presents and discusses the experimental results for the proposed method. Section 6 discusses the use of the two algorithms. Section 7 concludes the paper.

2. Kinetic Analysis

It is worth noticing that the subject of this paper is the amphibious robot. The fin surface is driven by the fin rays, as they move up and down in turn in both environments. Its motion mode has its own characteristics in different environments. The propulsion force is generated by waving the fin surface underwater, and on the land, it is generated by the friction between the fin surface and the ground. The amplitude and frequency of the oscillation need to be further adjusted according to the different environments. The structure of the amphibious robot is generally divided into two parts: fish body and fin surface. The fish body includes the control system, the transmission system and various sensors on it, and the fin surface is regarded as the motion system.

2.1. Kinetic Analysis on the Land

The Newton–Euler equation is chosen to describe the dynamic equation, which can express two motion modes of rotation and translation, respectively, and it obtains the initial parameters that are taken as the input for algorithm. As mentioned above, the motion of the amphibious robot is powered by the fin surface waving, and the undulation is controlled by the swing of the fin with certain phase differences. Therefore, the specific Newton equation of kinetic analysis for the fin can be expressed as Equation (1).
m i v ˙ i = T i + F i a = F i
where i is the fin number, v ˙ i is the acceleration of the center of mass of the i th fin, T i is the constraining force, F i a is the active force, and F i is the external main force of the i th fin.
The expression of the Euler equation is denoted as follows:
I C · ω ˙ i + ω i × I C · ω i = L i a + L i t = M i
where I C represents the inertia, ω i represents the angular velocity of the i th fin, ω ˙ i represents the angular acceleration of the i th fin, L i a and L i t represent the main moment and the counter main moment, respectively, and M i is the external main moment of the i th fin.
When the amphibious robot is analyzed as a whole, the diagram of stress analysis can be formulated, as shown in Figure 1. The friction is produced by the contact between the fin surface and the ground, which creates the driving force to propel the amphibious robot forward. Thus, the analysis mainly focuses on the contact point, where G is gravity, F is the supporting force, and f . is the friction force. The summary formula can be expressed as Equations (3) and (4).
F = 1 λ [ ( G + m z g ¨ ) ( x g x ) m x g ¨ z g ]
f = μ s g n ( v i ) F
where λ is the wavelength of the fin surface, x g ¨ and z g ¨ are the inertia force in the x axis and the z axis, respectively, while x g and z g are the coordinates of the center of mass in the x axis and z axis, respectively, x is the abscissa of the contact point, and μ is the coulomb friction coefficient.
From Equations (1)–(4), the velocity and acceleration of each fin and the amphibious robot can be acquired. This provides the initial parameters and dynamical equation of the amphibious robot on land for the algorithm.

2.2. Kinetic Analysis Underwater

Different from the motion mode on the land, the underwater motion mainly depends on the water propulsion on both sides of the fin surface. Besides the rotation motion, a roll motion should be taken into account as well. A 5–DOF motion model of the designed amphibious robot is shown in Figure 2, which is expressed in a Cartesian coordinate system without rotational motion around the z axis.
In Figure 2, α, β and γ are the rotation angles corresponding to the x, y and z axes, respectively. The expression of the kinetic equation is given as follows:
C t = C t 0 + t 0 t v t 0 d t
θ t x = θ t 0 x + t 0 t ω t 0 x d t
θ t y = θ t 0 y + t 0 t ω t 0 y d t
V t = V t 0 + t 0 t F m d t + t 0 t M I C d t
ω t = ω t 0 + t 0 t M I C × r d t
where C t is the centroid vector of the amphibious robot at time t, θ t x is the rotation angle around the x axis at time t, V t is the velocity, ω t is the angular velocity at time t, M is the external moment, I C is the inertia, and r is the distance from any point to the rotation centerline.
The basic motion parameters can be determined in combination with the designed amphibious robot through the above analysis, and the specific parameters are shown in Table 1.
Through the kinetic analysis of the motion modes in different environments, a more vivid, clear and accurate motion description is obtained, which can theoretically explain the basic principle of the motion propulsion mode of the amphibious robot. Meanwhile, these parameters also provide the motion information of the amphibious robot for the algorithm, so that the simulation process can be closer to the practical case and also deliver more convincing results.

3. Artificial Potential Field Method

3.1. Traditional Artificial Potential Field Method

The traditional artificial potential field method assumes that there is a virtual repulsion field around the obstacles, and there is also a virtual attraction field around the target point. The robot is affected by the attraction field to approach the target point, then avoids the obstacles under the repulsion field, and finally reaches the target point without any collisions.
The functions of the attraction field U a t t ( q ) , repulsive field U r e p ( q ) and resultant field U ( q ) are denoted as follows:
U ( q ) = U a t t ( q ) + U r e p ( q )
U a t t ( q ) = 1 2 k a t t ( q q g ) 2
U r e p ( q ) = { 0 , ρ ( q )     ρ 0 1 2 k r e p ( 1 ρ ( q ) 1 ρ 0 ) 2 ,   ρ ( q ) < ρ 0
ρ ( q ) = | | q q 0 | |
where k a t t and k r e p are the attraction coefficient and repulsive coefficient, respectively, q is the current position of the robot, q o is the position of the obstacle, q g is the position of the target point, and ρ 0 is the influence distance of the obstacle. When the distance between the obstacle and the robot is greater than ρ 0 , the robot cannot be affected.
By deriving the distance from the above Equations (10)–(12), we can get the attractive force F a t t ( q ) , repulsion force F r e p ( q ) and resultant force F ( q ) . Their functions are represented as follows:
F ( q ) = F a t t ( q ) + F r e p ( q )
F a t t ( q ) = U a t t ( q ) = k a t t ( q q g )
F r e p ( q ) = { 0 ,   ρ ( q )     ρ 0 k r e p ( 1 ρ 0 1 ρ ( q ) ) ( q q o ρ 3 ( q ) ) , ρ ( q ) < ρ 0

3.2. Facing Problems

The traditional artificial potential field method mainly faces two problems; one is the local minimum problem, the other is the goal unreachable problem.
The first problem is shown in Figure 3. In these two cases, the resultant force of the robot at this position is 0. As the robot’s movement is in the direction of the resultant force, the robot may stop moving so that it cannot arrive at the target point.
The second problem is shown in Figure 4. The goal is near the obstacle. While the robot is approaching the goal, the repulsion force is greater than the attractive force because the attractive force is directly proportional to the distance between the robot and the goal, which makes the robot unable to reach the target point and move away from the goal.

4. Improved Artificial Potential Field Method

4.1. Improved Attraction Field

A large number of scholars have improved and optimized the traditional artificial potential field method from various aspects. Most of them paid attention to modifying the potential field function, and there are some reasons for this, as follows: (1) the expression of the potential field function is easy to modify; (2) the potential field is more in line with actual physics, so it is easy to understand; (3) the modification of the potential field can improve the efficiency of the algorithm in essence. Considering the following reasons, this paper focuses on the improvement of the attraction potential field.
First of all, the core of the local minimum problem is that the values of the attraction force and repulsion force are the same, and the directions are opposite, which can be improved by modifying one of them. As shown in Figure 3a, it can be found that modifying the value of the force field cannot solve this problem. No matter how the values of attraction force and repulsion force are modified, it can only aggravate the instability of the robot’s motion, inducing vibration. This paper chooses to modify the direction of the attraction potential field to solve this problem. The general idea is as below: taking the goal as the center, a quadrilateral is generated within a certain distance. When the value of the resultant force is 0, the four corners of the created quadrilateral will be regarded as interim goals for navigation, and choosing which one is the goal relies on the evaluation function. After the robot reaches a position at a certain distance d 0 from the goal, the four virtual goals will be invalidated, so that the robot can reach the real goal. In addition, if the target point cannot be reached, it means the goal is too close to the obstacles, so we could increase the attraction force to make it reach the goal. According to the traditional attraction potential function, the attraction force is inversely proportion to the distance between the robot and the goal. Therefore, we can assume the attraction force as a constant within a certain range d 0 from the goal. In order to avoid the situation where the value of the resultant force is still 0 when the robot is near the goal, we can increase d 0 to solve this problem. The improved attraction potential field (Equation (17)) and schematic diagram (Figure 5) are as follows:
U a t t ( q ) = { 1 2 k a t t ( q q g ) 2 ,   U 0   ρ ( q )     d 0 1 2 k a t t ( q q g i ) 2 ,   U = 0   ρ ( q )     d 0 1 2 k a t t d 0 2 ,   U     0   ρ ( q ) < d 0
Equation (18) mainly compares the angle value θ between attraction force and repulsion force. When the value of the resultant force is 0, the angle value is equal to 180°. As such, the greater the difference is between the real angle value and 180°, the higher the evaluation function value’s virtual goal can be; the robot is much more likely to move in the direction of the virtual goal a with higher evaluation function value.
C ( q ) = | a r c c o s | ( q q 0 ) ( q q g ) | | q     q 0 g | | q q g | 180 |

4.2. Combing with Dynamic Window Method

The essence of the dynamic window method [22] is to sample the velocity space ( v , ω ) of the robot according to its dynamic characteristics, and generate new velocity v and angular velocity ω under the influence of various factors over time. The series of velocity spaces ( v , ω ) are simulated and analyzed to obtain a variety of paths; then, the optimal velocity space ( v , ω ) is obtained through the evaluation function. Finally, the whole optimal path will be obtained by repeating the process above.
The motion equation of the amphibious robot can be summarized as follows:
{ x t = x t Δ t + v Δ t c o s α y t = v y t Δ t + Δ t c o s β z t = z t Δ t + v Δ t c o s γ θ t = θ t Δ t + ω Δ t
where x t represents the displacement of the amphibious robot in the x axis at time t , y t and z t similarly represent the displacement in the y axis and z axis, θ t represents the motion angle of the robot at time t , Δ t represents the time step, v and ω represent the velocity and acceleration, respectively, and the specific values can be obtained from the above kinetic function. α, β and γ represent the angle between velocity v and the x axis, y axis, z axis, respectively.
This algorithm needs to be constrained by the robot’s motion ability and environment, which consists of three points: (1) the velocity constraint V m , which is the velocity and angular velocity within the range of the robot’s own motion ability; (2) the acceleration constraint V a , which measures the influence of the acceleration range of the robot on the speed; (3) the obstacle constraint V d , which is to ensure that the robot will not collide with the obstacle under the range of braking ability. The expressions are as follows:
V m = { ( v , ω ) | v [ v m i n , v m a x ] ,   ω [ ω m i n , ω m a x ] }
V a = { ( v , ω ) | v [ v t v b ˙ Δ t , v t + v a ˙ Δ t ] ,   ω [ ω t ω b ˙ Δ t , ω t + ω a ˙ Δ t ]
V d = { ( v , ω ) | v 2 d i s t ( v , ω ) v b ˙ ,   ω     2 d i s t ( v , ω ) ω b ˙ }
where v a ˙ and ω a ˙ represent the maximum acceleration of the robot at time t , v b ˙ and ω b ˙ represent the maximum deceleration, and d i s t ( v , ω ) represents the nearest distance between the robot and the obstacle.
The evaluation function is given as Equation (23).
G ( v , ω ) = a * h e a d i n g ( v , ω ) + b * d i s t ( v , ω ) + c * v e l o c i t y ( v , ω )
where h e a d i n g ( v , ω ) is the angle between the velocity direction and the goal, v e l o c i t y ( v , ω ) is the value of the velocity, and a , b , c are the influence factors of angle, distance and velocity, respectively.
This paper concentrates on the path planning in an amphibious environment. The trajectory and motion state of the robot can be restored as much as possible by combining with the artificial potential field method and the dynamic window method. The impact on the whole trajectory can be observed more precisely when the motion state changes, and this provides the data support for the further adjustment and optimization later on.
Figure 6 shows the flow-process diagram of the hybrid algorithm. Firstly, information related to the environment, obstacles and the robot itself must be obtained. The former two items of information are identified by sensors mounted on the robot, while the latter information is obtained by its own parameters, kinematics and dynamics equations. Since this paper mainly studies amphibious bionic robotic fish, it is necessary to determine whether the environment of the robot is land or underwater. This can be identified by mounting a pressure sensor on the top of the robot. Before the environment is confirmed, the robot is in a static state. Then, the corresponding motion parameters are selected through the controller based on the environment. After the above preparation work is completed, the potential field function is established and the path planning for the unknown environment is carried out; meanwhile, the constraint function also constrains the robot itself. In the process of movement, whether the resultant force of the potential field is counteracted is constantly judged. If it is counteracted, the virtual target is added, and the potential field function is re-established. This process is repeated continuously until the resultant force is not counteracted. On this basis, it is also necessary to constantly determine whether the environment of the robot has changed, and if so, the motion parameters will be transformed. Finally, when approaching the target point, it is necessary to determine whether the distance between the robotic fish and the target point is less than the influence distance of the target point. If it is within the influence range of the target point, it is necessary to delete the virtual target point so as not to affect the accuracy when the virtual target point is confirmed as the real target point.

5. Simulation Analysis

It is necessary to carry out a simulation to verify the effectiveness of the proposed hybrid algorithm. In this paper, the CPU of the experimental computer is i7–9750h, the memory of the computer is 16GB, and the operating system is windows 10. The algorithm is simulated and verified by the MATLAB 2019a.

5.1. Simulation of Improved Artificial Potential Field

In order to verify that the improved artificial potential field method can overcome the problems of local minimum and goals being unreachable, the traditional artificial potential field method and the improved artificial potential field method are compared and tested. In the process of several simulations, they performed the same, and all could reach the target point. However, in order to highlight the advantages of the improved algorithm, we specifically find this special case and record the coordinate points to present it.
The specific parameters are shown in Table 2.
The simulation experiment is conducted for the problem of goal unreachable. The purpose is to verify whether the improved artificial potential field method can solve this problem and whether the execution time and path length can perform better than the traditional artificial potential field method. The results are shown in Figure 7, Figure 8 and Figure 9, as follows:
It is very important to prove the conclusion with data. Table 3 is obtained by integrating the data in Figure 7, Figure 8 and Figure 9. The main parameters are execution time and path length, due to these two data can well prove the performance of a path algorithm.
Although the goal can be reached and the path lengths of both methods are the same, as shown in Figure 7, the improved algorithm is less time-consuming than the traditional algorithm, which means that the improved algorithm is more efficient. The advantages of the improved artificial potential field method can be obviously highlighted as given in Figure 8 and Figure 9, as the robot cannot reach the goal by choosing the traditional artificial potential field method, and its execution time and path length are significantly longer than the improved method. As such, the results confirm that the improved artificial potential field method can solve the problem of goal unreachable, which reflects its effectiveness, efficiency and reliability.
The purpose is to verify whether the improved artificial potential field method can also solve this goal unreacheable problem, and whether the execution time and path length can perform better than the traditional artificial potential field method. The results are shown in Figure 10 and Figure 11, as follows:
The left side pictures represent the simulation results of traditional artificial potential field method, and the right side is the improved artificial potential field method. In the same environment, it can well show the excellent performance of the improved traditional artificial potential field method, which not only solves the local minimum problem, but also has shorter running path, and also proves the effectiveness of the improved algorithm.
It can be seen from Table 4 that the robot using the traditional artificial potential field method halts and vibrates when halfway, since the value of the resultant force is equal to 0 in the case of the local minimum problem. The improved artificial potential field method solves this problem well, which again verifies the superiority of the improved artificial potential field method compared with the traditional artificial potential field method.

5.2. Simulation of the Hybrid Algorithm

In order to enhance the simulation performance of the path planning for an amphibious robot, it is very important to take into consideration the impact of different motion modes on path planning. The dynamic window method is combined with the improved potential field method for simulation, because its algorithm requires the dynamics and kinematics equations of the robot as its own constraints, which is more in line with the actual situation. Figure 12, Figure 13, Figure 14 and Figure 15 are the simulation results as follows, the right side figures show the curve which means the distance between the robot and the obstacle, and the left side is the whole process of the robot running.
Here, the numbers from 1 to 10 represent the obstacles’ serial numbers. The horizontal axis represents the number of iterations, and the vertical axis represents the distance between the robotic fish and the obstacle. Every curve has this pattern: with an increase in time, the robot approaches the obstacle and then moves away from it, and finally, the fluctuation is caused by the constant correction of distance (essentially local minima problem). In the end, the vibration can approach and flatten quickly, indicating that at this time, it keeps a certain distance from the obstacle, and does not take a repeated road section. In other words, it can continue to move towards the target point. Meanwhile, it can also prove the correctness of the establishment of the artificial potential field equation. The bottom horizontal blue line indicates the minimum boundary distance, and our simulation is always within the safe range. In addition, the intersection of 10 lines with different distances in the figure is precisely due to the change of the environment, which changes the motion mode.
We divide these into two groups. Figure 12 and Figure 13 are group 1, and Figure 14 and Figure 15 are group 2. Among all the environmental parameters and the parameters of robot fish itself, the only difference lies in the transformation time of the dynamic equation. This is because, according to the improved equation, only this parameter is easy to control. Figure 12 and Figure 14 show that there is no time step for the transformation progress; however, Figure 13 and Figure 15 show the results of the transformation motion mode with 20 times steps. It can be seen that the robot can reach the goal in all cases, which proves that the hybrid algorithm is effective. As shown in group 1, the transformation time has little impact on path planning; however, in the second group, which has a local minimum problem, the transformation time has a significant impact on the efficiency and stability of the whole path planning. We set the duration of the conversion so that the wavelength is shorter, faster and more stable. Therefore, the hybrid algorithm increases the transformation time as much as possible to ensure that it can be more efficient and effective.

6. Discussion

The artificial potential field method is widely used in local path planning because of its simple and real-time performance. Many scholars have studied the improved algorithm to further improve its performance. It is usually used as follows: through the improvement of the gravitational field model to avoid the problem of encountering obstacles, when the distance is too far and the gravitational force is too large; on the basis of the original repulsion field and considering the influence of the relative position and velocity between the target and the robot, a new repulsion function is introduced to reduce the strength of the repulsion potential field of the obstacle near the target, and solve the problem that the obstacle near the target leads to an unreachable target. By adding a random perturbation, the robot can jump out of the local optimal value, similar to the local optimal value solution of the gradient descent method, or react in advance by introducing the method of predicted distance.
Dynamic path planning in a complex environment is required for the environmental adaptability of amphibian robotic fish. This paper combines the advantages of the two methods: on the premise of exploring in the unknown environment and reaching the target, at the same time, the robot itself is constrained to ensure that the path planned according to the robot’s own conditions can be achieved by the algorithm. This fusion algorithm can restore the motion track and motion state of the robot as much as possible, and the result is more convincing. Meanwhile, it can more accurately observe the influence degree of the change of motion state on the whole motion track, which is convenient for targeted improvement.

7. Conclusions

In this paper, an improved path planning algorithm for an amphibious robot is proposed, which overcomes the shortcomings of the existing algorithm. The simulation experiment in this paper can be divided into two parts: one is to verify that the improved artificial potential field method has a greater ability to solve the target unreachable and local minimum problems than the traditional artificial potential field method. Secondly, the feasibility of the fusion algorithm is verified, and the performance of the fusion algorithm is improved by adjusting the conversion time. The simulation is suitable for describing the path planning of amphibious robot. The results verify the efficiency, instantaneity, and reliability of the hybrid algorithm. This provides a new approach to path planning for this kind of amphibious robot with a variable motion pattern.

Author Contributions

Writing—original draft preparation, W.Y.; writing—review and editing, P.W. and X.Z.; supervision, H.L.; software, P.W. and X.L.; funding acquisition, G.Z., Z.H. and W.W. All authors have read and agreed to the published version of the manuscript.

Funding

This research has been supported by the project of high flexible and multidimensional blended Series-parallel robot and industrialization, China (2014ZT05G132).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Acknowledgments

We would like to thank our mentors and all our colleagues for their help and support.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Patle, B.K.; Babu, L.G.; Pandey, A.; Parhi, D.R.K.; Jagadeesh, A. A review: On path planning strategies for navigation of mobile robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
  2. Liu, Y.; Li, Z.; Liu, H.; Kan, Z. Skill transfer learning for autonomous robots and human–robot cooperation: A survey. Robot. Auton. Syst. 2021. [Google Scholar] [CrossRef]
  3. Pan, M.; Linner, T.; Pan, W.; Cheng, H.-M.; Bock, T. Influencing factors of the future utilization of construction robots for buildings: A Hong Kong perspective. J. Build. Eng. 2021. [Google Scholar] [CrossRef] [Green Version]
  4. Hawes, N.; Burbridge, C.; Jovan, F.; Kunze, L.; Lacerda, B.; Mudrova, L.; Young, J.; Wyatt, J.L.; Hebesberger, D.; Kortner, T.; et al. The STRANDS Project: Long-Term Autonomy in Everyday Environments. IEEE Robot. Autom. Mag. 2017, 24, 146–156. [Google Scholar] [CrossRef] [Green Version]
  5. Karami, H.; Hasanzadeh, M. An adaptive genetic algorithm for robot motion planning in 2D complex environments. Comput. Electr. Eng. 2015, 43, 317–329. [Google Scholar] [CrossRef]
  6. Han, J.; Seo, Y.H. Mobile robot path planning with surrounding point set and path improvement. Appl. Soft Comput. 2017, 57, 35–47. [Google Scholar] [CrossRef]
  7. Zhang, J.; Xia, Y.; Shen, G. A novel learning-based global path planning algorithm for planetary rovers. Neurocomputing 2019, 361, 69–76. [Google Scholar] [CrossRef] [Green Version]
  8. Chand, P.; Carnegie, D.A. A two-tiered global path planning strategy for limited memory mobile robots. Robot. Auton. Syst. 2012, 60, 309–321. [Google Scholar] [CrossRef]
  9. Heinemann, T.; Riedel, O.; Lechler, A. Generating smooth trajectories in local path planning for automated guided vehicles in Production. Proc. Manuf. 2019, 39, 98–105. [Google Scholar] [CrossRef]
  10. Saranya, K.; Koteswara, R.; Unnikrishnan, M.; Brinda, V.; Lalithambika, V.R.; Dhekane, M.V. Real Time Evaluation of Grid Based Path Planning Algorithms: A comparative study. IFAC Proc. 2014, 47, 766–772. [Google Scholar] [CrossRef]
  11. Fu, B.; Chen, L.; Zhou, Y.; Zheng, D.; Wei, Z.; Dai, J.; Pan, H. An improved A* algorithm for the industrial robot path planning with high success rate and short length. Robot. Auton. Syst. 2018, 106, 26–37. [Google Scholar] [CrossRef]
  12. Xie, L.; Xue, S.; Zhang, J.; Zhang, M.; Tian, W.; Haugen, S. A path planning approach based on multi-direction A* algorithm for ships navigating within wind farm waters. Ocean Eng. 2019, 184, 311–322. [Google Scholar] [CrossRef]
  13. Song, R.; Liu, Y.; Bucknall, R. Smoothed A* algorithm for practical unmanned surface vehicle path planning. Appl. Ocean Res. 2019, 83, 9–20. [Google Scholar] [CrossRef]
  14. Jiao, Z.; Ma, K.; Rong, Y.; Wang, P.; Zhang, H.; Wang, S. A path planning method using adaptive polymorphic ant colony algorithm for smart wheelchairs. J. Comput. Sci. 2018, 25, 50–57. [Google Scholar] [CrossRef]
  15. Wang, Z.; Zhu, X.; Han, Q. Mobile robot path planning based on parameter optimization ant colony algorithm. Proc. Eng. 2011, 15, 2738–2741. [Google Scholar]
  16. Orozcorosas, U.; Montiel, O.; Sepúlveda, R. Mobile robot path planning using membrane evolutionary artificial potential field. Appl. Soft. Comput. 2019, 77, 236–251. [Google Scholar] [CrossRef]
  17. Keyu, W.; Esfahani, M.A.; Yuan, S.; Wang, H. TDPP-Net: Achieving three-dimensional path planning via a deep neural network architecture. Neurocomputing 2019, 357, 151–162. [Google Scholar]
  18. Wang, M.; Su, Z.; Tu, D.; Lu, X. A hybrid algorithm based on Artificial Potential Field and BUG for path planning of mobile robot. In Proceedings of the 2013 2nd International Conference on Measurement, Information and Control, Harbin, China, 16–18 August 2013. [Google Scholar]
  19. Yuan, M.; Wang, S.; Wu, C.; Li, K. Hybrid ant colony and immune network algorithm based on improved APF for optimal motion planning. Robotica 2010, 28, 833–846. [Google Scholar]
  20. Lee, M.; Park, M.G. Artificial potential field-based path planning for mobile robots using a virtual obstacle concept. In Proceedings of the 2003 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM 2003), Kobe, Japan, 20–24 July 2003. [Google Scholar]
  21. Wang, Q.; Cheng, J.; Li, X. Path planning of robot based on improved artificial potentional field method. In Proceedings of the 2017 International Conference on Artificial Intelligence, Automation and Control Technologies, Wuhan, China, 7–9 April 2017. [Google Scholar]
  22. Ballesteros, J.; Urdiales, C.; Velasco, A.B.M.; Ramos-Jiménez, G. A biomimetical dynamic window approach to navigation for collaborative control. IEEE Trans. Hum. Mach. Syst. 2017, 47, 1123–1133. [Google Scholar] [CrossRef]
Figure 1. Diagram of stress analysis.
Figure 1. Diagram of stress analysis.
Applsci 11 02114 g001
Figure 2. Diagram of 5–DOF motion.
Figure 2. Diagram of 5–DOF motion.
Applsci 11 02114 g002
Figure 3. The local minimum problem. (a) Case 1. (b) Case 2.
Figure 3. The local minimum problem. (a) Case 1. (b) Case 2.
Applsci 11 02114 g003
Figure 4. The goal unreachable problem.
Figure 4. The goal unreachable problem.
Applsci 11 02114 g004
Figure 5. Improved attraction field diagram.
Figure 5. Improved attraction field diagram.
Applsci 11 02114 g005
Figure 6. The flow-process diagram of the hybrid algorithm.
Figure 6. The flow-process diagram of the hybrid algorithm.
Applsci 11 02114 g006
Figure 7. Case 1. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Figure 7. Case 1. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Applsci 11 02114 g007
Figure 8. Case 2. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Figure 8. Case 2. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Applsci 11 02114 g008
Figure 9. Case 3. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Figure 9. Case 3. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Applsci 11 02114 g009
Figure 10. Case 4. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Figure 10. Case 4. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Applsci 11 02114 g010
Figure 11. Case 5. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Figure 11. Case 5. (a) Traditional artificial potential field method. (b) Improved artificial potential field method.
Applsci 11 02114 g011
Figure 12. Case without time step in group 1. (a) Path planning of 3D map. (b) The distance from obstacles.
Figure 12. Case without time step in group 1. (a) Path planning of 3D map. (b) The distance from obstacles.
Applsci 11 02114 g012
Figure 13. Case with time step in group 1. (a) Path planning of 3D map. (b) The distance from obstacles.
Figure 13. Case with time step in group 1. (a) Path planning of 3D map. (b) The distance from obstacles.
Applsci 11 02114 g013
Figure 14. Case without time step in group 2. (a) Path planning of 3D map. (b) The distance from obstacles.
Figure 14. Case without time step in group 2. (a) Path planning of 3D map. (b) The distance from obstacles.
Applsci 11 02114 g014
Figure 15. Case with time step in group 2. (a) Path planning of 3D map. (b) The distance from obstacles.
Figure 15. Case with time step in group 2. (a) Path planning of 3D map. (b) The distance from obstacles.
Applsci 11 02114 g015
Table 1. The amphibious robot motion parameters.
Table 1. The amphibious robot motion parameters.
NameSymbolUnderwaterLand
Total mass m 10 kg10 kg
Length of the fin surface l 75 cm75 cm
Wavelength λ 20 cm20 cm
Coulomb friction coefficient μ /0.85
Velocity V 0.23 m/s0.13 m/s
Angular velocity ω 0.31 rad/s0.12 rad/s
Table 2. The parameters of the improved potential field method.
Table 2. The parameters of the improved potential field method.
NameSymbolValue
Attractive field factor k a t t 15
Repulsive field factor k r e p 5
Obstacle influence distance ρ 0 1 m
Goal influence range d 0 3 m
Maximum number of iterations n 200
Time step Δ t 0.1 s
Angle influence factor α 0.2
Velocity influence factor β 0.1
Distance influence factorγ0.1
Table 3. The comparison results between the improved and traditional algorithm.
Table 3. The comparison results between the improved and traditional algorithm.
MethodFigureExecution timePath Length
traditional artificial potential field method7a0.8230 s14.1421 m
8a0.7760 s11.0143 m
9a0.7990 s17.8513 m
improved artificial potential field method7b0.7910 s14.1421 m
8b0.6930 s9.7637 m
9b0.5430 s8.9057 m
Table 4. The comparison results between the improved and traditional algorithm.
Table 4. The comparison results between the improved and traditional algorithm.
MethodFigureExecution TimePath Length
traditional artificial potential field method10a0.7830 s2.6717 m
11a0.7770 s1.3853 m
improved artificial potential field method10b0.8030 s4.1231 m
11b0.7940 s4.4283 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

Yang, W.; Wu, P.; Zhou, X.; Lv, H.; Liu, X.; Zhang, G.; Hou, Z.; Wang, W. Improved Artificial Potential Field and Dynamic Window Method for Amphibious Robot Fish Path Planning. Appl. Sci. 2021, 11, 2114. https://doi.org/10.3390/app11052114

AMA Style

Yang W, Wu P, Zhou X, Lv H, Liu X, Zhang G, Hou Z, Wang W. Improved Artificial Potential Field and Dynamic Window Method for Amphibious Robot Fish Path Planning. Applied Sciences. 2021; 11(5):2114. https://doi.org/10.3390/app11052114

Chicago/Turabian Style

Yang, Wenlin, Peng Wu, Xiaoqi Zhou, Haoliang Lv, Xiaokai Liu, Gong Zhang, Zhicheng Hou, and Weijun Wang. 2021. "Improved Artificial Potential Field and Dynamic Window Method for Amphibious Robot Fish Path Planning" Applied Sciences 11, no. 5: 2114. https://doi.org/10.3390/app11052114

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