Simulation Research on Real-time Path Planning and Formation Control of Unmanned Ship

Source: Journal of System Simulation

Authors: Song Dalei, Gan Wenhao, Xu Yingzhi, Qu Xiuqing, Cao Jiangli

pick

want

Safe and collision-free navigation is the basis for the normal navigation of unmanned ships. A high-fidelity virtual ocean environment is constructed through Unity3D. Based on the modeling of unmanned ships, a real-time path planning and formation control method for unknown and complex environments is proposed. Using the local environment information obtained by lidar, under the re-planning strategy, combined with A-star and route thinning methods to complete real-time local path planning. The formation control is based on the leader-follower strategy and consistency method, combined with the artificial potential field method to complete the obstacle avoidance navigation task of multiple unmanned ships. The simulation experiments on a variety of complex maps show that the simulation system has better authenticity and visual effects, and provides an effective means for the simulation test of unmanned ships. At the same time, using the proposed algorithm, the unmanned fleet can arrive at the preset waypoints one by one, change formation autonomously and avoid obstacles in real time, which has certain theoretical significance and practicality in engineering applications.

Key words

 unmanned ship ; motion simulation ; scene simulation ; path planning ; formation control

introduction

As countries around the world pay more and more attention to the ocean, the unmanned surface vessel (USV) has been widely used in marine scientific investigation, maritime search and transportation [1-2] due to its high degree of autonomy and strong mobility. widely used. At the same time, with the increase in the complexity of navigation tasks, multi-unmanned ship collaborative operations have emerged [3].

Path planning and formation control of multiple unmanned ships is one of the core issues that need to be considered in the operation of unmanned ships [4]. Effective design of them can improve the work efficiency of unmanned ships. Due to the size of the USV, the sensors it carries, and the complexity of the water environment, it is difficult and time-consuming to implement USV field experiments. In the early stages of development, it is not appropriate to test the correctness of the system design through actual flight experiments. Therefore, it is particularly important to simulate the navigation of USV in the virtual environment. The simulation of its motion control scheme and the visualization of the navigation process are of great importance for the analysis of the integrity of the system design and the movement of the USV under the requirements of environmental disturbance and automatic collision avoidance. Significance.

In terms of path planning and formation algorithms, there have been some related researches in recent years. Literature [5] proposed an improved ant colony algorithm for path planning, and used the leader-follower method to realize multi-robot formation, but did not consider the problem of group real-time path planning and formation transformation. Literature [6] proposes a path planning algorithm based on rapidly expanding random trees, and combines the leader-follower structure and position constraints to realize formation. Literature [7] uses the artificial potential field method to plan the path and avoid obstacles in formation for multi-robots, but does not perform formation transformation and there is a certain range of errors in the process of traveling. Literature [8] combined the artificial potential field method with the virtual structure method, and designed a formation control method. This method can flexibly realize formation changes, but when avoiding obstacles, a single aircraft is allowed to slide along the boundary of obstacles and then return to the original formation. Literature [9] aimed at the obstacle avoidance problem of unmanned ship formation in an unknown environment, modeled the obstacles, and then designed a real-time collision avoidance controller based on the pilot-follow method. Although this method can guarantee the completion of obstacle avoidance while completing the tracking task, each unmanned ship avoids obstacles by itself. In general, at this stage, the formation method using the leader-follower has been able to better solve the problems of formation maintenance and trajectory tracking. In the study of formation and obstacle avoidance problems, there are different solutions, such as maintaining the original formation and controlling the entire group to avoid obstacles from one side, or breaking up the original formation to avoid obstacles and so on. Most of these methods are designed based on the situation where the state of the environment is known, and the shape of obstacles is regular and the distribution is relatively sparse. It is not an optimal solution for complex environments.

In response to the above problems, this paper aims to build a high-fidelity unmanned ship simulation platform, and propose a real-time path planning and formation control strategy for unknown and complex environments. The built simulation platform can provide a full-stack closed-loop simulation, simulate ideal conditions or specific environmental disturbances, reproduce the navigation effect of unmanned ships and provide real-time feedback information. The proposed navigation algorithm can guide multiple unmanned ships to perform real-time path planning in an unknown environment to reach each preset waypoint, and maintain order and autonomous formation and obstacle avoidance during the navigation process.

1 Construction of simulation platform

1.1

 Unmanned ship model

