Simulation Framework for Addressing Challenges in Path Planning Evaluation for an Autonomous Surface Vehicle
https://doi.org/10.1007/s11804-025-00646-z
-
Abstract
An efficient algorithm for path planning is crucial for guiding autonomous surface vehicles (ASVs) through designated waypoints. However, current evaluations of ASV path planning mainly focus on comparing total path lengths, using temporal models to estimate travel time, idealized integration of global and local motion planners, and omission of external environmental disturbances. These rudimentary criteria cannot adequately capture real-world operations. To address these shortcomings, this study introduces a simulation framework for evaluating navigation modules designed for ASVs. The proposed framework is implemented on a prototype ASV using the Robot Operating System (ROS) and the Gazebo simulation platform. The implementation processes replicated satellite images with the extended Kalman filter technique to acquire localized location data. Cost minimization for global trajectories is achieved through the application of Dijkstra and A* algorithms, while local obstacle avoidance is managed by the dynamic window approach algorithm. The results demonstrate the distinctions and intricacies of the metrics provided by the proposed simulation framework compared with the rudimentary criteria commonly utilized in conventional path planning works.Article Highlights● In order to accurately evaluate the effectiveness of path planning algorithms before practical implementation, an intergrated simulation environment is developed. The simulation environment incorperates relevant modules such as navigation, guidance & control system; simulated sensors; simulated 3D model of the vessel; visual presentation of the environment; basic physics; external disturbance; data logger.● The simulation framework also outlines the process of creating 3D testing sites from 2D satellite images.● A detailed 6-DOF dynamic model of vessel is applied on the ASV to demonstrate the intricacies of its motions.● The comparisons of ASV's motion between planned trajectories and resultant motion at different maximum velocities are shown. -
1 Introduction
In recent years, attention to autonomous surface vehicles (ASVs) that can navigate marine environments independently has been increasing. ASVs provide advantages such as reduced risks to personnel and lower operational costs because they require minimal human intervention (Ahmed and Aloufi, 2022). Unlike autonomous underwater vehicles (AUVs), ASVs do not need to resurface periodically to correct GPS errors, which is a necessity for AUVs that depend on onboard dead reckoning navigation systems (Vagale et al., 2021). These benefits make ASVs ideal for a wide range of missions, such as water quality sampling and monitoring (Griffiths et al., 2022; Pinto et al., 2022), river cleaning and patrolling (Xie et al., 2020; SaiTeja and Pramod, 2021; Luis et al., 2022), maritime search and rescue operations (Kang et al., 2020; Zhou et al., 2020b), and anti-submarine tasks (Su et al., 2020). The success of these missions relies on robust path planning, which is a crucial technology that underpins the operation of autonomous systems.
Path planning involves determining feasible routes to guide an ASV from its current pose to a designated target pose (Sun et al., 2018). Vagale et al. (2021) detailed several advancements in path planning algorithms for ASV applications regarding computation time, online planning capabilities, and the heuristic characteristics of these algorithms. Overall, the predominant focus of the existing literature has been tailored toward specific operational scenarios for maritime traffic, such as complying with the Convention on the International Regulations for Prevent‐ing Collisions at Sea (Beser and Yildirim, 2018; Zhao and Roh, 2019; Ni et al., 2021; Yu et al., 2021), maneuvering in narrow water passages (Gu et al., 2020), and traversing through wave fields (Lyridis, 2021).
Implementing planned paths for ASVs in real-world scenarios often demands considerable time and resources. Therefore, thoroughly assessing the performance of path planning algorithms using appropriate simulators is important. However, this practice is notably lacking in current research on ASV path planning. Beser and Yildirim (2018) and Naeem et al. (2016) proposed the method of analyzing generated paths depicted on a 2D map lacked proper numerical analysis. Similarly, path length was the only metric utilized to compare the quality of paths generated by different planners (Yang et al., 2015; Singh et al., 2018; Shi et al., 2019; Song et al., 2019; Gu et al., 2020; Zhou et al., 2020a). However, choosing a shorter but rugged path can lead to unsteady motions, which is suboptimal for ASVs due to their inherent inertia, potential for collisions, and deviations from the global path. By contrast, a longer yet smoother path ensures a stable motion profile, which minimizes collision risk and compensates for the total travel time. In addition, the number of turns has been introduced as a comparative metric (Lyridis, 2021; Song et al., 2019), but its impacts on the resultant motion of the vessel and its correlation with other metrics have yet to be analytically discussed.
Some authors ignored computational time as a significant factor in the total execution time (Yang et al., 2015; Singh et al., 2018; Shi et al., 2019; Wen et al., 2020; Zhou et al., 2020b). However, computational time is important, particularly in a navigation pipeline that triggers global path replanning at specific intervals. Similarly, a rudimentary temporal model was used to estimate the total execution time without considering the dynamics of the ASV or the characteristics of low-level controllers (Peralta et al., 2020).
A key factor affecting the evaluation of path planners is the quality of localization methods. Previous studies often assume ideal conditions due to the lack of simulated sensors. However, incorporating measurement noise in simulated sensor models introduces localization inaccuracies, which reflect real-world scenarios. The robustness of a path planner can be effectively evaluated by incorporating variations in localization. Velocity profiles were generated from its path planners (Singh et al., 2020), and Sun et al. (2018) integrated them with system dynamics to estimate vessel motion. However, both studies ignored the significant external influences of wind and waves, which are crucial factors affecting the resultant velocity profile of an ASV.
In the field of ASV simulation, several works have made significant contributions. Thakur and Gupta (2011) developed a vessel simulation approach based on potential-flow theory, combined with model simplification techniques such as clustering, temporal coherence, and parallel computing to reduce computational overhead while maintaining an acceptable level of accuracy. Subsequently, Heins et al. (2017) introduced a comprehensive simulation framework for the Halcyon vessel. This framework encompasses a detailed six-degree-of-freedom (6-DOF) nonlinear unified model for seakeeping and maneuvering boat dynamics, an actuation dynamics model, and an innovative sea-surface wave environment model. Furthermore, MARS (MArine Robotics Simulator) was introduced by Tosik and Maehle (2014), which is an online hardware-in-the-loop simulation environment designed for AUVs and ASVs. MARS, which is powered by the 3D Engine jMonkeyEngine, provides advanced underwater graphics and focuses on interactions between marine robots and their environment. However, the aforementioned vessel simulators lack a proper physics engine, which is essential for simulating fundamental interactions such as gravity and collisions. Moreover, the application and integration of software-in-the-loop (SIL) within these simulators remain unclear, even though SIL is crucial for implementing path planning algorithms.
Regarding simulators based on the robot operating system (ROS), Mendonça et al. (2013) introduced Kelpie, which focuses on aerial and water surface vehicles, using OpenGL for visual rendering and BulletPhysics Engine for basic physical interactions. Moreover, Lončar et al. (2022) and Garg et al. (2020) developed marine vehicle simulators using the Unity3D platform, which is known for high visual fidelity. However, the software pipelines of these simulators do not specifically support the integration of path planning algorithms and assessments for ASVs, which is the main focus of this research.
Therefore, to address the shortcomings identified in previous research regarding the integration of navigation in ASV simulators, this study introduces an integrative simulation framework with the following contributions:
• A vessel simulator based on the ROS, which is notable for its high customizability. It features an integrated navigation stack and a data logging system specifically designed to evaluate path planning strategies. The navigation stack acts as a comprehensive pipeline, including localization and global and local planners tailored for ASV maneuvering tasks.
• A simulation environment utilizing the OGRE graphical engine and ODE physics engine, which incorporates environmental effects to realistically simulate real-world conditions. The framework also outlines the process of creating 3D testing sites from 2D map images, which allows for the evaluation of navigation algorithms across various environmental topologies.
• A detailed 6-DOF ASV model of a dual-thruster trimaran is designed and integrated into the simulation. This model is enhanced with various customizable simulated sensors to further support the evaluation of navigation algorithms.
The remainder of the paper is organized as follows: Section 2 presents the system architecture of the ASV model selected for this research. Section 3 outlines the navigation module to be implemented in the simulation framework, which is detailed in Section 4. Section 5 describes the simulation results and provides further analysis. Section 6 concludes the paper and suggests directions for future works.
2 System architecture
The system modeled in this study is a customized lightweight ASV with dimensions of 150 cm×100 cm×50 cm. This system is suitable for small-scale autonomous inspection applications, as shown in Figure 1.
The system supports three operation modes: (ⅰ) Manual Mode, where the vessel is directly operated by the user; (ⅱ) Autonomous Navigation, in which the user designates target poses on a map, and the ASV autonomously navigates to these targets; and (ⅲ) Hold Position/Pose, which enables the ASV to stay in its current position/pose, which resists external disturbances such as wind and currents.
For communication, the user operates the ASV through a ground station computer, which wirelessly exchanges data with the System on Chip (SoC) transceiver on the ASV using Wi-Fi or cellular modules, as illustrated in Figure 2. The SoC receives and processes user commands and sensor data. Subsequently, it generates a reference velocity input for the thruster system. Navigation sensors, including GPS, IMU, and LiDAR, continuously feed data to the SoC, which enables real-time tracking of the position and orientation of the ASV, as well as monitoring the surrounding environment. The thruster system then receives velocity commands from the SoC and applies the necessary forces to the vessel.
The software architecture depicted in Figure 3 allows the user to configure the ASV by adjusting parameters such as maximum speed, goal tolerance, operational mode, manual control override, and mission loading. The ASV provides feedback on its current state, such as pose, velocity, power, and miscellaneous status. Internally, the Guidance, Navigation, and Control system executes the commanded missions, with the first two modules focused on monitoring and calculating the optimal path, whereas the Control module manages the thruster system.
Figure 3 Software architecture of the proposed ASV model. From the ground station, users can configure settings, define missions, select operation modes, and control the ASV. On the ASV, the Guidance, Navigation, and Control (GNC) system processes missions/commands from users and constantly generates feedbackThe system is built on the ROS platform, where communication between functional blocks, or ROS nodes, follows publisher–subscriber, service–client, and action–client schemes managed by a ROS master. The underlying protocols include a TCP/IP-based protocol (TCPROS) for node-to-node communication and an HTTP-based protocol XML-Remote Procedure Call (XML-RPC) for master-to-node and node-to-node communication.
3 Path planning pipeline
This section outlines the path planning pipeline, as described in Figure 4. The primary functions of the pipeline include localization, as well as global and local path planners.
3.1 Localization
The navigation sensors in the pipeline in Figure 4 offer a range of options. One or more sensors can be used for localization. By default, the pipeline uses fused information from RTK GPS and IMU to supply data for the localization block. For localization methods, Thrun et al. (1999) presented a sampling-based Monte Carlo localization (MCL) method that generates a population of particles, where each one represents a belief of the system pose and further filtering the particles with sensor readings and input map to find the actual pose of the system. Additional work on adaptive MCL was subsequently introduced by Aini et al. (2016) to further improve the efficiency of MCL by dynamically adjusting the number of particles. The particle size is linearly increased when the system pose is highly uncertain and otherwise decreased. Hening et al. (2017) also explored the Kalman filter (KF) to estimate a single pose of the system and correct it by fusing readings from various sensors. Subsequently, KF variants such as extended KF (EKF) and unscented KF with an emphasis on nonlinearities were introduced (Hening et al., 2017; Ullah et al., 2019) accordingly.
In this work, ASV localization is achieved by fusing data from GPS and IMU sensors with the use of an EKF to linearize readings from real-life systems. The EKF handles linearized functions because nonlinear functions can distort the Gaussian distribution of sensor measurements using a first-order Taylor series expansion. In other words, all readings are assumed to follow a Gaussian distribution, with the mean representing their outputs and the standard deviation representing their error ranges. Finally, two main phases are considered:
• The prediction phase utilizes previous poses and current IMU readings to estimate the current pose of the ASV.
• The update phase comprises GPS readings to correct the result from the prediction phase.
3.2 Global path planner
In Figure 4, the input map and user-defined goals are used to create a global cost map, which is used by the Global Path Planner (GPP) to chart the optimal path. The GPP aims to generate a complete path toward a desired pose using the global cost map and the current pose of the ASV. Traditional methods, such as Dijkstra (Wang et al., 2011; Qing et al., 2017) and A* (Wang et al., 2011; He et al., 2022; Li et al., 2022; Fan et al., 2023) algorithms, employ grid-based geometry and graph search theory to assign costs to each region of the input map and determine the optimal path that minimizes travel costs. Similarly, force-based methods such as the potential field approach (Zhang et al., 2021; Zhou et al., 2022) enforce an artificial force field where each point on the map presents an attractive or repulsive force on the system. In this approach, regions containing the goal pose attract the ASV, while occupied regions repulse it. Temporal characteristics have also been explored (Liu et al., 2017; Tan et al., 2020) to obtain the path with the optimal arrival time by solving the Eikonal equation of wave propagation. Methods such as the fast marching method and its variants, including the fast marching square method (Hinostroza et al., 2018; Hinostroza et al., 2021) and the adaptive adjustable fast marching square (Tan et al., 2023), have been developed for this purpose. Alternatively, adaptive learning heuristic algorithms such as rapidly exploring random trees (RRT), which are based on graph search theory, facilitate the search for a complete path to the goal pose through a randomly distributed tree of potential poses, as discussed in Qureshi and Ayaz (2015). Modified versions, such as improved bidirectional RRT (Dai et al., 2023; Ma et al., 2023; Xin et al., 2023; Ye et al., 2023), nonlinear risk bounded RRT (Renganathan et al., 2023), improved RRT based on path expansion heuristic sampling (Ding et al., 2023), and bi-directional APF-RRT (Fan et al., 2023), further enhance this approach. Moreover, Zhang et al. (2023c) introduced a path planning algorithm based on concept lattice, which is designed to minimize turning costs. Next, Zuo et al. (2023) proposed a three-stage search path utilizing a reduced approximated generalized Voronoi graph. Meta-heuristic approaches have also been developed. One example is combining A* with coevolutionary algorithms (García et al., 2023). Another example is the gray wolf optimizer (GWO) and its hybrid with differential evolution, which simulates the social behavior of gray wolf (Jia et al., 2023; Liu et al., 2023; Yu et al., 2023; Zhang et al., 2023b). The immune plasma algorithm simulates the use of blood donators to treat infected patients in a population (Aslan and Erkin, 2023). The artificial bee colony (ABC) and its fractional-order calculus variant ABC mimic the foraging behaviors of honeybees (Cui et al., 2023). Finally, the hybrid search and rescue optimization algorithm simulates the behavior of rescuers in disaster scenarios (Zhang et al., 2023a).
In this work, Dijkstra and A* are chosen as GPPs to demonstrate the simulation pipeline due to their simplicity and above-average performance. Both algorithms divide the cost map into various regions and generate a path that traverses the regions with the lowest cost. Dijkstra focuses on finding the optimal path, whereas A* introduces a heuristic factor to each explored node to decrease search time, which can result in a sub-optimal path.
3.3 Local path planner
The local path planner (LPP) that is responsible for following the generated global path while avoiding obstacles detected on its own cost map is updated using LiDAR readings in our specific setup. The LLP also issues rotational rate commands to low-level motor driver controllers. In a marine context, Beser and Yildirim (2018), Ni et al. (2021) and Yu et al. (2021) proposed a case-based LLP that identifies different scenarios described in COLREGs and responds accordingly. Similarly, learning-based approaches using deep reinforcement learning were introduced (Shen et al., 2019; Zhao and Roh, 2019; Guo et al., 2020; Chun et al., 2021). Li et al. (2021), Wang et al. (2021), Xu et al. (2022) and Zhou et al. (2022) explored approaches focusing on simple but effective maneuvers to avoid detected obstacles and adhere to different COLREG scenarios. Next, Hinostroza et al. (2021) and Hinostroza et al. (2018) employed line-of-sight, vector field (VF), and proportional-integral-derivative algorithms to track the path generated by the global planner. Notably, Xu et al. (2021) employed a modified VF enhanced with a repelling field function. This approach considers the shape of obstacles and collision risks and uses the velocity obstacle algorithm to effectively avoid unknown obstacles. Force-based approaches, such as elastic bands (EB) and its variant timed EB (Marin-Plaza et al., 2018; Silva et al., 2019), dynamically adjust the global path generated by the GPP to avoid detected obstacles. Therefore, GPPs can work in conjunction with primitive LPPs given sufficient frequency of the planning loop (Peralta et al., 2020).
In this work, the dynamic window approach (Ji et al., 2021) is chosen as the LPP with the following control loop:
• Sample the control space (dx, dy, dθ) of the ASV.
• Perform forward simulations for each sampled velocity from the current state of the ASV.
• Evaluate each trajectory based on criteria such as proximity to the global path and obstacles to discard any trajectories that result in collisions.
• Select the best trajectory and send the corresponding velocity command to the base.
4 Simulation framework
This section details the components and construction of the simulation stack that incorporates the discussed motion planning pipeline.
4.1 Software platform
The simulation stack is powered by the ROS, which provides basic functionalities of resources such as scheduling, monitoring, and handling; it binds all hardware drivers and software components for robotics applications (Quigley et al., 2009). Moreover, the Gazebo simulator, which uses the ODE physics engine, is integrated into the ROS ecosystem. Figure 5 shows the simulation pipeline, where the ASV interacts with the external environment and generates sensor readings in Gazebo, which are then fed to ROS. From these readings, the navigation stack performs localization and obstacle detection to determine the appropriate velocity commands for the ASV model in Gazebo.
4.2 Data collection and assessment
The data collection mechanism is facilitated by the effective communication framework in ROS, which includes three schemes: publisher–subscriber, service–client, and action–client. These communications between ROS nodes are managed by a centralized ROS master node that maintains related information about all nodes.
Information exchange within ROS is facilitated through ROS messages. They are structured data types defined in ".msg" files, which are simple text files where each field specifies the type and name of the data it represents. The types can include standard primitive types (e.g., int32, float64, and string) and time-related types (e.g., time and duration). ROS messages are recorded in ". bag" file format, which is a binary format that stores ROS message data along with metadata, such as timestamps and topic names.
Therefore, users can easily record all relevant data during a path planning simulation for assessment. These data include the vessel model's ground truth pose, ground truth velocity, the calculated pose from localization, wind direction, and insensitivity.
4.3 Environment modeling
The 3D environment in Figure 6 replicates real-life occupied regions based on parameters from the 2D input map. Triangular meshes, which separate boundaries between land and river paths derived from the global cost map, are created using Python's trimesh library and then imported as a 3D model in Gazebo. Additional properties, such as color, transparency, and materials, are associated with the mesh file through the Extensible Markup Language (XML) format.
4.4 ASV modeling
The complete model in Gazebo is originally designed using the computer-aided design program SolidWorks. The model is exported in the simulation description format, which includes physical properties that the Gazebo engine can interpret, such as mass, inertia tensor, materials, color, joints, and links. In addition, sensors like LiDAR, GPS, IMU, and thrusters are incorporated.
The dynamics model of the ASV in simulation, which is embedded as a Gazebo plugin, is given as
$$ \begin{aligned} \boldsymbol{M}_{\mathrm{RB}} \dot{\boldsymbol{v}} & +\boldsymbol{C}_{\mathrm{RB}}(v) \boldsymbol{v}+\boldsymbol{M}_A \dot{\boldsymbol{v}}+\boldsymbol{C}_A\left(v_r\right) v_r+\boldsymbol{D}\left(v_r\right) v_r \\ & +\boldsymbol{G}(\eta)=\tau_{\text {thrust }}+\tau_{\text {wind }}+\tau_{\text {wave }} \end{aligned} $$ (1) where the vector $ \boldsymbol{\eta}=[x, y, z, \varphi, \theta, \psi]^{\mathrm{T}} $ represents the position and orientation. Meanwhile, the vector $ \boldsymbol{v}=[u, v$, $w, p, q, r]^{\mathrm{T}} $ denotes the velocity of the ASV for surge, sway, heave, roll, pitch, and yaw. The resultant velocity vector $\boldsymbol{v}=v_r+v_c$ is the sum of the non-rotational water current velocity vc and the velocity of the ASV relative to the fluid vr. Next, τthurst, τwind, and τwave are the thrust, wave, and wind force, respectively. The rigid body forces are determined by the mass matrix MRB and its Coriolis-centripetal matrix CRB(v). The effects of hydrodynamic force are accounted for by the added mass matrix MA, the Coriolis-centripetal matrix for the added mass CA(vr) and the hydrodynamic damping matrix D(vr). Finally, G(η) is the hydrostatic force generated from the presence of ocean waves.
The hydrodynamic terms are expressed as
$$ \boldsymbol{M}_A=\left[\begin{array}{cccccc} X_{\dot{u}} & 0 & 0 & 0 & 0 & 0 \\ 0 & Y_{\dot{v}} & 0 & 0 & 0 & Y_{\dot{r}} \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & N_{\dot{v}} & 0 & 0 & 0 & N_{\dot{r}} \end{array}\right] $$ (2) $$ \boldsymbol{C}_A\left(v_r\right)=\left[\begin{array}{cccccc} 0 & 0 & 0 & 0 & 0 & Y_{\dot{r}} v_r+Y_{\dot{r}} r \\ 0 & 0 & 0 & 0 & 0 & -X_{\dot{u}} u_r \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & -Y_{\dot{v}} v_r-Y_{\dot{r}} r & X_{\dot{u}} u_r & 0 \end{array}\right] $$ (3) $$ \boldsymbol{D}\left(v_r\right)=\boldsymbol{D}_l+\boldsymbol{D}_n\left(v_r\right) $$ (4) $$ \boldsymbol{D}_l=-\left[\begin{array}{cccccc} X_u & 0 & 0 & 0 & 0 & 0 \\ 0 & Y_v & 0 & 0 & 0 & Y_r \\ 0 & 0 & Z_w & 0 & 0 & 0 \\ 0 & 0 & 0 & K_p & 0 & 0 \\ 0 & 0 & 0 & 0 & M_q & 0 \\ 0 & N_v & 0 & 0 & 0 & N_r \end{array}\right] $$ (5) $$ \boldsymbol{D}_n\left(v_r\right)=-\left[\begin{array}{cccccc} X_{u|u|}\left|u_r\right| & 0 & 0 & 0 & 0 & 0 \\ 0 & Y_{v|v|}\left|v_r\right|+Y_{|r| v}|r| & 0 & 0 & 0 & Y_{|v| r}\left|v_r\right|+Y_{|r| r}|r| \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & N_{|v| v}\left|v_r\right|+N_{|r| r}|r| & 0 & 0 & 0 & N_{|v| r}\left|v_r\right|+N_{r \mid r}|r| \end{array}\right] $$ (6) The effect of τwave is simulated by the Pierson–Moskow-itz wave spectrum sampling model (Fréchot, 2006), and τwind is simulated using the wind model provided by Fossen (Vagale et al., 2021).
5 Simulation results and discussion
5.1 Software platform
The simulation is conducted on a PC with an Intel i7-9700 3.00 GHz processor, an NVIDIA GeForce RTX 2070 SUPER graphics card, and 32 GB of RAM. The operating system is Ubuntu 18.04, with ROS Melodic and Gazebo 9.14 installed.
For the user input map in the path planning process, the input aerial image used to compute the global cost map is pre-processed by converting it to grayscale for distinguishing among occupied, free, and unknown zones. The input image, which is sourced from Google Maps, is treated as a colored 2D map that includes surrounding terrains. The blue zones in the input image, which represent water, are transformed into the cost map as free zones (indicated by white color), while the remaining areas are considered occupied zones (indicated by black color). This transformation is achieved using the thresholding technique from the Image Processing Toolbox add-on in MATLAB. The resulting grayscale image has values ranging from 0 to 255, where black is 0 and white is 255, with gradients adjusted according to specific shades of blue that indicate different sea and river areas. These zones are then converted to grayscale values corresponding to occupied (0 – 20), unknown (21–234), and free zones (235–255) to reflect the actual occupancy cost.
In these simulation experiments, a global path is planned first. Then, five different speed levels (i. e., 0.3, 0.6, 0.9, 1.2, and 1.8 m/s) are applied, measured, and compared with estimations based only on the global path. The comparison includes visualization, path deviation between the global path and the actual motion path, and the time difference between the estimated execution and actual execution times.
Next, the experimental zone measures 464 m×433 m and is located at 10°42'56.2''N, 106°40'27.3''E. The planned paths of the ASV using Dijkstra and A* as GPPs are shown in Figure 8, where X denotes the starting point and O denotes the goal. The total path length generated by Dijkstra is 1 123.73 m, with a planning time of 31.45 s. The total path length generated by A* is 1 175.01 m, with a planning time of 13.76 s. The comparisons of planned path by Dijkstra and A* with actual motion paths at different maximum velocities are shown in Table 1 and 2, where Figure 9 highlights the differences in total execution time. Finally, Figures 10 and 11 visualize the generated path at each maximum velocity.
Table 1 Measurement results with Dijkstra as the GPPMaximum speed (m/s) Global path length by dijkstra (m) Path deviation (%) Estimated motion time (s) Actual motion time (s) Time difference (%) 0.3 0.77 3746 3441 8.14 0.6 0.81 1873 1299 30.65 0.9 1123.73 0.85 1249 707 43.39 1.2 0.87 936 623 33.44 1.8 0.91 624 592 5.12 Table 2 Measurement results with A* as the GPPMaximum speed (m/s) Global path length by A* (m) Path deviation (%) Estimated motion time (s) Actual motion time (s) Time difference (%) 0.3 4.21 3917 2658 32.14 0.6 4.79 1958 1191 39.17 0.9 1175.01 4.53 1306 707 45.87 1.2 5.12 979 715 26.97 1.8 5.31 653 732 12.10 5.2 Simulation results
All velocity profiles are highly deviated from the global path at each sharp turn. Moreover, higher velocities tend to deviate more due to the inertia of the vessel. Given that A* involves more turns than Dijkstra, the deviations are larger and more complex. Notable differences between the estimated and actual motion times are observed.
As shown in Figure 8, although the path generated by Dijkstra is longer, it can result in shorter execution times in some cases due to its smoother path. In addition, the total execution time decreases as the maximum speed increases.
5.3 Results and discussions
First, as shown in Table 2 and Figure 9, a significant deviation from the global path is observed when using A* as the GPP, which averages around 4.79%. The reason is that the saw-like segments in the generated path that follow the occupancy grid on the cost map cause the ASV to swing and result in unstable motions. Furthermore, substantial time differences are found between the estimated and actual motion times, which average nearly 31.25%. By contrast, using Dijkstra as the GPP results in an average time difference of 24.15%, as indicated in Table 1. Figure 10 illustrates that the motion paths generated by Dijkstra also exhibit certain deviations from the static path generated by the global planner, especially at sharp turns. Next, the relationship between actual motion time and nominal speed is nonlinear, as assumed by the estimated motion time (Tables 1 and 2). Finally, although Dijkstra generates a longer path than A*, its total execution time is faster at speeds of 1.2 and 1.8 m/s, with reductions of 92 and 140 s due to its smoother trajectory. Various factors contribute to these differences in path planner performance, including the limitations of the thruster model, the inertia of the ASV model combined with sharp turns, variations in sensor models, and external forces at a given time. Such results can only be accurately observed and analyzed with a simulation pipeline that incorporates real-life variables into the path planner.
6 Conclusions
This paper presents a comprehensive simulation pipeline that incorporates the navigation stack of an ASV. The pipeline covers the entire process, which ranges from user input commands to the generation of velocity streams. It integrates localization, as well as global and local path planners. Furthermore, the methodology for constructing a 3D simulation using Gazebo, which is chosen due to its open-source nature and ROS integration, is discussed. This environment includes fundamental physical effects, a 3D representation of the testing site, and an ASV model that dynamically responds to various environmental factors, such as thruster performance, wind, waves, hydrodynamics, and rigid-body forces. The resulting pipeline provides a comprehensive environment to access the performance of any path planner in real time. The experiment results demonstrate that common metrics used in most research are insufficient to justify such performance. Notably, the analysis shows that using only the path length generated by the global planner is inadequate. The reason is that a longer but smoother path can result in shorter execution times. The inclusion of ASV's inertia, thruster model limitations, sensor variances for localization, and external disturbances in the simulation leads to substantially different motion paths and execution times compared with individual assessments in the aforementioned works.
For future works, unknown static and dynamic obstacles usually encountered in maritime traffic will be added to the Gazebo library, especially those specific to the modeled location. Corresponding wind and wave conditions need to be measured and adjusted to accurately represent the environment. Finally, a real ASV model is developed, and its experimental data will be compared with the generated data of the proposed simulation framework.
Competing interestThe authors have no competing interests to declare that are relevant to the content of this article. -
Figure 3 Software architecture of the proposed ASV model. From the ground station, users can configure settings, define missions, select operation modes, and control the ASV. On the ASV, the Guidance, Navigation, and Control (GNC) system processes missions/commands from users and constantly generates feedback
Table 1 Measurement results with Dijkstra as the GPP
Maximum speed (m/s) Global path length by dijkstra (m) Path deviation (%) Estimated motion time (s) Actual motion time (s) Time difference (%) 0.3 0.77 3746 3441 8.14 0.6 0.81 1873 1299 30.65 0.9 1123.73 0.85 1249 707 43.39 1.2 0.87 936 623 33.44 1.8 0.91 624 592 5.12 Table 2 Measurement results with A* as the GPP
Maximum speed (m/s) Global path length by A* (m) Path deviation (%) Estimated motion time (s) Actual motion time (s) Time difference (%) 0.3 4.21 3917 2658 32.14 0.6 4.79 1958 1191 39.17 0.9 1175.01 4.53 1306 707 45.87 1.2 5.12 979 715 26.97 1.8 5.31 653 732 12.10 -
Ahmed MA, Aloufi J (2022) A smart memory controller for system on chip-based devices. Journal of Nanomaterials. DOI: 10.1155/2022/4944335 Aini FRQ, Jati AN, Sunarya U (2016) A study of monte carlo localization on robot operating system. 2016 International Conference on Information Technology Systems and Innovation (ICITSI), IEEE. DOI: 10.1109/ICITSI.2016.7858235 Aslan S, Erkin T (2023) A multi-population immune plasma algorithm for path planning of unmanned combat aerial vehicle. Advanced Engineering Informatics 55: 101829. DOI: 10.1016/j.aei.2022.101829 Beser F, Yildirim T (2018) COLREGS based path planning and bearing only obstacle avoidance for autonomous unmanned surface vehicles. Procedia Computer Science 131: 633–640. DOI: 10.1016/j.procs.2018.04.306 Chun DH, Roh MI, Lee HW, Ha J, Yu D (2021) Deep reinforcement learning-based collision avoidance for an autonomous ship. Ocean Engineering 234: 109216. DOI: 10.1016/j.oceaneng.2021.109216 Cui Y, Hu W, Rahmani A (2023) Fractional-order artificial bee colony algorithm with application in robot path planning. European Journal of Operational Research 306(1): 47–64. DOI: 10.1016/j.ejor.2022.11.007 Dai J, Zhang Y, Deng H (2023) Novel potential guided bidirectional rrt* with direct connection strategy for path planning of redundant robot manipulators in joint space. IEEE Transactions on Industrial Electronics 71(3): 2737–2747. DOI: 10.1109/TIE.2023.3269462 Ding J, Zhou Y, Huang X, Song K, Lu S, Wang L (2023) An improved RRT* algorithm for robot path planning based on path expansion heuristic sampling. Journal of Computational Science 67: 101937. DOI: 10.1016/j.jocs.2022.101937 Fan J, Chen X, Liang X (2023) UAV trajectory planning based on bi-directional APF-RRT* algorithm with goal-biased. Expert Systems with Applications 213: 119137. DOI: 10.1016/j.eswa.2022.119137 Fréchot J (2006) Realistic simulation of ocean surface using wave spectra. Proceedings of the First International Conference on Computer Graphics Theory and Applications (GRAPP 2006) García E, Villar J R, Tan Q, Sedano J, Chira C (2023) An efficient multi-robot path planning solution using A* and coevolutionary algorithms. Integrated Computer-Aided Engineering 30(1): 41–52. DOI: 10.3233/ICA-220695 Garg S, Quintas J, Cruz J, Pascoal AM (2020) NetMarSyS-A tool for the simulation and visualization of distributed autonomous marine robotic systems. 2020 IEEE/OES Autonomous Underwater Vehicles Symposium (AUV), IEEE. DOI: 10.1109/AUV50043.2020.9267922 Griffiths NA, Levi PS, Riggs JS, DeRolph CR, Fortner AM, Richards JK (2022) Sensor-equipped unmanned surface vehicle for high-resolution mapping of water quality in low-to mid-order streams. ACS ES & T Water 2(3): 425–435. DOI: 10.1021/acsestwater.1c00342 Gu S, Zhou C, Wen Y, Zhong X, Zhu M, Xiao C, Du Z (2020) A motion planning method for unmanned surface vehicle in restricted waters. Proceedings of the Institution of Mechanical Engineers, Part M: Journal of Engineering for the Maritime Environment 234(2): 332–345. DOI: 10.1177/1475090219898566 Guo S, Zhang X, Zheng Y, Du Y (2020) An autonomous path planning model for unmanned ships based on deep reinforcement learning. Sensors 20(2): 426. DOI: 10.3390/s20020426 He Z, Liu C, Chu X, Negenborn RR, Wu Q (2022) Dynamic anticollision a star algorithm for multi-ship encounter situations. Applied Ocean Research 118: 102995. DOI: 10.1016/j.apor.2021.102995 Heins PH, Jones BL, Taunton DJ (2017) Design and validation of an unmanned surface vehicle simulation model. Applied Mathematical Modelling 48: 749–774. DOI: 10.1016/j.apm.2017.02.028 Hening S, Ippolito CA, Krishnakumar KS, Stepanyan V, Teodorescu M (2017) 3D LiDAR SLAM integration with GPS/INS for UAVs in urban GPS-degraded environments. AIAA Information Systems-AIAA Infotech@Aerospace: 0448. DOI: 10.2514/6.2017-0448 Hinostroza M, Xu H, Guedes Soares C (2018) Path-planning and path following control system for autonomous surface vessel. Taylor & Francis Group London, UK: 991–998. DOI: 10.1115/OMAE2018-78537 Hinostroza M, Xu H, Guedes Soares C (2021) Experimental results of the cooperative operation of autonomous surface vehicles navigating in complex marine environment. Ocean Engineering 219: 108256. DOI: 10.1016/j.oceaneng.2020.108256 Ji X, Feng S, Han Q, Yin H, Yu S (2021) Improvement and fusion of A* algorithm and dynamic window approach considering complex environmental information. Arabian Journal for Science and Engineering 46: 7445–7459. DOI: 10.1007/s13369-021-05445-6 Jia Y, Qu L, Li X (2023) Automatic path planning of unmanned combat aerial vehicle based on double-layer coding method with enhanced grey wolf optimizer. Artificial Intelligence Review 56(10): 12257–12314. DOI: 10.1007/s10462-023-10481-9 Kang CM, Yeh LC, Jie SYR, Pei TJ, Nugroho H (2020) Design of USV for search and rescue in shallow water. Intelligent Robotics and Applications: 13th International Conference, ICIRA 2020, Kuala Lumpur, Malaysia, Proceedings 13, Springer. DOI: 10.1007/978-3-030-66645-3_30 Li L, Wu D, Huang Y, Yuan ZM (2021) A path planning strategy unified with a COLREGS collision avoidance function based on deep reinforcement learning and artificial potential field. Applied Ocean Research 113: 102759. DOI: 10.1016/j.apor.2021.102759 Li Z, Yao C, Zhu X, Gao G, Hu S (2022) A decision support model for ship navigation in Arctic waters based on dynamic risk assessment. Ocean Engineering 244: 110427. DOI: 10.1016/j.oceaneng.2021.110427 Liu X, Li G, Yang H, Zhang N, Wang L, Shao P (2023) Agricultural UAV trajectory planning by incorporating multi-mechanism improved grey wolf optimization algorithm. Expert Systems with Applications 233: 120946. DOI: 10.1016/j.eswa.2023.120946 Liu Y, Bucknall R, Zhang X (2017) The fast marching method based intelligent navigation of an unmanned surface vehicle. Ocean Engineering 142: 363–376. DOI: 10.1016/j.oceaneng.2017.07.021 Lončar I, Obradović J, Kraševac N, Mandić L, Kvasić I, Ferreira F, Slošić V, Nađ Đ, Mišković N (2022) MARUS-a marine robotics simulator. OCEANS IEEE. DOI: OCEANS47191.2022.9976969. Luis SY, Peralta F, Córdoba AT, del NozalÁ RS, Marín T, Reina DG (2022) An evolutionary multi-objective path planning of a fleet of ASVs for patrolling water resources. Engineering Applications of Artificial Intelligence 112: 104852. DOI: 10.1016/j.engappai.2022.104852 Lyridis DV (2021) An improved ant colony optimization algorithm for unmanned surface vehicle local path planning with multimodality constraints. Ocean Engineering 241: 109890. DOI: 10.1016/j.oceaneng.2021.109890 Ma G, Duan Y, Li M, Xie Z, Zhu J (2023) A probability smoothing Bi-RRT path planning algorithm for indoor robot. Future Generation Computer Systems 143: 349–360. DOI: 10.1016/j.future.2023.02.004 Marin-Plaza P, Hussein A, Martin D, Escalera A (2018) Global and local path planning study in a ROS-based research platform for autonomous vehicles. Journal of Advanced Transportation 2018: 1–10. DOI: 10.1155/2018/6392697 Mendonça R, Santana P, Marques F, Lourenço A, Silva J, Barata J (2013) Kelpie: A ROS-based multi-robot simulator for water surface and aerial vehicles. 2013 IEEE International Conference on Systems, Man, and Cybernetics (SMC). DOI: 10.1109/SMC.2013.621 Naeem W, Henrique SC, Hu L (2016) A reactive COLREGs-compliant navigation strategy for autonomous maritime navigation. IFAC-PapersOnLine 49(23): 207–213. DOI: 10.1016/j.ifacol.2016.10.344 Ni S, Liu Z, Huang D, Cai Y, Wang X, Gao S (2021) An application-orientated anti-collision path planning algorithm for unmanned surface vehicles. Ocean Engineering 235: 109298. DOI: 10.1016/j.oceaneng.2021.109298 Peralta F, Arzamendia M, Gregor D, Reina DG, Toral S (2020) A comparison of local path planning techniques of autonomous surface vehicles for monitoring applications: The ypacarai lake case-study. Sensors 20(5): 1488. DOI: 10.3390/s20051488 Pinto AF, Cruz NA, Ferreira BM, Abreu NM, Gonçalves CF, Villa MP, Matos AC, de Mello Honório L, Westin LG (2022) An autonomous system for collecting water samples from the surface. OCEANS 2022-Chennai, IEEE. DOI: 10.1109/OCEANSChennai45887.2022.9775519 Qing G, Zheng Z, Yue X (2017) Path-planning of automated guided vehicle based on improved Dijkstra algorithm. 2017 29th Chinese control and decision conference (CCDC), IEEE. DOI: 10.1109/CCDC.2017.7978471 Quigley M, Conley K, Gerkey B, Faust J, Foote T, Leibs J, Wheeler R, Ng AY (2009) ROS: an open-source robot operating system. ICRA Workshop on Open Source Software, Kobe, Japan Qureshi AH, Ayaz Y (2015) Intelligent bidirectional rapidly-exploring random trees for optimal motion planning in complex cluttered environments. Robotics and Autonomous Systems 68: 1–11. DOI: 10.1016/j.robot.2015.02.007 Renganathan V, Safaoui S, Kothari A, Gravell B, Shames I, Summers T (2023) Risk bounded nonlinear robot motion planning with integrated perception & control. Artificial Intelligence 314: 103812. DOI: 10.1016/j.artint.2022.103812 SaiTeja G, Pramod S (2021) Design and simulation of an autonomous surface vehicle for trash collection using ROS. 2021 IEEE 9th Region 10 Humanitarian Technology Conference (R10-HTC), IEEE. DOI: 10.1109/R10-HTC53172.2021.9641589 Shen H, Hashimoto H, Matsuda A, Taniguchi Y, Terada D, Guo C (2019) Automatic collision avoidance of multiple ships based on deep Q-learning. Applied Ocean Research 86: 268–288. DOI: 10.1016/j.apor.2019.02.020 Shi B, Su Y, Wang C, Wan L, Luo Y (2019) Study on intelligent collision avoidance and recovery path planning system for the waterjet-propelled unmanned surface vehicle. Ocean Engineering 182: 489–498. DOI: 10.1016/j.oceaneng.2019.04.076 Silva R, Leite P, Campos D, Pinto AM (2019) Hybrid approach to estimate a collision-free velocity for autonomous surface vehicles. 2019 IEEE International conference on autonomous robot systems and competitions (ICARSC), IEEE. DOI: 10.1109/ICARSC.2019.8733643 Singh Y, Bibuli M, Zereik E, Sharma S, Khan A, Sutton R (2020) A novel double layered hybrid multi-robot framework for guidance and navigation of unmanned surface vehicles in a practical maritime environment. Journal of Marine Science and Engineering 8(9): 624. DOI: 10.3390/jmse8090624 Singh Y, Sharma S, Sutton R, Hatton D, Khan A (2018) A constrained A* approach towards optimal path planning for an unmanned surface vehicle in a maritime environment containing dynamic obstacles and ocean currents. Ocean Engineering 169: 187–201. DOI: 10.1016/j.oceaneng.2018.09.016 Song R, Liu Y, Bucknall R (2019) Smoothed A* algorithm for practical unmanned surface vehicle path planning. Applied Ocean Research 83: 9–20. DOI: 10.1016/j.apor.2018.12.001 Su J, Zhang H, Yao Y (2020) Design of anti-submarine warfare module for unmanned surface vehicle. 2020 3rd International Conference on Unmanned Systems (ICUS), IEEE. DOI: 10.1109/ICUS50048.2020.9274874 Sun X, Wang G, Fan Y, Mu D, Qiu B (2018) An automatic navigation system for unmanned surface vehicles in realistic sea environments. Applied Sciences 8(2): 193. DOI: 10.3390/app8020193 Tan G, Zhuang J, Zou J, Wan L (2023) Adaptive adjustable fast marching square method based path planning for the swarm of heterogeneous unmanned surface vehicles (USVs). Ocean Engineering 268: 113432. DOI: 10.1016/j.oceaneng.2022.113432 Tan G, Zou J, Zhuang J, Wan L, Sun H, Sun Z (2020) Fast marching square method based intelligent navigation of the unmanned surface vehicle swarm in restricted waters. Applied Ocean Research 95: 102018. DOI: 10.1016/j.apor.2019.102018 Thakur A, Gupta SK (2011) Real-time dynamics simulation of unmanned sea surface vehicle for virtual environments. Journal of Computing and Information Science in Engineering 11(3): 031005. DOI: 10.1115/1.3617443 Thrun S, Bennewitz M, Burgard W, Cremers AB, Dellaert F, Fox D, Hahnel D, Rosenberg C, Roy N, Schulte J (1999) MINERVA: A second-generation museum tour-guide robot. Proceedings 1999 IEEE International Conference on Robotics and Automation (Cat. No. 99CH36288C), IEEE. DOI: 10.1109/ROBOT.1999.770401 Tosik T, Maehle E (2014) MARS: A simulation environment for marine robotics. 2014 Oceans-St. John's, IEEE. DOI: 10.1109/OCEANS.2014.7003008 Ullah I, Shen Y, Su X, Esposito C, Choi C (2019) A localization based on unscented Kalman filter and particle filter localization algorithms. IEEE Access 8: 2233–2246. DOI: 10.1109/ACCESS.2019.2961740 Vagale A, Bye RT, Oucheikh R, Osen OL, Fossen TI (2021) Path planning and collision avoidance for autonomous surface vehicles II: a comparative study of algorithms. Journal of Marine Science and Technology 26(4): 1307–1323. DOI: 10.1007/s00773-020-00790-x Wang H, Yu Y, Yuan Q (2011) Application of Dijkstra algorithm in robot path-planning. 2011 Second International Conference on Mechanic Automation and Control Engineering, IEEE. DOI: 10.1109/MACE.2011.5987118 Wang Z, Zhang S, Feng X, Sui Y (2021) Autonomous underwater vehicle path planning based on actor-multi-critic reinforcement learning. Proceedings of the Institution of Mechanical Engineers, Part I: Journal of Systems and Control Engineering 235(10): 1787–1796. DOI: 10.1177/0959651820937085 Wen N, Zhang R, Liu G, Wu J, Qu X (2020) Online planning low-cost paths for unmanned surface vehicles based on the artificial vector field and environmental heuristics. International Journal of Advanced Robotic Systems 17(6): 1729881420969076. DOI: 10.1177/1729881420969076 Xie J, Zhou R, Luo J, Peng Y, Liu Y, Xie S, Pu H (2020) Hybrid partition-based patrolling scheme for maritime area patrol with multiple cooperative unmanned surface vehicles. Journal of Marine Science and Engineering 8(11): 936. DOI: 10.3390/jmse8110936 Xin P, Wang X, Liu X, Wang Y, Zhai Z, Ma X (2023) Improved bidirectional RRT* algorithm for robot path planning. Sensors 23(2): 1041. DOI: 10.3390/s23021041 Xu H, Hinostroza MA, Guedes Soares C (2021) Modified vector field path-following control system for an underactuated autonomous surface ship model in the presence of static obstacles. Journal of Marine Science and Engineering 9(6): 652. DOI: 10.3390/jmse9060652 Xu X, Cai P, Ahmed Z, Yellapu VS, Zhang W (2022) Path planning and dynamic collision avoidance algorithm under COLREGs via deep reinforcement learning. Neurocomputing 468: 181–197. DOI: 10.1016/j.neucom.2021.09.071 Yang JM, Tseng CM, Tseng P (2015) Path planning on satellite images for unmanned surface vehicles. International Journal of Naval Architecture and Ocean Engineering 7(1): 87–99. DOI: 10.1515/ijnaoe-2015-0007 Ye L, Wu F, Zou X, Li J (2023) Path planning for mobile robots in unstructured orchard environments: An improved kinematically constrained bi-directional RRT approach. Computers and Electronics in Agriculture 215: 108453. DOI: 10.1016/j.compag.2023.108453 Yu K, Liang X, Li M, Chen Z, Yao Y, Li X, Zhao ZX, Teng Y (2021) USV path planning method with velocity variation and global optimisation based on AIS service platform. Ocean Engineering 236: 109560. DOI: 10.1016/j.oceaneng.2021.109560 Yu X, Jiang N, Wang X, Li M (2023) A hybrid algorithm based on grey wolf optimizer and differential evolution for UAV path planning. Expert Systems with Applications 215: 119327. DOI: 10.1016/j.eswa.2022.119327 Zhang C, Zhou W, Qin W, Tang W (2023a) A novel UAV path planning approach: Heuristic crossing search and rescue optimization algorithm. Expert Systems with Applications 215: 119243. DOI: 10.1016/j.eswa.2022.119243 Zhang L, Mou J, Chen P, Li M (2021) Path planning for autonomous ships: A hybrid approach based on improved APF and modified vo methods. Journal of Marine Science and Engineering 9(7): 761. DOI: 10.3390/jmse9070761 Zhang Q, Zhao J, Pan L, Wu X, Hou Y, Qi X (2023b) Optimal path planning for mobile robots in complex environments based on the grey wolf algorithm and self-powered sensors. IEEE Sensors Journal. DOI: 10.1109/JSEN.2023.3252635 Zhang Z, Xu X, Yue F, Ba Y (2023c) Robot path planning based on concept lattice. International Journal of Approximate Reasoning 153: 87–103. DOI: 10.1016/j.ijar.2022.11.013 Zhao L, Roh MI (2019) COLREGs-compliant multiship collision avoidance based on deep reinforcement learning. Ocean Engineering 191: 106436. DOI: 10.1016/j.oceaneng.2019.106436 Zhou C, Gu S, Wen Y, Du Z, Xiao C, Huang L, Zhu M (2020a) Motion planning for an unmanned surface vehicle based on topological position maps. Ocean Engineering 198: 106798. DOI: 10.1016/j.oceaneng.2019.106798 Zhou C, Gu S, Wen Y, Du Z, Xiao C, Huang L, Zhu M (2020b) The review unmanned surface vehicle path planning: Based on multi-modality constraint. Ocean Engineering 200: 107043. DOI: 10.1016/j.oceaneng.2020.107043 Zhou C, Wang Y, Wang L, He H (2022) Obstacle avoidance strategy for an autonomous surface vessel based on modified deep deterministic policy gradient. Ocean Engineering 243: 110166. DOI: 10.1016/j.oceaneng.2021.110166 Zuo X, Zhou J, Yang F, Su F, Zhu H, Li L (2023) Real-time global action planning for unmanned ground vehicle exploration in Three-dimensional spaces. Expert Systems with Applications 215: 119264. DOI: 10.1016/j.eswa.2022.119264