1. Introduction
With the rapid development of intelligent manufacturing and automatic control technologies, mobile robots are increasingly being deployed across a wide range of fields, such as smart warehousing [
1], security inspection [
2], medical delivery [
3], and autonomous driving [
4]. Central to the autonomous navigation capabilities of such robots is the task of path planning [
5], which plays a pivotal role in determining their operational efficiency and the likelihood of completing assigned tasks. Global path planning [
6] involves computing an optimal or near-optimal path from a specified starting point to a designated goal location using preexisting knowledge of the environment. In contrast, local path planning [
7] operates in real time, utilizing data acquired from onboard sensors to dynamically update the robot’s trajectory. This approach allows the robot to respond effectively to dynamic obstacles and evolving environmental conditions. Currently, a wide range of path planning algorithms are employed, including Dijkstra [
8,
9], A* [
10], rapidly exploring random tree [
11], particle swarm optimization [
12], genetic algorithm [
13], simulated annealing [
14], ant colony optimization [
15], and artificial potential field [
16].
Among various pathfinding algorithms, A* is commonly used for its effective heuristic search capabilities and high robustness. However, its performance declines on larger maps due to rapid growth in node expansions, resulting in a heavy computational burden and redundant processing. To overcome this limitation, Harabor and Grastien [
17] introduced the jump point search (JPS) algorithm, which retains A*’s heuristic function while enhancing efficiency by eliminating redundant nodes through jump-based pruning. Despite its advantages, JPS remains limited by suboptimal jump point selection and reduced flexibility in environments with dense obstacles, diminishing its effectiveness in dynamic scenarios. To overcome these limitations, Wang et al. [
18] proposed a bidirectional JPS algorithm aimed at minimizing node expansion and turning angles. While this method reduces node count to some extent, it may encounter convergence failures when obstacle-induced separation prevents the forward and backward search frontiers from connecting. To enhance reliability, Lin [
19] introduced a safety-expanded JPS, incorporating an adjustable inflation factor to improve performance in complex and dynamic environments.
The dynamic window approach (DWA) [
20], a velocity–space sampling method for local obstacle avoidance, is widely adopted in mobile robotic platforms, such as ROS, due to its real-time responsiveness, smooth trajectories, and computational efficiency. Despite these strengths, DWA often suffers from local optima in complex environments, and tuning the evaluation function’s weight parameters remains a significant challenge, potentially leading to path deviations or navigation failure. To address these issues, Gao and Li [
21] proposed an improved DWA that dynamically adjusts the evaluation function and incorporates multiple performance metrics to enhance obstacle avoidance in complex scenarios. Nonetheless, the improved DWA still entails substantial computational costs, particularly in large-scale or highly dynamic environments with dense obstacles. Zhu and Chen [
22] introduced a hybrid planning approach that integrates a refined and enhanced A* algorithm with an improved DWA. The modified A* integrates obstacle-aware and adaptive weighting mechanisms to facilitate proactive avoidance in densely obstructed areas, while employing segmented Bézier curves for path smoothing. For local planning, the enhanced DWA leverages global guidance and distance-based heading weights, effectively reducing the risk of local minima and goal deviations from the target path. Chen [
23] incorporated a confidence ellipse—derived from the time-varying distribution of tracking errors—into the DWA evaluation function to assess collision risk more effectively. In addition, the execution accuracy of DWA was enhanced by integrating a kinematic-based Model Predictive Control (MPC).
To enhance the practicality and robustness of path planning in real-world dynamic environments, this study presents a hybrid path planning method that integrates an improved JPS algorithm with the DWA. In the global planning phase, a directional quadrant pruning strategy is employed to minimize redundant node expansions, while a sine-weighted dynamic heuristic function improves search efficiency. The resulting path is smoothed using cubic B-spline curves to ensure smoothness and execution feasibility. In the local planning phase, the DWA algorithm is refined by incorporating an advanced trajectory evaluation function that considers the angle to the goal, safety distance penalties, and normalization, supported by a dynamic adjustment coefficient to better respond to dense, rapidly changing environments. Finally, the proposed method is validated through simulation experiments in both static and dynamic environments, as well as real-world tests on a mobile robot platform, confirming its practical applicability and performance. The main contributions of this work are as follows: (1) In the global planning phase, a quadrant-based pruning strategy guided by the target direction and a sine-enhanced heuristic function is proposed to significantly reduce the search space and improve efficiency, while preserving natural jump points to maintain path continuity. Cubic B-spline smoothing is further applied to generate smooth global paths. (2) In the local planning phase, the DWA is enhanced by introducing a target orientation factor, a safety distance penalty term, a cost function normalization mechanism, and a dynamic weighting strategy, thereby improving adaptability to dynamic obstacles. (3) The proposed hybrid algorithm is comprehensively evaluated in both static and dynamic environments, showing significant improvements in search time, node expansions, and navigation safety compared to baseline methods.
The remainder of this paper is organized as follows:
Section 2 introduces the basic JPS algorithm and its improvement directions;
Section 3 presents the basic DWA algorithm and its improvement directions;
Section 4 describes the hybrid path planning method that integrates the improved JPS with the enhanced DWA;
Section 5 provides the simulation environment setup, results, and analysis; and finally,
Section 6 concludes the paper.
2. Optimization of the JPS Algorithm
In this section, we address the optimization of the Jump Point Search (JPS) algorithm, which serves as the global planning module of the proposed method. While the traditional JPS significantly improves the search efficiency of the A* algorithm by reducing unnecessary node expansions, it still exhibits certain limitations, including redundant exploration in specific regions, limited adaptability in complex environments, and insufficient path smoothness. To overcome these issues, we first review the fundamental principles of the traditional JPS algorithm, and then present our proposed enhancements, which incorporate a directional quadrant pruning strategy, a sine-weighted heuristic function, and cubic B-spline-based path smoothing.
2.1. Traditional JPS Algorithm
In grid-based path planning, the JPS algorithm is a widely adopted enhancement of the A* algorithm. Similarly to A*, the JPS algorithm relies on an estimated cost function to guide node expansion. However, it enhances search efficiency by introducing a “jump point” strategy that significantly reduces node expansions and compresses the overall search space. The conventional cost estimation function used in JPS is defined as follows:
where
x denotes the current node;
f(
x) implies the total estimated cost from the start node to the goal node via node
x;
g(
x) refers to the actual cost from the start node to
x; and
h(
x) signifies the heuristic function that estimates the cost from node
x to the goal. During the search process, the algorithm prioritizes nodes with smaller
f(
x) values, as they are more likely to lead to an optimal path.
Unlike the conventional A* algorithm, JPS streamlines the pathfinding process by selectively expanding only key nodes, referred to as jump points, based on predefined rules. The algorithm greatly improves search efficiency by skipping a large number of nonessential nodes, focusing only on critical waypoints. In grid maps, JPS typically categorizes search directions into two types: straight (horizontal or vertical) and diagonal, enabling more structured and efficient exploration.
In the absence of surrounding obstacles around the current node, as depicted in
Figure 1a,b, consider a scenario where node 4 is the parent node,
x is the current node, and node 6 is an unexpanded neighbor. If the shortest path from node 4 to 6 necessarily passes through node
x, then node 6 is identified as a natural neighbor. In contrast, nodes, such as 1, 2, 3, 7, 8, and 9 (gray nodes), can be accessed independently of
x and are thus deemed nonessential and excluded from expansion. In diagonal searches, nodes 2, 3, and 6 are recognized as natural neighbors, while nodes 1, 4, 8, and 9 are treated as nonessential.
In the presence of obstacles around the current node, as illustrated in
Figure 1c,d, where black squares denote obstacles, consider node 4 as the parent and
x as the current node. If the shortest path from node 4 to node 3 is obstructed, it must be traversed through node
x to identify node 3 as a forced neighbor. During diagonal search, node 1 qualifies as a forced neighbor when direct access from the parent node is blocked by obstacles.
Based on the aforementioned cases, the criteria for determining jump points in the JPS algorithm can be summarized as follows:
If node x is the start or goal node, it is a jump point.
If node x has at least one forced neighbor, it is a jump point.
During diagonal search, if a jump point exists in any of the straight-line directions originating from node x, then x is designated as a jump point.
The traditional JPS algorithm enhances pathfinding efficiency by substantially reducing node expansions. However, it suffers from several limitations. First, on large-scale maps, the preprocessing phase involves exhaustive traversal to determine jump points and directional obstacle data, resulting in considerable computational and memory overhead. Second, the absence of smoothness constraints often results in irregular and jagged paths, which can pose collision risks during robot movement. Furthermore, an inadequately designed heuristic function may lead the algorithm to stray from the optimal path or become trapped in local optima during the search process.
2.2. Improved JPS Algorithm
2.2.1. Heuristic Function Enhancement
To improve search efficiency, path optimality, and adaptability in complex environments, this paper introduces a refined heuristic function that more effectively prioritizes nodes and minimizes redundant node expansions, thereby accelerating the search process. Traditional methods typically adopt the Euclidean distance as the heuristic function:
To address the tendency of heuristic estimates to undervalue actual path costs, a dynamic weight coefficient is introduced. During the initial stages of the search, when the goal remains distant, the heuristic value tends to be much lower than the actual cost. By amplifying the weight coefficient at this stage, the heuristic value is elevated, which expedites node expansion and enhances search efficiency. Conversely, ensuring the optimality of the final path requires the heuristic to closely approximate the true cost. As the search approaches the goal, the weight coefficient is progressively reduced, resulting in a lower heuristic estimate. This deliberate slowdown increases the number of explored nodes, enabling finer path adjustments and more accurate convergence toward the optimal solution.
The modified total cost function is defined as:
where
α implies the distance from the current node to the goal, and
β denotes the fixed distance from the start node to the goal. Both
α and
β are defined as scalar Euclidean distances rather than angular measures. The ratio
α/
β thus represents a normalized scalar input within the valid domain of the sine function. The sine function is selected to introduce a smooth, bounded, and nonlinear modulation of the heuristic weight, enabling a gradual transition from global exploration to local refinement—an effect that is difficult to achieve with conventional linear weighting schemes. In the early stage of the search, the parameter
α is large, while
β remains constant, causing the ratio sin
α/
β to increase the heuristic weight. This configuration promotes broader exploration and accelerates coverage of the search space. As the algorithm proceeds and the current node approaches the goal,
α gradually decreases, leading to a reduction in sin
α/
β. Consequently, the influence of the heuristic diminishes, intentionally decelerating the search to refine the path near the goal. The behavior of
f(
x) under this formulation enables a dynamic balance between global search efficiency and local path optimality, thereby enhancing the overall performance of the pathfinding.
2.2.2. Search Direction Pruning
In the traditional JPS algorithm, all eight neighboring directions are uniformly considered during each node expansion, as shown in
Figure 2a. While the jump point mechanism effectively reduces the search space, the lack of goal-oriented direction selection leads to redundant expansions in irrelevant directions, thereby diminishing the algorithm’s overall efficiency.
To enhance search efficiency, this study proposes a direction pruning strategy based on quadrant judgment. By determining the relative position of the goal node concerning the current node, the algorithm selectively retains only five candidate directions oriented toward the goal for further expansion, while pruning the remaining three directions, deemed irrelevant to the search objective. As shown in
Figure 2b, when the goal lies in the upper-right quadrant relative to the current node, only the directions, such as right, upper-right, up, upper-left, and lower-right, are retained, as they align more closely with the goal’s heading. In contrast, the other three directions, such as left, down, and lower-left, are excluded from expansion due to their divergence from the goal’s heading.
Specifically, the relative direction vector between the current node and the goal node is expressed as Δ
x =
xb −
xa, Δ
y =
yb −
ya. Based on this vector, the goal’s position is classified into one of eight quadrant regions (Q
1–Q
8). Each region is associated with a specific set of recommended directions for node expansion, along with a complementary set of directions to be pruned, as shown in
Table 1.
This strategy significantly reduces redundant directional expansions and alleviates the computational load on the jump point selection module. By preserving path quality, it enhances the overall efficiency and responsiveness of the algorithm.
2.2.3. Path Smoothing Optimization
In grid-based path planning, the JPS algorithm efficiently produces a sequence of jump points; however, the resulting trajectory is typically piecewise linear with frequent turning points and limited smoothness, making precise trajectory tracking challenging for robots. To overcome this limitation, this study proposes the use of cubic B-spline interpolation to convert the discrete jump point path into a smooth curve, thereby improving path continuity and controllability.
Cubic B-splines are commonly employed in robotic path planning and trajectory design due to their ability to produce smooth curves with continuous higher-order derivatives. A B-spline curve is defined by a sequence of control points and their associated basis functions, with the curve generation process determined by a continuous parameter u.
The mathematical formulation of the B-spline curve is expressed as follows:
where
Pi indicates the control point; B
i,k(
u) signifies the
i-th B-spline basis function of order
k;
n denotes the number of control points; and
u refers to the curve parameter within the defined domain.
The zeroth-order (piecewise constant) basis function is defined as follows:
Higher-order basis functions are recursively computed using the following formula:
In the actual smoothing process, the proposed method begins by extracting a sequence of jump points from the initial JPS-generated JPS path. A subset of these jump points is then selected, typically at uniform or fixed intervals, to serve as control points. The associated knot vector is constructed, and the relevant basis functions are computed. Using these components, cubic B-spline interpolation is performed to generate a continuous and smooth trajectory.
The overall smoothing procedure comprises the following steps:
Extract the jump point path and obtain the original control points.
Generate the suitable knot vector and compute the corresponding B-spline basis functions.
Use interpolation to produce the smooth trajectory.
Optionally, conduct the performance optimization on the curve, such as curvature control or path length adjustment.
Compared to the original jump point path, the B-spline-based trajectory offers superior visual smoothness and continuous curvature transitions, eliminating abrupt turns or sudden stops during robot motion. This configuration provides a more feasible and stable reference path for the subsequent DWA algorithm, thereby improving the overall stability and safety of both path planning and execution.
3. Dynamic Window Approach
The DWA is a widely adopted method for local path planning and obstacle avoidance in mobile robots. It integrates the robot’s kinematic constraints with real-time environmental perception to generate feasible velocity commands. At each control cycle, the algorithm assesses a range of candidate trajectories within a defined velocity space, comprising linear and angular velocity pairs, and selects the optimal path based on a multiple criteria evaluation, prioritizing obstacle avoidance, target proximity, and motion efficiency. The DWA algorithm identifies feasible pairs of linear and angular velocities within a defined velocity space. It evaluates the resulting candidate trajectories based on several key metrics, including the safety distance from obstacles, proximity to the target, and overall velocity efficiency. By computing a composite score for each trajectory, the algorithm selects the optimal path that achieves a balanced trade-off between obstacle avoidance and goal-directed movement. By explicitly integrating dynamic constraints and real-time environmental uncertainties, the DWA algorithm proves highly effective for local navigation and obstacle avoidance tasks in dynamic and unpredictable environments.
3.1. Kinematic Model of Mobile Robot
Mobile robots can be categorized into omnidirectional and non-omnidirectional types based on their motion capabilities. Omnidirectional robots can move seamlessly in any direction, forward, sideways, or diagonally, without altering their orientation. This enhances maneuverability; however, it demands complex motion control algorithms and typically results in higher structural costs. In contrast, non-omnidirectional robots are limited to linear movement along their current orientation, requiring body rotation to alter direction. Directional changes in non-omnidirectional robots are realized by rotating the robot’s body. Although their motion is limited, these robots provide notable benefits, including ease of implementation, stable control, and lower cost. Consequently, they are commonly employed in indoor navigation, path planning simulations, and various industrial applications. The robot utilized in this study is a four-wheeled, non-omnidirectional platform based on a differential-drive mechanism. Its movement is primarily governed by adjusting the relative velocities of the left and right wheels, allowing it to move forward, backward, or turn. The corresponding kinematic model is illustrated in
Figure 3.
Let
vl and
vr represent the velocities of the left and right wheels, respectively. The robot’s linear velocity
v and angular velocity
ω can be expressed as follows:
where
L denotes the distance between the centers of the two wheels (wheelbase).
The turning radius
Rc of the robot during a curved motion is given by:
As indicated by the equation, the turning radius is inversely proportional to the difference in wheel speeds. When vl = vr, the turning radius approaches infinity, and the robot moves in a straight line.
Based on the robot’s kinematic model, its current pose is defined by the position [
X,
Y] and orientation
θ. Over a discrete time interval Δ
t, the robot’s position and orientation are updated using the following equations:
3.2. Velocity Sampling for Mobile Robots
In the DWA, velocity sampling plays a pivotal role in local path planning. Taking into account the robot’s current state, dynamic limitations, and the distribution of environmental obstacles, the algorithm generates a set of feasible velocity pairs and predicts their resulting trajectories. The optimal control command is then selected from these candidates. This process is framed within a dynamic window, which represents a velocity space constrained by the robot’s kinematic and dynamic limits. It defines the admissible ranges of linear and angular velocities, acceleration, angular acceleration, and braking distance. The specific computation of the velocity window typically involves the following components:
- 1.
Velocity constraint range based on system settings:
The allowable range of minimum and maximum linear and angular velocities is defined according to the robot’s design specifications and control limits:
where
vmin and
vmax signify the minimum and maximum allowable linear velocities, respectively, and
ωmin and
ωmax indicate the minimum and maximum allowable angular velocities, respectively.
- 2.
Velocity range over the prediction time interval:
Considering the robot’s acceleration capabilities over the prediction time Δ
t, the reachable velocity range is given by:
where
v and
ω denote the current linear and angular velocities, respectively,
a refers to the linear acceleration, and
α signifies the angular acceleration.
- 3.
Braking distance constraint:
To ensure the robot maintains a safe distance from nearby obstacles during emergency braking, a safe velocity range is expressed as:
where dist(
v,
ω) refers to the distance from the robot to the nearest obstacle along the predicted trajectory.
Therefore, the final set of valid velocities is obtained by computing the intersection of the three previously defined constraints:
3.3. Evaluation Function and Optimization for Mobile Robots
In the DWA, the design of the evaluation function plays a critical role in determining the optimal path selection, as it directly affects trajectory smoothness, safety, and goal orientation. The traditional DWA algorithm assesses each candidate trajectory using a weighted sum of three key metrics, expressed as:
where heading(
v,
ω) quantifies the angular deviation between the trajectory endpoint and the target point, encouraging goal-directed movement; distance(
v,
ω) measures the proximity to the closest obstacle, promoting safe navigation; velocity(
v,
ω) represents the linear velocity of the sampled trajectory, favoring efficient and rapid movement toward the goal; and
α,
β, and
γ denote the weighting coefficients for each term.
While the function performs reliably under standard environments, it may face challenges in complex or narrow spaces. Specifically, it offers limited safety margins when operating near obstacle proximity; at the same time, it is susceptible to generating oscillatory paths as trajectories approach obstacles and cannot dynamically balance the speed and obstacle avoidance in response to changing environmental conditions.
To address these limitations, this study introduces an improved evaluation function designed to improve adaptability and safety, defined as follows:
The improvements are incorporated through the following three aspects:
ε·penalty: This term introduces a penalty quantified as 1.2 times the distance between the robot and nearby obstacles. By amplifying the cost near obstacle boundaries, it promotes safer planning, particularly in narrow environments.
λ: This adaptive weight coefficient dynamically adjusts in response to the spatial distribution of nearby obstacles. When the closest obstacle lies well beyond the predefined safety threshold, the weight of the velocity term is increased, enabling the robot to adopt a more assertive motion strategy.
σ: This denotes a normalization function that standardizes the evaluation terms to maintain uniform scaling across different metrics, thereby enhancing trajectory smoothness and overall stable trajectories.
4. Integrated Planning Algorithm
Although the JPS algorithm is effective for global path planning, it exhibits certain limitations in dynamic environments, particularly when maneuvering around complex obstacles, where it may become trapped in local optima. To overcome this issue, this study introduces a hybrid path planning approach that integrates the strengths of both the JPS and DWA algorithms, leveraging their respective advantages in global navigation and local obstacle avoidance.
The proposed approach initially utilizes the JPS algorithm to rapidly generate key nodes along the global path. These jump points serve as intermediate targets for the DWA algorithm, which performs local trajectory optimization and dynamic obstacle avoidance in a segmented manner. During each local planning cycle, the algorithm restricts its focus to the area between the robot’s current position and the next jump point. Within this region, it applies velocity sampling and the evaluation function to perform short-term prediction and control. This localized strategy facilitates real-time obstacle avoidance while ensuring steady advancement toward the final goal.
Based on the above approach, this study presents the pseudocode of the enhanced JPS–DWA algorithm, as shown in Algorithm 1, which concisely captures the key operational logic of the overall path planning strategy. In addition,
Figure 4 visually demonstrates the planning process of the hybrid algorithm.
Algorithm 1 Integrated Improved JPS and DWA Algorithm |
1: Input: Map |
|
Cost function |
Path smoothing method: B-spline DWA parameters: , , |
2: Output: Final optimal path: |
3: #Step 1: Global Path Planning (Improved JPS) |
4: Compute jump-based path: |
5: if then |
6: return Failure |
7: else |
8: Perform B-spline smoothing: − |
9: Extract key waypoint set: |
10: # Step 2: Local Path Planning (DWA) |
11: Initialize current position: index: |
12: while do: |
13: Set sub-goal |
14: while do: |
15: Sample velocity space: |
16: Predict trajectories: |
17: Evaluate trajectories: |
18: Select optimal velocity: |
19: Move to new position: |
20: If a collision occurs or the trajectory deviates from the path: |
Jump back to Step 1 and replan using JPS |
21: end while |
22: |
23: end while |
5. Experimental Validation
To verify the effectiveness and resilience of the proposed hybrid path planning approach, simulations were run in 2D grid map environments. The method combines an improved JPS algorithm with the DWA algorithm. Tests were performed in both static and dynamic scenarios. The main focus was on path search efficiency, trajectory smoothness, obstacle avoidance capability, and how well the method works in complex environments. Different map layouts and obstacle configurations were used for comparison. All simulations were performed in MATLAB R2021b on a 64-bit Windows operating system. The test platform was equipped with an Intel Core i5-10210U processor (1.60 GHz base, 2.11 GHz max) and 12 GB of RAM.
5.1. Simulation Analysis of the Improved JPS Algorithm in Static Environments
Figure 5,
Figure 6 and
Figure 7 display the simulation results of four path planning algorithms: the original JPS algorithm, the method proposed in Wang et al. [
18], the improved JPS algorithm proposed in this study, and the B-spline smoothing method. These algorithms were tested on three static map environments: a 30 × 30 simple map, a 50 × 50 standard map, and a complex map. In the simulation maps, green cells indicate the start point, blue cells denote the goal point, black cells imply the static obstacles, and yellow cells indicate the nodes expanded during the search process. The paths generated by the jump point algorithm are illustrated using purple and red polylines, and the final smooth trajectory, derived through cubic B-spline interpolation, is depicted as the blue curve. Each scenario was executed ten times independently to ensure result consistency, and average values were used for comparative analysis.
In the 30 × 30 simple map environment, the original JPS algorithm, the method proposed in Wang et al. [
18], and the improved JPS algorithm generate similar jump point paths and complete the search efficiently with near-optimal results. However, the method proposed in Wang et al. [
18] demonstrates a slightly more conservative node expansion strategy, leading to relatively longer path lengths and higher search times. In contrast, the improved JPS algorithm employs quadrant-based direction pruning guided by the target direction, which minimizes the redundant expansions. Coupled with the dynamic sine-weighted heuristic function, this algorithm enhances search efficiency, significantly reducing both node expansion and search time while preserving path quality.
In the 50 × 50 standard and complex map environments, the performance differences between the algorithms become more evident. The original JPS algorithm tends to perform redundant node expansions in densely obstructed regions, leading to an increased search time and reduced path quality. Although the method proposed in Wang et al. [
18] offers partial improvements, it still exhibits significant expansion overhead. In contrast, the improved JPS algorithm consistently achieves more efficient search behavior across all three map types, characterized by reduced node expansions, shorter search times, and overall shorter path lengths.
After applying cubic B-spline interpolation, the discrete jump point paths from all algorithms are transformed into continuous trajectories. These blue trajectories effectively avoid obstacles while maintaining high feasibility, making them suitable for practical mobile robot path tracking and control applications.
Table 2 presents a comparative analysis of the average performance of the original JPS algorithm, the algorithm proposed in Wang et al. [
18], and the improved JPS algorithm across three different map environments. The evaluation focuses on key metrics, such as path length, the number of expanded nodes, and search time. In the 30 × 30 simple map, the improved JPS algorithm significantly enhances efficiency, reducing the search time from 0.42 s to 0.26 s, representing a 38.1% decrease. The number of expanded nodes drops from 12 to 8, registering a reduction of 33.3%.
In the 50 × 50 standard map, the improved JPS algorithm shortens the search time from 0.84 s to 0.53 s, showing a 36.9% improvement. It also significantly reduces the number of expanded nodes from 78 to 19, achieving a 75.6% reduction. In the more complex 50 × 50 map, it continues to perform well, cutting the search time from 0.88 s to 0.57 s and reducing the number of expanded nodes from 57 to 15, with an optimization rate of 73.7%.
Cubic B-spline interpolation effectively enhances the continuity and feasibility of the path while causing minimal impact on the overall path length. In all three scenarios, the increase in path length remained below 2%, indicating that the smoothing process significantly improves trajectory quality without incurring substantial computational or spatial cost. The algorithm proposed in Wang et al. [
18] maintains moderate search efficiency; it does not consistently yield shorter paths. In contrast, the improved JPS algorithm demonstrates superior adaptability in balancing path quality and search efficiency, making it well suited for large-scale or structurally complex environments.
5.2. Simulation Analysis of the Integrated Algorithm in Dynamic Environments
To evaluate the adaptability of the proposed hybrid algorithm in dynamic environments, this section introduces multiple sets of unknown and dynamic obstacles into the previously static maps to simulate the process of path planning and obstacle avoidance in complex scenarios. The improved JPS algorithm is initially used to generate a sequence of jump points, which are refined through cubic B-spline interpolation. Subsequently, the DWA is employed for local obstacle avoidance and real-time trajectory adjustment.
Figure 8 and
Figure 9 illustrate an environment where gray cells indicate unknown obstacles and red cells signify dynamic ones. The scenario includes two sets of horizontally and two sets of vertically moving dynamic obstacles. As the robot navigates, it continuously adapts its speed and direction in real time based on perceived environmental feedback, resulting in the actual trajectory marked by the green curve.
To further assess the algorithm’s real-time performance, we conducted 10 simulation runs in both standard and complex environments. In the standard environment, the smoothed path comprises approximately 160 trajectory points with a total path length of about 73.1 m. Given that each control step corresponds to a single point tracking operation, the system executes around 160 steps in total, averaging 350 s per run, which yields an average time of approximately 2.19 s per step. In contrast, the complex environment contains about 137 trajectory points over a path length of roughly 64.6 m, with an average runtime of 420 s per run, resulting in an average step time of approximately 3.07 s.
Figure 10 illustrates the robot’s velocity responses, with the blue curve indicating the variation in linear velocity and the red curve representing the angular velocity. When the dynamic obstacle moves from (18, 40) to (10, 40), the robot proactively reduces its linear velocity from V
1 = 0.27 m/s to V
2 = 0.16 m/s at approximately t = 48 s, maintaining a safe clearance distance, thereby significantly decreasing its speed and successfully avoiding a collision. Similarly, in another case where an obstacle moves from (20, 11) to (20, 29), the robot markedly alters its trajectory at approximately t = 123 s, with the peak angular velocity increasing from ω
1 = 0.14 rad/s to ω
2 = 0.20 rad/s to steer clear of the obstacle’s path. In the more complex map environment, as shown in
Figure 9, the integrated algorithm demonstrates strong adaptability by making real-time adjustments to speed and heading based on obstacle movements, effectively avoiding collisions. These outcomes affirm the algorithm’s robustness and general applicability in highly dynamic and uncertain environments.
The integration of the improved JPS algorithm with the DWA enables the robot to navigate around previously unknown dynamic obstacles while following a predefined global path. This combination highlights the algorithm’s ability to adapt in real time and maintain robust performance in dynamic environments.
6. Conclusions
This study presents a hybrid path planning algorithm for mobile robots by combining an improved JPS algorithm with DWA. The goal is to improve path planning efficiency and obstacle avoidance in complex and dynamic environments. In the global planning phase, a quadrant-based direction pruning strategy and a dynamic sine-based heuristic function are used to reduce redundant expansions and improve search efficiency. Additionally, cubic B-spline interpolation was applied to smooth the planned path, making it more continuous and easier to follow. In the local planning phase, the traditional DWA framework was improved by adding a heading angle factor, a safety distance penalty term, and a normalization mechanism. A dynamic weight adjustment strategy based on the distance to obstacles was also introduced to balance the trade-off between robustness and velocity during obstacle avoidance.
Simulation results show that the proposed integrated algorithm performs effectively in both static and dynamic environments. It generates reasonable paths while greatly reducing search time and node expansions, demonstrating strong practical applicability. However, this study is currently limited to simulation-based validation. The performance of the algorithm in real-world scenarios—particularly under challenging conditions such as sensor noise, localization errors, and varying densities of dynamic obstacles—remains to be further evaluated. Moreover, the adaptability of the hybrid approach in multi-robot cooperative tasks and scenarios with constrained real-time computational resources still has room for improvement. Future work will aim to apply this algorithm to multi-robot cooperative tasks and test it in real-world experiments to further enhance its reliability and applicability in real-world scenarios.