A real USV is used for simulation research, the model is shown in Figure 1, and the structural parameters are shown in Table 1. In order to meet the higher simulation fidelity and simulation performance of USV objects, the model is partially simplified, and the simplified hull mesh has 23 707 triangular faces and 34 559 vertices. The ship adopts a double body structure, and is equipped with 2 propellers on both sides of the stern, and the vector angle is fixed. The unmanned ship can generate yaw motion by controlling the speed of two propellers.

Figure 1 USV model used in this paper

Table 1 USV model parameters

 1.1.1 

 Kinematic model of unmanned ship

Although the USV can only move on the sea surface by controlling the propellers on both sides, when it sails, it may encounter various waves at various speeds and heading angles, resulting in 6 degrees of freedom. Therefore, This article will focus on the 6 degrees of freedom (6DOF) motion of the USV. The coordinate system used in this work is shown in Fig. 2, where E0 represents the inertial coordinate system, B0 represents the body coordinate system, and the descriptions of related variables are given in Table 2.

Figure 2 Schematic diagram of the USV coordinate system

Table 2 Coordinate variables of unmanned ships

The state of the USV can be described as

(1)

The conversion matrix from the velocity and angular velocity in the USV body coordinate system to the inertial coordinate system can be expressed as

(2)

(3)

Thus, the kinematic model of the USV can be described as

(4)

 1.1.2 

Dynamic model of unmanned ship

The dynamic model of the unmanned ship is used to describe the state changes of the unmanned ship when it is subjected to force and moment [10]. According to the Newton-Euler equation of motion of a rigid body in a fluid, the dynamic model of the underactuated USV can be described as

(5)

In the formula: M is the inertial mass matrix of the unmanned ship, which is composed of the rigid body inertia matrix MRB and the inertia matrix MA of the additional mass, which can be obtained by obtaining the fluid dynamic parameters through Solidworks and other software modeling and CFD simulation analysis; similarly, C( v) is the centripetal force and Coriolis force coefficient matrix; D is the water damping matrix, the resistance of the unmanned ship on the water surface can be approximately expressed as a correlation with the square of the velocity [11], which can be completed through the FLUENT resistance simulation of the unmanned ship The fitting relationship; g(η) is the restoring force/moment, which represents the joint action of gravity and buoyancy; τ is the driving force and driving moment vector of the unmanned ship; d is the ocean disturbance. Meanwhile, the driving force and driving moment τ of the USV are calculated from the thrusts Tport and Tstbd of the port and starboard thrusters. In the actual control task, since it is necessary to control the rotational speed of the differential propeller, it is also necessary to obtain the corresponding relationship between the thrust and the revolutions per minute (RMP) of the propeller, and this process can be completed through hydrodynamic simulation fit.

The key to solving equation (5) is to obtain various forces and moments acting on the unmanned ship. This process is calculated in the FixedUpdate function in Unity3D: the force value is transmitted to the AddRelativeForce component function, and the torque value is transmitted To the AddRelativeTorque component function, the relevant matrix variables are updated every frame and the real-time motion state of the USV is solved, and the update period is 0.02 s.

1.2

 The marine environment

The purpose of the USV is to navigate and perform tasks on the sea surface, so the construction of the sea surface environment is the main focus. When it sails, it is mainly affected by the two factors of waves and currents.

 1.2.1 

 wave construction

For the simulation of the sea surface, the seawater can be regarded as composed of various surface particles, and these particles move on the three-dimensional curved surface to form the surface structural waves [12]. The amplitude of these particles can be regarded as the wave height at a certain point on the sea level, and the movement of many such particles constitutes the wave height field in the entire sea area.

Considering that the wave spectrum is an important means to study the properties of ocean waves at this stage [12], the simulation platform realizes the drawing of ocean waves based on the Phillips spectrum model, which can be expressed as

(6)

In the formula: A is the Phillips constant, and the value is 0.008 1 according to the literature [13];

is the wind speed (wave height affecting the wave), g is the gravity constant; ωD is the wind direction (two-dimensional vector, affecting the wave direction of the wave); the wave number can be expressed as n=2π/ωl, ωl is the wavelength; the wave number vector is k=( kx,ky)=(ncosθ,nsinθ) , θ is the angle between the vector k and the positive semi-axis of the x-axis.

The wave is set to be formed by superposition of 14 different waves, index=0,1,⋯,13. From this, the corresponding wavelength ωl=2−4+index can be obtained. For the spectral analysis model, the seawater height field at the position vector X=(x,y) at time t can be expressed as

(7)

In the formula: * is a complex conjugate number;

is the initial spectral model, which consists of two independent Gaussian random numbers εr and εi and the spectral function:

During the simulation process, the wave height hw corresponding to each grid vertex on the sea surface where the USV is located, the real-time three-dimensional wave velocity vw=[uw , vw , ww] and the wave normal nw can be obtained, so as to further calculate the USV's Real-time buoyancy, as well as wave disturbance forces and moments on the USV.

 1.2.2 

 stream construction

Considering the actual working time of the USV and the limitation of the working area, the movement speed, flow rate and flow direction of the ocean current in a specific area are usually relatively stable for a long period of time, that is, the ocean current changes slowly and is stable and non-rotating. .

The existence of ocean currents will change the hydrodynamic forces on the USV [14]. Let Vc=(Uc , Vc , 0) be the ocean current velocity in the inertial coordinate system; vr indicates the motion velocity of the USV relative to the fluid, and its components in the body coordinate system are (ur , vr , wr), and the integrated wave velocity can be get

(8)

1.3

 sensor model

Because the height of obstacles has little effect on USV path planning, the path planning of USV can be regarded as navigation on a two-dimensional surface. In this paper, the simplified Merlin shipborne laser sensor is used to obtain obstacle information around the USV, as shown in Figure 3 and Table 3. The simplified sensor uses virtual light to detect the local environment, so as to obtain information such as the position and angle of obstacles from the current USV. At the same time, once the sensor detects a local obstacle, it will store the information of the obstacle and use it for obstacle avoidance.

Figure 3 The laser sensor mounted on the USV

Table 3 Simplified shipborne laser sensor information

For the operation part of the simulation platform, a control platform was built using WinForm technology to simulate the command and operation of the unmanned ship by the ground shore station. The rest of the visualization parts, such as the camera angle of view, the construction of the seabed terrain, the rendering of lights, the display of the aircraft track and trailing effect, etc., the design process is similar to that mentioned in the literature [15-16], and will not be repeated here. repeat.

2 Algorithm design

2.1

 overall plan

The designed algorithm is suitable for solving the problem of path planning and formation control of multiple unmanned ships in an unknown environment. The problem can be described as follows: there are several unknown obstacles in the environment (such as islands arising from tidal phenomena), and the unmanned ships need to form a formation to safely pass through a narrow area composed of obstacles or bypass obstacles to reach the preset waypoints. The overall strategy adopts a multi-agent layered navigation control scheme, and the entire control system is divided into: target layer, leadership layer and follower layer.

  • (1) Target layer: This layer is input by the user using the control platform, that is, to designate a series of key waypoints during the navigation of USVs.

  • (2) Leadership: The formation leader plans the path in real time according to key waypoint information, determines the corresponding formation formation by communication topology analysis, and avoids obstacles in real time during navigation.

  • (3) Follow layer: the formation follower moves with the leader and maintains the corresponding formation.

Figure 4 shows a class of application scenarios of this algorithm. When the USV group does not detect any obstacles around it, it will advance in the set formation. Once a USV detects that there is an obstacle in the forward direction, it will change its formation to a long snake array passing through or bypassing the obstacle along the edge (where Δd represents the relative distance between the front and rear unmanned ships). After getting away from the obstacle, adjust back to the original formation and continue to the next waypoint.

Figure 4 Schematic diagram of path planning and tracking

According to the distance between the USV and the obstacle, the area near the obstacle can be defined as a safe area, an obstacle avoidance area or a dangerous area. When the USV enters the obstacle avoidance zone, the obstacle avoidance mode is triggered to avoid the obstacle without entering the forbidden zone, as shown in Figure 5. Among them, Rmax and Rmin are the radii of the obstacle avoidance area and the danger area respectively, and Rmax=80 m and Rmin =20 m are selected; Robs is the shortest distance from the obstacle to the USV.

Figure 5 Schematic diagram of obstacle avoidance strategy for unmanned ships

(1) When Robs>Rmax, the path following mode is valid.

(2) When Rmin≤Robs≤Rmax, the collision avoidance mode is valid.

(3) When Robs<Rmin, the USV is too close to the obstacle at this time, and it is considered as an obstacle avoidance failure.

2.2

 Navigator's Path Planning Algorithm

An unmanned ship needs to have the ability to navigate autonomously in a complex environment. The first thing it should have is the path planning ability, that is, how to find a safe navigation route from the starting point to the end point in the USV mobile space. Considering that this paper mainly studies the path planning problem of unmanned ships in the environment with obstacles of arbitrary shape, the operation of gridding the environment by using the graph search method can well incorporate the shape of obstacles into the scope of planning. At the same time, this method is currently recognized as the most mature algorithm with the highest safety factor [17].

On this basis, a real-time re-planning strategy is designed based on the A-Star algorithm [17], and combined with the PID control method to complete the path planning and path tracking tasks. This algorithm is suitable for planning local collision-free routes in real time when the distribution of obstacles is unknown. After determining the position of the waypoints that must be passed during the voyage, a pre-planned path will be generated, and the unmanned ships will pass through each waypoint in turn; at the same time, when the laser sensor on the unmanned ship detects obstacles , the local dynamic path planning will be performed again to avoid obstacles. The overall flowchart of the algorithm is shown in Figure 6.

Figure 6 Path re-planning and tracking flow chart

Among them, the size of the grid granularity needs to be designed according to the scope of the operating environment of the unmanned ship, and is related to the size of the global two-dimensional grid map map[x, y] shared among multiple unmanned ship groups. A larger granularity means that the environment division is relatively rough, but the algorithm execution efficiency will be greatly improved. On the contrary, a smaller granularity means that the environment is divided more finely, and the planned path will be finer, but it also increases the planning time of the algorithm. At the same time, due to the unknown environment, the shared grid map map[x, y] has no prior information at the beginning, and the terrain will be gradually filled only after new environmental information is explored (according to the information collected by each USV sensor) information data.

Every time you reach a new necessary waypoint (key point, obtained by artificial setting), a planned path point (obtained by a planning algorithm) or a sensor detects a new obstacle, you need to execute the new A* planning algorithm again, so that Get a navigation path that matches the current state. After that, the Douglas-Peucher algorithm (Douglas-Peucher) is used to optimize the route to reduce the redundant steering maneuvers of the unmanned ship group.

After obtaining the optimized navigation path, use the double closed-loop controller to complete the navigation control of the pilot unmanned ship. The control block diagram is shown in Figure 7.

Figure 7 Double closed-loop control strategy

The controller mainly consists of a position loop and a speed loop connected in series.

  • (1) For the position loop, according to the planned coordinates of the next path point P(x, y), the corresponding rotation angle deviation eψ and position deviation ep can be calculated to form the input items of the loop, and the output is the body coordinates of the USV system The expected advance and retreat linear velocity uR and the expected rotational angular velocity rR under the system.

  • (2) For the speed loop, according to the output of the position loop and combined with the real advance and retreat linear velocity u and the rotational angular velocity r of the USV system at the current moment, the velocity deviation eu and the angular velocity deviation er are formed, and finally the rotational speed control amount of the USV differential propeller is calculated nport and nstbd complete the control of the USV navigation system.

2.3

 Algorithm of Unmanned Ship Formation Control

The multi-unmanned ship formation problem mainly considers the information interaction strategy and the design of the formation control scheme. Among them, the distributed method in the information interaction strategy has lower requirements on communication equipment and computing equipment, and is considered to be the optimal information interaction strategy. The mature and easy-to-extend features of the lead-follow Fein theory in the formation control scheme have been widely used. This paper will use the graph theory method to determine the communication topology of the unmanned ship formation, and then use the leader-follower distributed control structure combined with the cluster consensus method to solve the formation control problem.

 2.3.1 

 system consistency

The key idea of ​​the formation control algorithm based on cluster consistency is to control the state quantities such as the relative position and velocity between the leader and the follower. When these state quantities reach a steady state, the formation formation is realized [18]. In this paper, the USV swarm dynamic system is cooperatively controlled through a communication graph. Information exchange in formation is represented by G=(X, E). Among them, X={x1 , x2 , ⋯, xN} represents the set of N nodes, EE is the edge set of the network topology graph, and the element (pi , pj) in the set E represents the edge from the node pj to pi, denoted as eji. A(G)=[aij]∈Rn×n is used to represent the adjacency matrix of the interaction graph G, which satisfies the following relationship:

(9)

 2.3.2 

 Navigator-Based Behavioral Consistency Approach

First establish the mathematical model of the follower:

(10)

In the formula: ξi and δi are the state information (such as turning angle, position information, velocity, etc.) and control input (such as turning angular velocity, velocity, acceleration, etc.) of the i-th USV follower, respectively.

The mathematical model for the navigator can be expressed as

(11)

Under any initial conditions, when the state of the follower satisfies:

(12)

The USV group is formed with a coherent leader. For leader-based cluster consistency can be expressed as

(13)

In the formula: δi is the speed change control value of unmanned ship i;

is the distance to be kept between unmanned ships i and j. while the weight term is set to

Finally, the expected velocity components of the i-th (i>0) follower unmanned ship in the x- and y-axis directions in the inertial coordinate system are obtained at time t:

(14)

In the formula:

And it has a maximum value δmax, which is taken as 2 in the simulation; it indicates the direction of speed change; K0 and γ are constants, which are taken as 1 and 0.5 in the simulation, respectively.

 2.3.3 

 Collision avoidance between hulls based on artificial potential field method

In order to avoid the collision between unmanned ships, the repulsion field in the artificial potential field is introduced. The repulsive force frep can represent the gradient of the repulsive force field Urep, and the repulsive force relationship between the unmanned ship i and the unmanned ship j in the x-axis direction can be expressed as

(15)

In the formula: η is the repulsion scale factor, which is taken as 10 in the simulation; lij is the distance between unmanned ships i and j; Rdetect represents the influence radius of the repulsion field, that is, when the unmanned ships are far apart There is no repulsion effect between them.

Similarly, the repulsion relationship between ships in the y-axis direction can be obtained. Finally, the expected velocity components of the i-th (i>0) unmanned ship in the x and y-axis directions in the inertial coordinate system at time t are obtained by superposition:

(16)

3 Simulation experiment and analysis

In order to verify the authenticity of USV motion simulation, the validity and reliability of path planning and formation algorithms, and the practicability of the simulation platform, the following three types of experiments were carried out.

3.1

 Verification experiment of unmanned ship motion model

The position, velocity, and angular velocity of the USV were initialized to 0, and then they were dropped into a sea area for drifting experiments. By adjusting the wind speed ωs, the simulation effect obtained is shown in Figure 8.

Figure 8 Simulation results under different wind speeds

The motion states and drifting trajectories of the USV under three wind speeds are plotted, and the simulation results obtained are shown in Figures 9 and 10.

Figure 9. Changes in the motion state of the USV under different wind speeds

Fig.10 Changes of waves at the center of the USV under different wind speeds

It can be seen from the simulation results that the simulation platform can well simulate the motion state of the USV under different wind speeds, which meets the expected effect.

3.2

 Path planning and formation algorithm test experiment

In this experiment, the algorithm was tested using the Python environment. The simulation is carried out by taking the multi-unmanned ship formation passing through the narrow and long waterway as the task scenario. The initial state information of the unmanned fleet is shown in Table 4.

Table 4 Initial state information of unmanned ship swarm

Set the number of waypoints that must be passed during navigation to 4, and the specific location information is as follows:

  • (1) Waypoint 1: (200, 300) m;

  • (2) Waypoint 2: (760, 620) m;

  • (3) Waypoint 3: (1 360, 1 480) m;

  • (4) Waypoint 4: (1 900, 1 900) m.

The simulation step length is set to 0.02 s, and the navigation is carried out according to the start and end formations shown in Figure 4, and the simulation results are shown in Figure 11.

Figure 11 Path planning and formation simulation of unmanned ships passing through narrow and long waterways

It can be seen from Fig. 11(a) that from 0 s, the unmanned ship swarm quickly formed the initial formation structure and moved to waypoint 1; after reaching waypoint 1, it moved to waypoint 2, , the unmanned ship detects that there is an obstacle in front of it, and quickly changes its formation into a long snake array to continue moving; during the movement from waypoint 2 to waypoint 3, since the obstacle is always near the unmanned ship group, the formation is always maintained as Long Snake Formation: During the movement from waypoint 3 to waypoint 4, the group of unmanned ships changes back to the original formation and continues to move after reaching an open area. It can be seen from Fig. 11(b) that during the period from 240 to 730 s, the unmanned ships detected obstacles and changed their formation into a long snake formation, and each unmanned ship kept a fixed distance of 20 m between them. .

The simulation was further carried out in a more complex archipelago area, and the number of waypoints that must be passed during the navigation process was set to 4. The specific location information is as follows:

  • (1) Waypoint 1: (440, 60) m;

  • (2) Waypoint 2: (1 060, 1 140) m;

  • (3) Waypoint 3: (1 640, 1 540) m;

  • (4) Waypoint 4: (1 900,1 900) m.

The simulation results are shown in Figure 12 and Table 5.

Figure 12 Path planning and formation simulation of unmanned ship archipelago

Table 5 Navigation performance of unmanned ships in the archipelago area

It can be seen from Figure 12 and Table 5 that when the unmanned ship group performs path planning and formation tasks in the archipelago, the proposed algorithm can independently plan a safe navigation path and meet the requirements of real-time obstacle avoidance, which reflects the Higher practicality.

3.3

 Comprehensive experiment of simulation system

As a surface intelligent mission platform, the unmanned ship can be used to complete many tasks such as environmental monitoring, marine survey, patrol search and rescue and investigation. Avoiding islands, reefs or other obstacles during navigation and safely arriving at a designated location with a shorter path is one of the basic capabilities that a USV should possess. This section uses the built high-fidelity simulation platform and unmanned ship motion model to carry out comprehensive simulation verification under specific tasks.

Design a reconnaissance mission scenario in which unmanned ship clusters are located in multiple islands and reefs. The unmanned ships need to reach several preset locations. At the same time, due to the unknown tidal environment of islands and reefs, unmanned ships need to continuously collect environmental information during navigation for autonomous path planning and group obstacle avoidance. In this scene, a near-real island scene is built using the terrain editor in Unity3D, and a Mesh collider is added to complete the collision detection of the aircraft. Three USVs are used for simulation, and the initial and final formations are both set to a triangular array with a side length of 40 m. Set 4 key waypoints, and the simulation results are shown in Figures 13-15.

Figure 13 USV group navigation process

Figure 14 Formation formations at the start and end of the USV voyage

Figure 15. The overall navigation trajectory of the USV group under calm sea conditions

The circle around the USV in Figure 14 represents the obstacle avoidance sensor, and when it turns red, it means that the USV has detected an obstacle. It can be seen from the navigation trajectory in Figure 15 that the USV constantly switched formations according to the real-time status information during the navigation process, and finally passed the preset four key waypoints on the premise of ensuring the safety of the group to avoid collisions, and completed the mission. Formation sailing missions.

In addition, in order to verify the applicability of the algorithm in different environments, the constant ocean current and wave are applied in the environment as ocean disturbance items to continue the experiment. In the simulation, the velocity of the sea current is set to 0.5 m/s, and the wind speed is 15 km/h along the direction of 45° west by south. The overall trajectory of the formation is shown in Fig. 16.

Figure 16 The overall navigation trajectory of the USV group under ocean disturbance

It can be seen from Figure 16 that although the swarm trajectory tends to shift to the south-west direction, the unmanned ship swarm can still complete path planning and formation control tasks.

4 Conclusion

Aiming at the needs of the development of unmanned ship navigation system, a set of 3D visual simulation system for multi-unmanned ships is designed and implemented. The mathematical model of USV movement under the interference of currents is established, and a multi-unmanned ship movement visualization simulation platform is built in imitation of the real ship control environment. At the same time, for the navigation problem of multi-unmanned ship groups in complex and unknown environments, a real-time path planning and formation control method based on multi-algorithm fusion is proposed. The method is based on the airborne laser sensor to collect the surrounding environment information, uses the path re-planning strategy, and combines A-star and route thinning methods to complete the real-time path planning of the unmanned ship group in the unknown environment. Then, formation control is carried out based on the leader-follower strategy and consistency method, and the obstacle avoidance function between hulls is completed in combination with the artificial potential field method. This fusion method solves the problem of real-time path planning of multiple unmanned ships in an unknown environment and orderly obstacle avoidance by changing formations, and has greater flexibility and scalability.

On this basis, a specific application scenario is designed for simulation verification. The results show that the simulation system can better simulate the actual navigation status of USV, as well as the path planning and formation behavior of multiple USVs. practicality. At the same time, it also verified that the proposed path planning and formation algorithm can enable the USV group to accurately reach each preset waypoint while effectively avoiding obstacles, and can maintain certain effectiveness and stability in different environments. sex. This method has potential application value in tasks such as maritime transportation and search and rescue of multiple unmanned ships.

Disclaimer: The articles and pictures reproduced on the official account are for non-commercial educational and scientific research purposes for your reference and discussion, and do not mean to support their views or confirm the authenticity of their content. The copyright belongs to the original author. If the reprinted manuscript involves copyright and other issues, please contact us immediately to delete it.

"Artificial Intelligence Technology and Consulting" released

Guess you like

Origin blog.csdn.net/renhongxia1/article/details/131370364