Next Article in Journal
A Low-Cost, Wide-Band, High-Gain Mechanically Reconfigurable Multi-Polarization Antenna Based on a 3-D Printed Polarizer
Previous Article in Journal
Real-Time Temperature Prediction for Large-Scale Multi-Core Chips Based on Graph Convolutional Neural Networks
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Effective Path Planning Method Based on VDWF-MOIA for Multi-Robot Patrolling in Expo Parks

School of Electronic and Electrical Engineering, Shanghai University of Engineering Science, Shanghai 201620, China
*
Author to whom correspondence should be addressed.
Electronics 2025, 14(6), 1222; https://doi.org/10.3390/electronics14061222
Submission received: 20 February 2025 / Revised: 17 March 2025 / Accepted: 19 March 2025 / Published: 20 March 2025

Abstract

:
Expo parks are characterized by dense crowds and a high risk of accidents. A multi-robot patrolling system equipped with multiple sensors can provide personalized services to visitors and quickly locate emergencies, effectively accelerating response times. This study focuses on developing efficient patrolling strategies for multi-robot systems. In expo parks, this requires solving the multiple traveling salesman problem (MTSP) and addressing multi-robot obstacle avoidance in static environments. The main challenge is to plan paths and allocate tasks effectively while avoiding collisions and balancing workloads. Traditional methods often struggle to optimize task allocation and path planning at the same time. This can lead to an unbalanced distribution of patrol tasks. Some robots may have too much workload, while others are not fully utilized. In addition, poor path planning may increase the total patrol length and reduce overall efficiency. It can also affect the coordination of the multi-robot system, limiting its scalability and applicability. To solve these problems, this paper proposes a multi-objective immune optimization algorithm based on the Van der Waals force mechanism (VDWF-MOIA). It introduces an innovative double-antibody coding scheme that adapts well to environments with obstacles, making it easier to represent solutions more diversely. The algorithm has two levels. At the lower level, the path cost matrix based on vector rotation-angle-based obstacle avoidance (PCM-VRAOA) calculates path costs and detour nodes. It effectively reduces the total patrol path length and identifies optimal obstacle avoidance paths, facilitating collaborative optimization with subsequent task allocation. At the higher level, a crossover operator inspired by the Van der Waals force mechanism enhances solution diversity and convergence by enabling effective crossover between antibody segments, resulting in more effective offspring. The proposed algorithm improves performance by enhancing solution diversity, speeding up convergence, and reducing computational costs. Compared to other algorithms, experiments on test datasets in a static environment show that the VDWF-MOIA performs better in terms of total patrol path length, load balancing metrics, and the hypervolume (HV) indicator.

1. Introduction

Expo parks are important cultural and entertainment centers, characterized by complex layouts, high visitor density, and unpredictable events. Currently, they rely on human patrols and CCD positioning monitoring, but these approaches cannot meet the security requirements at night. Combining monitoring patrols with security robot patrols would be a better solution [1]. Compared to traditional wireless sensor networks, multi-robot systems offer greater flexibility, lower energy consumption, and enhanced security. Robots equipped with various sensors can autonomously perceive their surroundings. They effectively collect different types of information [2,3,4,5]. According to specific situational needs, patrol robots can provide diverse services. These include information consulting, interactive entertainment, and medical assistance [6]. This significantly enhances the intelligence level of the expo parks and enriches the visitor experience. When robots encounter abnormal situations, the central controller analyzes data transmitted by the sensors. It can quickly identify potential risks and direct the robots to respond promptly. This greatly improves the park’s risk prevention and control capabilities, ensuring its safety. Therefore, establishing a multi-robot patrolling system for real-time monitoring and environmental information collection is crucial for ensuring the safety of the park.
In recent years, multi-robot systems have become a popular research topic, with wide applications in ocean exploration, mining, and disaster rescue [7,8,9,10]. In large-scale scenarios, using a single robot to complete all tasks is very time-consuming. Compared to a single robot, multi-robot patrolling systems have clear advantages in handling complex tasks, as they can collaborate to improve both efficiency and coverage. Therefore, multi-robot collaboration to complete tasks is an inevitable trend [11]. Without considering the characteristics of the problem, randomly assigning tasks to robots or simply assigning tasks that are closer to each other to the same robot will result in low system efficiency [12]. Therefore, designing an effective patrolling strategy for the multi-robot patrolling system of expo parks is a worthwhile research topic.
Despite their advantages, implementing effective multi-robot patrolling systems in complex environments like expo parks still faces challenges. The multi-robot patrolling problem involves multiple robots continuously moving, reaching target points, and performing tasks in a given environment. Therefore, developing path planning algorithms to guide robots from start to end points without hitting obstacles is essential for patrolling robots in obstacle environments. As one of the core links of multi-robot systems, path planning technology has been widely applied [13]. Path planning studies typically define environments as either known or unknown, based on pre-identified maps. Additionally, environments are classified as static or dynamic, depending on whether obstacles change during robot movement [14]. The multi-robot patrolling problem in expo parks combines the MTSP with the obstacle avoidance path planning problem, making it NP-hard [15]. It involves assigning multiple patrol points to robots, optimizing their visiting order, and planning collision-free paths. Additionally, when finding the optimal patrol plan, two objectives are considered, rather than focusing on just one objective. The main objectives are to minimize the total patrol path length and balance workloads among robots. Therefore, the multi-robot patrolling problem is essentially a multi-objective optimization problem, making it more suitable to be solved using a multi-objective optimization algorithm [16]. The multi-objective nature makes the problem more complex. First, reducing the total patrol path may conflict with workload balance, as shorter paths can lead to uneven task distribution among robots. Second, optimizing both path planning and task allocation is a major challenge. Path planning must consider obstacle avoidance, while task allocation requires balanced workloads among robots. In obstacle environments, it is challenging for the algorithm to find the best patrol scheme in a short time. Advanced algorithms are needed to manage the trade-offs and balance path length with robot workloads.
The core challenge of the multi-robot system for the expo park is to achieve collaborative optimization between task allocation and path planning. For the multi-robot patrolling problem in an expo park, a simple and direct solution is to break it down into two steps: task allocation and path planning. First, tasks are assigned to multiple robots, and then the patrol path for each robot is optimized. Although the traditional step-by-step method is simple, it has several key issues. First, the partitioned solution space can lead to local optima. The task allocation stage does not consider the constraints of path planning, which restricts path optimization to a limited local space and prevents overcoming the suboptimal solution framework formed by task allocation. Second, the step-by-step approach limits global path optimization. The process is split into independent stages, which prevents larger improvements. Lastly, the static task allocation strategy does not consider the robots’ actual movement costs, leading to poor load balancing in complex environments. Some robots accumulate tasks while others remain idle. These problems arise because the step-by-step optimization cannot integrate task allocation and path planning.
Therefore, for the multi-robot patrolling problem in a static environment, which is essentially the MSTP with obstacles, this study aims to develop an efficient multi-objective optimization algorithm that integrates task allocation and path planning. The algorithm seeks to balance shorter paths with equitable workload distribution among multiple robots. To address these issues, we propose a multi-robot patrolling algorithm that uses a synchronized decision-making mechanism, incorporating both task allocation and path planning into a unified optimization model. This model calculates the impact of path costs on task allocation in real time, breaking through the limitations of traditional methods. Specifically, a wireless sensor network is deployed in the expo park to gather prior environmental information. Sensors transmit the collected data to the central processor. By processing the sensor data, the central processor identifies high-risk areas that require patrolling by robots. Each robot in the multi-robot patrolling system is equipped with multiple sensors, such as infrared sensors [17], image sensors, sound sensors [18], and gas sensors [4]. The sensors collect information from the surrounding area, helping robots to patrol safely and perform special tasks. The robots share the collected information with each other along their paths. The central processor uses the patrol algorithm to achieve efficient patrol path planning for the multi-robot system. The control architecture diagram of the multi-robot patrolling system, as shown in Figure 1, comprises the decision layer, path planning layer, perception layer, and execution layer. The main contributions of this work are as follows:
  • A multi-objective multi-robot patrolling problem for the expo park is proposed. This problem combines the multiple traveling salesman problem (MTSP) and obstacle avoidance, simultaneously optimizing multi-robot task allocation and path planning. The objectives include minimizing the total patrol path length and achieving balanced task distribution among robots.
  • A path cost matrix method based on vector rotation-angle obstacle avoidance (PCM-VRAOA) is introduced. Before path optimization, this method calculates all feasible paths between patrol points and stores the path length and detour information. By establishing a global path cost matrix in the early stage of path planning, this method provides more reasonable obstacle avoidance paths and ensures better integration between path planning and task allocation, improving patrol path quality.
  • A new multi-objective immune optimization algorithm, VDWF-MOIA, is proposed. This algorithm is designed to enhance global search ability and path optimization in complex multi-robot patrolling problems. It adopts a dual-antibody encoding scheme to represent patrol paths and introduces a crossover operator inspired by the Van der Waals force mechanism. This operator improves solution diversity and convergence speed, effectively establishing a collaborative optimization mechanism between task allocation and path planning.
The remaining part of this paper consists of the following parts: Section 2 discusses related work, Section 3 states the multi-robot patrolling problem in the expo park, Section 4 describes our proposed optimization algorithm, and Section 5 presents simulation experiments and a comparison with other methods. The conclusion and a discussion of future work are finally presented in Section 6.

2. Related Work

Heuristic algorithms are effective methods for solving multi-robot path planning problems. Although they were initially designed for single-objective optimization, researchers have developed innovative mechanisms to adapt them for multi-objective optimization problems. As we aim to improve immune algorithms for solving the multi-robot patrolling problem, this section discusses the use of heuristic algorithms in addressing multi-robot path planning and multi-objective optimization.

2.1. Multi-Robot Path Planning Problem

In the past decades, various methods have been proposed to solve robot path planning problems. Broadly, traditional path planning methods can be divided into two categories: classical algorithms and heuristic algorithms. Classical methods, such as the cell decomposition scheme, potential field method, and sampling-based method, can guarantee optimal robot motion asymptotic. However, further studies have shown that these methods often lead to high computational costs and can easily be trapped in local minima values [19]. In order to overcome the defects of classical algorithms, heuristic algorithms have been developed, including neural networks, fuzzy logic, and nature-inspired algorithms (NIAs) [20].
As multi-robot systems are being increasingly applied in various fields, such as logistics delivery [21], environmental monitoring [22], counter-terrorism tasks [23], and disaster rescue [24,25,26], the requirements for different tasks are also expanding. Multi-robot systems now face increasingly complex scenarios. As a result, many researchers and engineers have focused on solving the multi-robot path planning problem in real-world environments, such as rugged terrain [27], underwater settings [28], and nuclear power stations [29]. In this paper, an important issue for the multi-robot patrolling system in expo parks is how to achieve effective multi-robot path planning. Researchers have made many efforts to address this problem.
According to whether prior map information is available, existing works can be divided into two types. One type is local path planning methods, which do not need any prior knowledge of the environment. Robots can use sensor data to plan their actions autonomously and respond to unexpected events. There are Simultaneous Localization and Mapping (SLAM) algorithms that allow robots to build maps of the environment. Combining SLAM with other navigation mechanisms can improve efficiency [30]. A widely used approach is the potential field method, which generates artificial attraction, repulsion, and alignment forces [31,32,33,34,35]. Multiple robots can share information and collaborate in navigation to jointly plan the optimal movement path [36,37]. The other type is the global path planning method. This method assumes that the robot receives environmental map information before path planning. This map can include all static obstacles and boundaries in the area. In this case, the optimal path is calculated based on prior map information. This paper mainly focuses on multi-robot path planning with known map information. The Dijkstra algorithm, popular in graph theory, is used to find the shortest path between nodes in an environment graph, making it effective for path planning problems [38]. Wu et al. used the Dijkstra algorithm to optimize path planning in urban traffic [39]. Compared to the Dijkstra algorithm, the A* algorithm has a notable heuristic function. It can predict the minimum cost between the current node and the goal, enabling A* to find more efficient paths. Ref. [40] proposes a path planning method that combines the A* algorithm with obstacle tangents for obstacle avoidance. Chen et al. uses the A* algorithm for global planning. Cubic spline functions are used to generate a set of candidate paths, ensuring path smoothness and obstacle avoidance. The optimal path is determined by adjusting the weight function [41]. Additionally, various alternative algorithms have been introduced: Collaborative A*, Hierarchical Collaborative A* (HCA*), Windowed HCA*, D*Lite [42], and M* [43,44]. However, graph-based methods have high computational complexity. Therefore, the need for intelligent algorithms increases when addressing more complex path planning problems. The genetic algorithm (GA) is a global search method. It optimizes paths through natural selection, crossover, and mutation [45]. Hao et al. optimizes the traditional genetic algorithm. They propose a global path planning method based on an adaptive genetic algorithm [46]. To improve exploration performance, Cui et al. introduces the teaching–learning-based optimization strategy to simultaneously determine the next position of all robots [47]. To enable robots to visit multiple target points and handle uncertainties in a known environment, ref. [48] further develops the Feedback-based Information Road Map (FIRM) to handle map uncertainties as a solvable Markov decision process. It achieves real-time replanning by combining offline and online algorithms.
Despite the emergence of various path planning algorithms, a single algorithm often struggles to meet practical requirements. Many scholars have found that combining multiple path planning methods can achieve better results [49,50,51,52,53]. Ref. [49] introduces logistic mapping in the immune algorithm (IA) to improve optimization. It combines the mutation and crossover operators of GA with the designed IA, enhancing antibody diversity during iterations. Ref. [50] uses an improved k-means clustering algorithm to divide the global map. Then, it uses a simulated annealing algorithm (SA) to compute the shortest patrol path for robots within the partitioned sub-maps. Ref. [51] presents a hybrid algorithm for global path planning of coal mine patrol robots, combining an improved artificial fish swarm algorithm with the dynamic window approach. However, these methods are not suitable for situations where robots have multiple target points. Ref. [52] adopts a centralized approach to task allocation and path planning. It uses GA for task allocation and A* for path planning. However, the A* algorithm requires storing all traversed paths, consuming significant memory and creating redundant paths. To improve the efficiency of iterative search, ref. [53] proposes the APF-IBRRT* algorithm, which integrates the Artificial Potential Field (APF) with an improved Bidirectional Rapidly-exploring Random Tree (B-RRT*). This algorithm addresses the local optima issue of traditional APF through potential field factor optimization and virtual obstacle introduction. It further designs a target threshold and an adaptive step size search strategy to improve tree search efficiency in narrow environments.
In recent years, reinforcement learning (RL) and deep learning (DL) have been used to improve multi-robot path planning. RL-based methods, such as signed-distance-field-based formation path planning (SDF-FPP), use rewards to learn better formation control and collision avoidance in static environments [54]. Deep Q-learning (DQN) helps optimize path planning by reducing redundant exploration with experience replay [55]. Hierarchical RL strategies, like TIHDP, enhance multi-robot cooperation by adapting to changing robot and object numbers. Its dynamic task priority layer optimizes resource allocation using global object data and inter-robot communication, ensuring efficient collaboration in dynamic environments [56]. However, reinforcement learning requires large training datasets and long training times. Deep learning models also have high inference delays, making real-time applications difficult. Beyond RL and DL, adaptive learning helps robots make better real-time decisions in dynamic environments. For example, an adaptive H control strategy was proposed for cruise control systems. It uses data-driven learning to estimate unknown system dynamics and update control strategies online [57]. This method shows how adaptive estimators and real-time learning can handle dynamic uncertainties well. Table 1 provides a concise summary of several different types of path planning algorithms.

2.2. Multi-Objective Optimization Algorithm

The multi-robot patrolling problem we address involves multiple targets. To address this kind of problem, some researchers have proposed multi-objective optimization for robot paths. The most direct way to solve a multi-objective optimization problem is to transform it into multiple single-objective optimization problems [58]. In [59,60], this transformation is achieved using weighted coefficients. While this method is simple, determining the weights scientifically is challenging. The resulting path is often just a compromise among several objectives.
Another approach is heuristic algorithms based on the Pareto-optimal set. This method provides a good solution for multi-objective optimization problems (MOPs), as it requires minimal mathematical operations and can generate satisfactory solutions [61]. Ref. [62] proposes an improved NSGA-II-based multi-objective optimization method for path planning in static environments. It uses discrete encoding, and introduces total path length and turning count as dual objectives, optimizing energy consumption as well. This method produces a better, diversified set of solutions in obstacle environments. Ref. [63] presents a Pareto front approximation method based on “regret” sampling. It gradually adds weight vectors using a greedy algorithm, ensuring even coverage of the Pareto front while providing clear error bounds. This achieves more efficient and accurate solutions in multi-objective optimization problems. Ref. [64] proposes a multi-objective discrete artificial bee colony algorithm. It combines a heuristic allocation method based on load balancing and a multi-objective local search strategy for non-dominated solutions. This ensures diversity and effectiveness of the initial solutions, achieving faster convergence and greater stability.

3. Multi-Robot Patrolling Problem

The multi-robot patrolling problem is one of the important components of studying multi-robot systems. This article mainly researches a multi-robot patrolling system for expo parks with multiple static obstacles.

3.1. Problem Statement

Firstly, construct a model of the expo park environment, where the exhibition halls are represented as convex polygonal obstacles. Then, install a set number of patrol points within the expo park as patrol tasks for the multi-robot system, and establish a robot station containing multiple operational robots. The environment modeling is illustrated in Figure 2. During a patrol cycle, each patrol point needs to be visited once by a robot without repetition. Robots depart from the robot station, execute all patrol tasks, and then return to the robot station.
In order to save energy costs, it is necessary to make the total patrol path length as short as possible. Here, the first objective function is introduced to minimize the total patrol path length of multiple robots. Additionally, to ensure balanced workload distribution among robots due to their limited energy capacity, the second optimization objective aims to minimize the standard deviation of patrol path lengths for each robot. In summary, this problem is a dual-objective optimization problem. The two objectives, namely minimizing the total patrol path length and minimizing the standard deviation of the patrol path length for each robot, are interconnected and mutually constraining.

3.2. Mathematical Model

First, we define all the variables that will be used:
R = { 1,2 , , m } : Set of robots.
P = { 1,2 , , n } : Set of patrol points.
S : Robot station (start/end point).
κ i j k { 0,1 } : Binary variable where κ i j k = 1 if robot k travels from i to j ( i , j P { S } ), else 0.
D = [ d i j ] : Distance matrix. d i j is the obstacle-avoiding shortest path between i and j .
The calculation formula for d i j , L k and L ¯ is as follows:
d i j = ( x i x j ) 2 ( y i y j ) 2 , i f   n o   o b s t a c l e s   b e t w e e n   i   a n d   j a v o i d a n c e   o b s t a c l e s   d i s t a n c e   b e t w e e n   i   a n d   j
L k = i = 1 n j = 1 , j i n κ i j k · d i j ,   k R
L ¯ = 1 m k = 1 m L k , k R
In addition, we also need to set the maximum and minimum number of patrol tasks for a single robot, represented by the symbols T m i n and T m a x , respectively.
Based on the definitions provided above, we can formulate our multi-robot patrolling problem as follows:
min f 1 = k = 1 m i p { S } j p { S } d i j κ i j k
m i n f 2 = 1 m k = 1 m ( L k L ¯ ) 2
s. t.
k = 1 m j = 1 , j i n κ i j k = 1 ,   i P
j = 1 n κ S j k = 1 ,   k R
i = 1 n κ i s k = 1 ,   k R
T m i n i P j P S , j i κ i j k T m a x ,   k R
Expressions (4) and (5) represent two optimization objectives stated in the previous subsection, which stand for minimizing the total patrolling path length and minimizing the standard deviation of patrol path lengths for each robot. Constraint (6) ensures that each patrol point is visited once and not repeatedly accessed. Constraint (7) guarantees that each robot departs from the robot station. Constraint (8) restrains each robot returns to the robot station after completing the last patrol task. Constraint (9) means that the number of patrol tasks performed by a single robot is greater than T m i n but less than T m a x .

3.3. Problem Complexity

The multi-robot patrolling problem for expo parks is classified as NP-hard due to its complexity, which comes from two main factors: the combinatorial nature of the MTSP and the presence of polygonal obstacles. The MTSP, even without obstacles, is NP-hard because the number of possible solutions grows exponentially as the number of patrol points increases. Obstacles make the problem even harder since calculating obstacle-avoiding paths between patrol points adds computation. The combination of task allocation and obstacle-aware path planning further increases complexity, making large-scale instances difficult to solve. Additionally, constraints like T m i n and T m a x limit the solution space, affecting both feasibility and solution quality. These constraints help balance the workload, but they need careful tuning. If the limits are too strict, optimal task assignments may be ruled out. If they are too loose, some robots may be overworked while others are underused. For example, a high T m i n might exceed a robot’s energy capacity, while a low T m a x could leave robots idle. These parameters should match the robots’ capabilities (e.g., battery life) to ensure both efficiency and feasibility.

4. Multi-Objective Immune Algorithm with Van Der Waals Force Mechanism

The multi-robot patrolling problem in expo parks, as described in Section 3.1, involves two main tasks. The first task is to assign patrol points to each robot and determine the optimal patrol order. The second task is to plan collision-free paths for multiple robots to complete their patrol tasks efficiently. A traditional way to solve this problem is optimizing task allocation and path planning separately. However, this method is prone to getting trapped in a local optimum. The core problem is that it overlooks their interdependence. Treating them independently means optimizing one task can harm the other. Thus, the final solution is likely suboptimal, restricted to a less-than-ideal result within a limited search space. To address this limitation, we propose the VDWF-MOIA, a unified framework that simultaneously optimizes task allocation and path planning. It ensures their interdependence is fully considered, leading to a globally optimal solution. The VDWF-MOIA builds on the artificial immune optimization algorithm but overcomes its limitations. Traditional immune algorithms struggle to converge efficiently due to the large solution space, but the VDWF-MOIA incorporates a Van der Waals force mechanism to improve exploration and convergence. The complete flowchart is shown in Figure 3.

4.1. Antibody Encoding

In the immune optimization algorithm, antibodies represent solutions to the problem. Considering traditional binary coding has the problem of a long bit string when facing large-scale problems, this paper adopts real number coding [65]. To address the problem in this paper, a novel antibody coding scheme called double-antibody encoding with virtual points is devised. Figure 4 shows a pair of antibodies, which map to each other and represent a solution to the problem. The first antibody is divided into two parts. In the first part, each gene position represents a patrol point, and the sequence of genes determines the patrol point visit order. In the second part, each gene position indicates the number of patrol tasks assigned to the corresponding robot. The second antibody is mapped from the first antibody. Here, 0 marks a break point to separate different patrol task sequences for each robot. The floating-point number represents the virtual patrol point, which is actually an obstacle detour node. The real part represents the obstacle serial number, and the decimal part represents the obstacle detour node serial number. Thus, the second antibody can represent the final patrol path of each robot, which is a feasible solution.

4.2. Affinity Calculation and Pareto-Optimal Solutions

The affinity values are calculated according to (4) and (5). In a multi-objective problem, each objective conflicts with the others. Optimizing one objective may impact the performance of the others simultaneously. Thus, there is not a single optimal solution but rather a set of optimal solutions. Given this analysis, selecting the optimal solution directly based on affinity values is not feasible. Therefore, we introduce the concept of Pareto-optimal solutions [66] to identify promising individuals.

4.3. Path Cost Matrix Based on Vector Rotation-Angle-Based Obstacle Avoidance

We propose a path cost matrix based on vector rotation-angle obstacle avoidance algorithm (PCM-VRAOA) for multi-robot path planning. The implementation involves four key phases:
(1)
Vector Polar Angle Calculation: For each obstacle vertex O i = ( x i , y i ) , the algorithm calculates the rotation angle θ relative to the robot’s current position r = ( x r , y r ) , using Formula (10):
θ i = arctan 2 y i y r   ,   x i x r
This formula computes the angle between the horizontal axis and the line connecting the robot to the vertex. These angles form an ordered sequence to identify critical detour nodes.
(2)
Bidirectional Search Strategy: The algorithm simultaneously explores two paths—one following maximum-angle vertices (clockwise) and another tracking minimum-angle vertices (counter-clockwise). This dual-path approach ensures comprehensive obstacle boundary coverage, as illustrated in Figure 5.
(3)
Path Cost Evaluation: The total length L of each candidate path is computed as shown in Formula (11):
L = r O 1 + i = 1 n 1 O i O i + 1 + O n g
Here, r 1 O 1 is the distance from the robot’s start position r to the first detour node O 1 , O i O i + 1 represents the distance between consecutive detour nodes, and O n g is the distance from the last detour node O n to the goal g .
(4)
Dynamic Path Selection: The shortest valid path is chosen based on Formula (12):
L f i n a l = m i n ( L 1 , L 2 )
where L 1 and L 2 are the lengths of the maximum-angle and minimum-angle paths, respectively. This ensures efficient navigation through complex environments.
By iterating this process across all patrol points, PCM-VRAOA constructs an n × n path cost matrix containing optimized detour nodes and precomputed path lengths. This matrix serves as a global navigation knowledge base, enabling rapid task allocation decisions. The visualization result of this path construction is shown in Figure 6. The complete calculation process, as shown in Figure 7, accepts map inputs such as patrol points, convex polygons, and robot stations, and outputs both collision-free paths and the cost matrix for multi-robot coordination.

4.4. Van Der Waals Force Mechanism

The Van der Waals force [67], also known as intermolecular force, is a type of interaction that widely exists between molecules, or between molecules and rare gas atoms. The magnitude of Van der Waals forces varies between different molecules. Essentially, the force is an attraction or repulsion between positive and negative charges. This interaction allows most substances to exist in a condensed state. The Van der Waals force cannot change the internal structure of molecules; it can only order the arrangement of molecules.
Inspired by this fundamental physical phenomenon, this paper introduces the Van der Waals force mechanism into multi-objective immune optimization algorithms. The flow chart of the Van der Waals force mechanism is shown in Figure 8. Firstly, antibodies are segmented into a certain number of gene fragments. These fragments are considered as molecules or atoms in the physical world, and the Van der Waals forces between gene fragments are defined. Secondly, the Van der Waals forces between gene fragments are calculated. These forces are calculated to accurately distinguish the importance of different gene fragments in parental antibodies. Gene fragments with larger Van der Waals forces are more likely to aggregate together, forming gene fragment pairs. Finally, crossover operations are performed on the matched gene fragments to generate new antibodies.
Compared to existing immune algorithms and their crossover operators, the Van der Waals force mechanism has significant advantages in the following aspects: First, compared to traditional crossover operators (such as order crossover, OX, and partially mapped crossover, PMX), the Van der Waals force mechanism intelligently matches similar gene fragments, avoiding inefficient crossover caused by randomness while maintaining path continuity and diversity. OX can preserve path continuity but lacks consideration of the intrinsic relationships between fragments, making it prone to local optima. PMX, due to its high randomness, may lead to ineffective crossover, reducing algorithm efficiency. Second, compared to classical immune algorithms, the Van der Waals force mechanism introduces a physical model to better utilize the structural information of the solution space, improving search efficiency and solution quality. Traditional immune algorithms typically rely on random crossover and mutation operations, lacking in-depth exploration of the solution space structure, resulting in lower search efficiency.

4.4.1. The Definition of Van Der Waals Force

The basic idea of designing the Van der Waals force calculation formula between any two gene fragments is straightforward. It considers two main factors: the length and gene value of each gene fragment. These factors affect the distance and similarity between fragments. The Van der Waals force between gene fragments is inversely proportional to their distance, and directly proportional to their similarity. Thus, the Van der Waals force formula between gene fragments a and b is defined as (13):
F v ( a , b ) = S ( a , b ) [ d ( a , b ) ] 2
where S ( a , b ) represents the similarity between gene fragments a and b , as shown in (14), assuming that L a represents the length of gene fragment a and L b represents the length of gene fragment b , and L a L b ; d ( a , b ) represents the distance between gene fragments a and b, as shown in (15), where N ( a , b ) represents the number of identical gene values in gene fragments a and b .
S a , b = 1 d a , b L b + 1
d a , b = L a N ( a , b )

4.4.2. Theoretical Basis and Formal Proof

The theoretical foundation of the Van der Waals force formula is based on the physical model of intermolecular interactions. Specifically, the similarity S ( a , b ) and distance d ( a , b ) in the formula simulate the attraction and repulsion between molecules. The similarity S ( a , b ) is defined as the cosine similarity between gene fragments a and b , with a range of [ 1,1 ] , accurately reflecting the correlation between fragments. The distance d ( a , b ) is defined as the Euclidean distance between gene fragments a and b , and its inverse-square relationship ensures strong attraction for closely located fragments. This design not only aligns with physical laws but also effectively captures the intrinsic relationships between gene fragments. To further validate the effectiveness of Formulas (13)–(15), we provide the following formal proofs:
  • Similarity Measure: Cosine similarity measures the directional consistency between gene fragments. A value closer to 1 indicates higher similarity, while a value closer to −1 indicates lower similarity.
  • Distance Measure: The inverse-square relationship of Euclidean distance ensures strong attraction for closely located fragments while avoiding excessive influence from distant fragments.
  • Convergence Analysis: Using a Markov chain model, we prove that the Van der Waals force mechanism ensures the algorithm converges to the global optimal solution within a finite number of iterations. Specifically, the optimization process can be modeled as a Markov chain, where each state represents the current solution, and state transitions are driven by the crossover operations of the Van der Waals force mechanism. The transition probability P i j is proportional to F v ( a , b ) , i.e., P i j F v a , b = S ( a , b ) [ d a , b ] 2 . The monotonicity of transition probabilities ensures that the algorithm gradually approaches better solutions while maintaining solution diversity through intelligent matching of similar fragments, avoiding local optima.

4.4.3. Gene Fragments Separating and Matching Process

This section explains in detail how to split and match the selected two parent antibodies. First, according to the gene representing the number of patrol points of each robot in the antibody, the gene representing the patrol point sequence is divided into different gene segments. Each gene segment represents the patrol point sequence of a robot. Then, according to (13)–(15), the Van der Waals forces between each gene fragment pair from two parent antibodies are calculated. These results are stored in the Van der Waals force matrix. Finally, the gene fragment pair corresponding to the largest Van der Waals force value in the Van der Waals force matrix is identified. These two gene fragments are matched together, laying the foundation for the subsequent crossover operation.

4.4.4. Gene Fragments Crossing Process

This section explains in detail how to perform a crossover operation on matched gene pairs. These gene pairs are generated from above process. For example, the antibody “Mom” is used as a benchmark. This benchmark is used to generate the offspring antibody “Child1”. Assume that “M3” and “D3” are gene pairs. These gene pairs are matched according to the Van der Waals force matrix.
Step1: Perform a crossover operation on the genes representing the patrol order in the antibody “Mom”. Two crossover points, denoted p1 and p2, are randomly generated. The length of the crossover fragment does not exceed the length of the shortest gene fragment. The gene fragments “M3” and “D3” are crossed at these two points. Then, check whether there are duplicate gene values in “M3” after crossing. If duplicates are found, the excess gene values are set to 0.
Step2: According to the position of gene fragment “M1” in antibody “Mom”, “M1” is inserted into the corresponding position in antibody “Child1”. Next, identify the remaining patrol points. These remaining patrol points are filled into the blank gene locations of “Child1,” according to their order in the antibody “Mom”.
Step3: Perform crossover operation on genes in antibody “Mom”. These genes represent the number of patrol points assigned to each robot. A gene is randomly selected to perform a single point crossover. After the crossover, the change amount of this gene location is calculated. If the change amount is positive, find the gene with the largest gene value among the remaining genes. Then subtract the change amount from the gene’ value. If the change amount is negative, find the gene with the smallest gene value among the remaining genes. Then add the change amount to the gene’s value. This ensures that the total number of all robot patrol points remains the same after crossover. It also creates more combinations of robot patrol points, which helps to improve antibody diversity. Meanwhile, employing the antibody “Dad” as a benchmark, the same operation as above is performed to generate the offspring antibody “Child2”. The schematic diagram of the separating, matching, and crossing process is shown in Figure 9.

5. Experiments

In this section, the effectiveness of PCM-VRAOA method is first verified. Then, the proposed VDWF-MOIA algorithm is compared and analyzed with various classic multi-objective optimization algorithms. Finally, the algorithm is applied to the path planning problem of the multi-robot patrolling system in the expo park, providing various patrol schemes for different scenarios.

5.1. Experimental Settings

Since the core of this study is path planning for the multi-robot patrolling system, all robots are simplified as particles, without considering their volume and specific actions. In order to verify the effectiveness of the proposed method, three simulation maps of the expo park, ranging from simple to complex, are set up. Table 2 provides the parameters of the three simulation maps of the expo park, including the number of patrol points, obstacles, and robots. The obstacles are set as convex polygonal entities. The types, shapes, and quantities of obstacles in the map are different. The map size is uniformly 100 × 100.
To evaluate the advantages of the PCM-VRAOA method in terms of runtime, total path length, and load balancing, we compare the MOIA algorithm embedded with PCM-VRAOA (MOIA w/PCM-VRAOA) to the MOIA algorithms embedded with A* [68], BAS-A* [69], and RRT* [70] (MOIA w/A*, MOIA w/BAS-A*, and MOIA w/RRT*); To evaluate the improvements in convergence and search capability of VDWF-MOIA, we compared it with classic multi-objective optimization algorithms, including the non-dominated sorting genetic algorithm (NSGA) [71], non-dominated sorting genetic algorithm II (NSGA-II) [72], non-dominated neighbor immune algorithm (NNIA) [73], and a many-objective immune algorithm with a novel immune cloning operator (MaIA) [74]. These algorithms are considered state-of-the-art and widely used benchmarks in the field of multi-objective optimization. Additionally, NNIA and MaIA are both derived from immune algorithms. Therefore, we believe that comparing our proposed method with these algorithms convincingly demonstrates its advantages. Each algorithm is independently run 50 times on three simulation maps. Based on the pre-defined mathematical model of multi-robot patrolling path planning and simulation maps, all experiments were conducted using the software MATLAB R2023a on an Intel Core i7-12700H CPU at 2.30 GHz and with 16 GB RAM on a laptop computer.

5.2. Parameter Sensitivity Analysis

To achieve the best optimization effect, we conduct sensitivity experiments on the parameters popsize, pc, and pm. In the first stage, we optimize the popsize by setting p m = 0.1 , p c = 0.9 , and popsize to 50, 100, 150, and 200, respectively. The performance indicators are HV and running time. The experimental results are shown in Table 3. For the HV indicator, when the popsize goes from 50 to 100, the HV value goes up by about 5.82%. When the popsize increases from 100 to 200, the rise in the HV value is small, at around only 1.52%, but the running time increases by 58.89%. Therefore, this paper selects a popsize of 100. This is because this value can achieve a good balance between the HV value and the running time. In the second stage, a comprehensive tuning is conducted for the crossover probability and mutation probability. The popsize is fixed at 100. The tested crossover probabilities are 0.5, 0.6, 0.7, 0.8, and 0.9, and the tested mutation probabilities are 0.05, 0.08, 0.10, 0.12, and 0.15. The heatmap of pc and pm is shown in Figure 10. In the heatmap, the area with p c = 0.9 and p m = 0.10 is the brightest, meaning the HV value there is the highest. Thus, this paper determines the parameters p c = 0.9 and p m = 0.10 .

5.3. Validation Experiment for the PCM-VRAOA

The comparative evaluation of MOIA combined with different path planning algorithms reveals performance differences in various test scenarios.
In terms of runtime, as shown in Table 4, MOIA w/ BAS-A* achieves the shortest runtime on all maps, demonstrating its efficiency in online path computation. Notably, compared to sampling-based methods, MOIA w/PCM-VRAOA shows competitive runtime efficiency in small and medium-scale environments. For example, on Map 1, MOIA w/PCM-VRAOA completes tasks in 50.94 s, which is 23.27% faster than MOIA w/RRT* but slower than MOIA w/A* and MOIA w/BAS-A*. Similarly, on Map 2, MOIA w/PCM-VRAOA takes 265.70 s, which is 30.67% faster than MOIA w/RRT* but slower than MOIA w/A* and MOIA w/BAS-A*. However, this advantage diminishes in large-scale environments, where MOIA w/PCM-VRAOA has a higher runtime than other methods on Map 3. This performance difference is due to a strategic trade-off in MOIA w/PCM-VRAOA; by introducing an offline precomputation mechanism, it increases computational overhead during online task allocation but enables real-time collaborative optimization of path planning and task allocation. Although the runtime increases, it significantly improves the quality of patrol solutions, which is a critical requirement for multi-robot patrol systems. Therefore, while MOIA w/BAS-A* has the shortest runtime, MOIA w/PCM-VRAOA achieves a balanced trade-off between total path length and load balancing, making it more suitable for optimizing multi-robot coordination and overall system performance.
In terms of solution quality, the MOIA w/PCM-VRAOA algorithm offers significant advantages in both total path length and load balancing. It consistently outperforms baseline algorithms across different map environments. Its superior performance stems from its visibility reasoning framework and collaborative optimization mechanism, which enable more efficient path planning and balanced task allocation.
Regarding total path length, MOIA w/PCM-VRAOA effectively eliminates unnecessary detours by pre-connecting navigable obstacle vertices, resulting in shorter and more efficient paths. As shown in Table 5, MOIA w/PCM-VRAOA demonstrates clear advantages over other methods. Compared to MOIA w/A*, its paths are 24.21% shorter on Map 1, 31.92% shorter on Map 2, and 14.21% shorter on Map 3. This is because MOIA w/A* relies on a heuristic-based search strategy, which limits its ability to explore optimal routes and often leads to inefficient paths. Similarly, MOIA w/BAS-A* improves upon A* with a bidirectional search strategy but is still prone to getting stuck in local optima, causing its paths to be 16.21% longer on Map 1, 19.28% longer on Map 2, and 7.32% longer on Map 3 compared to MOIA w/PCM-VRAOA. MOIA w/RRT*, as a sampling-based method, lacks precise path refinement, resulting in excessive detours. Its paths are 28.21% longer on Map 1, 36.84% longer on Map 2, and 17.51% longer on Map 3 compared to MOIA w/PCM-VRAOA. These results illustrate the advanced path optimization capabilities of MOIA w/PCM-VRAOA, especially in structured environments.
Additionally, load balancing metrics further demonstrate MOIA w/PCM-VRAOA’s coordination capabilities in multi-robot systems. As shown in Table 6, MOIA w/PCM-VRAOA maintains a low standard deviation in workload distribution. On Map 1–Map 3, this method improves by 23.07%, 29.89%, and 46.23% compared to the second-best method (MOIA w/BAS-A*). This advantage is mainly attributed to the dual optimization mechanism introduced by MOIA w/PCM-VRAOA, where collaborative optimization of task allocation and path planning is achieved through precomputation. Specifically, MOIA w/PCM-VRAOA reduces real-time computational burden by precomputing task allocation before path planning and optimizes load balancing during path planning to avoid spatial conflicts, enabling more efficient multi-robot coordination.
In summary, MOIA w/PCM-VRAOA successfully addresses the dual challenges of precise path planning and multi-robot coordination. While moderately increasing computational costs, the algorithm demonstrates excellent online performance in key areas such as solution quality and load balancing.

5.4. Comparison with Other Heuristic Algorithms

This paper selects the heuristic algorithms NSGA, NSGA-II, NNIA, and MaIA for comparison. They are all classic algorithms in the field of multi-objective optimization algorithms. Thus, they can serve as convincing competitors. To evaluate the improvements in convergence and search ability of our algorithm, we designed three maps of different sizes: small, medium, and large. To ensure effective optimization, we adjusted the population size and maximum iterations based on map scale. In the small-scale environment, we used a population of 100 and 500 iterations for efficient convergence. For the medium scale, we increased them to 200 and 1000 to balance exploration and efficiency. In the large-scale environment, we set them to 300 and 3000 for thorough optimization. These adjustments ensure effective performance across different scenarios while maintaining computational efficiency. The VDWF-MOIA algorithm presented in this study incorporates the PCM-VRAOA method for multi-robot path planning. To ensure consistency in the path planning method, the PCM-VRAOA method is also embedded in the NSGA, NSGA-II, NNIA, and MaIA algorithms when solving the problems in this study. To reduce randomness and more accurately assess the algorithms’ performance and stability, all algorithms were run independently 50 times. We provide the parameters of the compared algorithms and VDWF-MOIA in Table 7.
We introduce the hypervolume (HV) indicator [75] to comprehensively assess the convergence and diversity of the Pareto-optimal set, thereby evaluating the overall performance of these heuristic algorithms. A higher HV indicator indicates better overall performance of the algorithm. The calculation of the HV indicator is related to a reference point. Here we use the maximum value point of each group as the reference point. The HV convergence curves are shown in Figure 11, Figure 12 and Figure 13, clearly demonstrating the optimization performance of each algorithm in different scenarios. In the Map 1 scenario, VDWF-MOIA shows a strong initial convergence advantage. In the first 100 iterations, the HV indicator increases rapidly from 0.38 to 0.60, a growth of 57.89%, significantly outperforming other algorithms. By 500 iterations, the HV indicator stabilizes at 0.63, improving by 6.78%, 16.67%, 18.87%, and 23.53% compared to MaIA, NSGA-II, NNIA, and NSGA, respectively. In the Map 2 scenario, the convergence advantage of VDWF-MOIA is even more pronounced. In the first 300 iterations, the HV indicator increases by 66.67%, reaching 0.63 by 1000 iterations, with improvements of 2.28%, 8.28%, 16.54%, and 19.18% compared to MaIA, NSGA-II, NNIA and NSGA. In the Map 3 scenario, VDWF-MOIA achieves a 50% increase in HV indicator (from 0.30 to 0.60) within the first 1000 iterations. The HV metric eventually stabilized at about 0.65, representing improvements of 3.01%, 4.84%, 16.07%, and 24.81% compared to MaIA, NSGA-II, NNIA, and NSGA, respectively. The experimental results show that VDWF- MOIA exhibits fast convergence across scenarios of different scales, and its final solution quality is significantly better than that of the comparison algorithms. This verifies its excellent global search capability and resistance to premature convergence.
To further evaluate the stability and optimization effectiveness of VDWF-MOIA in multi-robot patrol tasks, this paper conducted boxplot analysis on the HV indicator. As shown in Figure 14, Figure 15 and Figure 16, VDWF-MOIA achieved the highest HV values across all test scenarios, demonstrating superior optimization performance. Additionally, its smaller interquartile range (IQR) indicates concentrated solution distribution and more stable optimization results. In contrast, NSGA and NNIA showed lower HV values with larger IQRs, revealing unstable optimization. While NSGA-II and MaIA showed improved HV values, they still underperformed compared to VDWF- MOIA. Overall, by optimizing task allocation and patrol sequence matching, VDWF-MOIA consistently maintains high-quality solution sets across various scale scenarios, exhibiting stronger global search capability and stability, effectively enhancing multi-robot system execution efficiency.
The two-tailed t-test compares mean differences between independent datasets to determine statistical significance. This study applied this method to verify whether VDWF-MOIA’s optimization effectiveness significantly outperforms other algorithms in repeated experiments. As shown in Table 8, VDWF-MOIA demonstrated statistically significant advantages with all p-values well below 0.05 across all maps. Particularly on small-scale maps (Map 1), p-values were far below 0.01, indicating strong optimization superiority. In medium- and large-scale maps (Map 2, Map 3), VDWF-MOIA maintained significant advantages (p < 0.05), further proving its stability and adaptability.

5.5. Simulation Patrol Scheme Diagram

As analyzed in Section 3, the multi-robot patrolling path planning problem concerned in this paper is a multi-objective optimization problem. Unlike general robot path planning problems, the scenarios we are concerned with require many different patrolling schemes. This is the main feature of this work, and it is also a realistic requirement that must be met.
We implemented and evaluated our VDWF-MOIA in the experimental environment described in Section 5.1. For the three simulation maps, the results of multi-robot patrolling path planning are shown in Figure 17, Figure 18 and Figure 19. Since the algorithm needs to optimize two objectives simultaneously, we select two representative Pareto solutions from the Pareto solution set as cases. Different Pareto solutions represent distinct multi-robot patrolling schemes. The objective function values for each scheme are shown in Table 9. For instance, in Map 3, for the first objective of minimizing the total patrolling path length, Figure 19a offers a satisfactory option for decision-makers. For the second objective of minimizing the standard deviation of path lengths between individual robots, Figure 19b provides a satisfactory choice. As can be seen from the results of Figure 17, Figure 18 and Figure 19, the VDWF-MOIA algorithm provides clear and rational path planning solutions for the multi-robot patrolling system in expo parks.

6. Conclusions and Future Work

In this research, we propose the VDWF-MOIA algorithm to address the multi-robot patrolling path planning problem in expo parks under a static environment. This problem is essentially equivalent to the MTSP with obstacles. The main contributions are as follows:
  • This paper proposes a dual-antibody encoding scheme with virtual patrol points. Antibody 1 represents the robot task sequence. Antibody 2 represents the allocation of patrol points. Virtual patrol points expand the representation of the solution space. Traditional immune algorithms usually use a single encoding method. They struggle to represent both task allocation and path planning. This limits diversity and search ability. The proposed scheme makes antibody expressions more diverse. It optimizes task allocation and path planning at the same time, and provides a foundation for future collaborative optimization.
  • This paper proposes the PCM-VRAOA method. The method precomputes path costs and obstacle avoidance nodes to ensure both feasibility and optimality. In multi-robot patrolling scenarios, the obstacle environment is complex. Traditional path planning methods struggle to balance obstacle avoidance and global optimization. The proposed method improves the coordination of multi-robot task allocation and path planning. It effectively enhances collaborative optimization, providing reliable support for multi-robot cooperative patrols.
  • This paper proposes a crossover operator based on the Van der Waals mechanism. The operator intelligently matches gene segments to improve crossover efficiency and fully utilize the solution space structure. Traditional multi-objective immune optimization algorithms struggle to balance global search and convergence. They easily fall into local optima. Moreover, traditional crossover operators cannot effectively use the structural information of the solution space. In contrast, the proposed operator not only generates better Pareto solutions and significantly accelerates convergence, but also enhances search diversity, thus improving overall optimization performance.
In the experiment, three static simulation environments of different scales are established to verify the effectiveness of the VDWF-MOIA. Compared with NNIA, NSGA, NSGA-II, and MaIA, the experimental results show that in map scales ranging from small to large, VDWF-MOIA outperforms the comparison algorithms in terms of the HV indicator, total patrol path length, and load balancing metric.
Although VDWF-MOIA performs well in static environments, it has limitations that need to be addressed for broader practical applications. Future work will focus on two key directions:
  • High Computational Cost: VDWF-MOIA requires significant computing resources due to the complexity of its fitness calculation and the Van der Waals force mechanism. In each iteration, the algorithm evaluates the fitness of all individuals, which relies on PCM-VRAOA to generate obstacle avoidance paths. Additionally, the Van der Waals force mechanism calculates the similarity and distance between all gene fragments, generating a Van der Waals force matrix. This process has a time complexity of O ( n 2 ) , where n is the number of gene fragments. As the number of patrol points and robots increases, the computational cost rises significantly. To reduce computational costs, future work will integrate deep learning and reinforcement learning (RL). A deep neural network (DNN) will replace traditional fitness calculations by learning path cost–task assignment mappings offline, significantly reducing online computation time. RL will dynamically adjust VDWF-MOIA parameters (e.g., crossover and mutation rates) to improve convergence speed and resource efficiency. Additionally, parallel computing and approximation techniques will be explored to optimize the Van der Waals force mechanism, further reducing computational overhead.
  • Dynamic Environment Adaptability: While VDWF-MOIA excels in static environments, its functionality can be extended to handle dynamic obstacles and real-time patrol changes. To achieve this, a data-driven module will be introduced. This module will use real-time sensor data to detect dynamic obstacles and update the environment model. A data-driven task allocation mechanism will dynamically adjust patrol priorities based on risk levels, ensuring efficient responses to changing environments. Additionally, future work will address hardware and communication challenges by developing lightweight algorithms for resource-constrained robots and designing robust communication protocols to minimize delays and data loss, enhancing multi-robot coordination in dynamic scenarios.
These optimizations will build on VDWF-MOIA’s strengths, improving its efficiency and adaptability for real-world applications.

Author Contributions

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

Funding

This work was supported in part by the National Natural Science Foundation of China under Grant 62103257; and in part by the Natural Science Foundation of Shanghai, China, under Grant 22ZR1426200.

Data Availability Statement

Our data sharing is applicable. The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Chung, L.-Y. Remote Teleoperated and Autonomous Mobile Security Robot Development in Ship Environment. Math. Probl. Eng. 2013, 2013, 902013. [Google Scholar] [CrossRef]
  2. Peng, Z.; Chen, B.; Zhang, L.; Qiu, X. Emergency-management-697 oriented model design and realization in artificial society. Manage. Rev. 2016, 28, 133. [Google Scholar]
  3. Qiu, S.; Chen, B.; Wang, R.; Zhu, Z.; Wang, Y.; Qiu, X. Atmospheric 700 dispersion prediction and source estimation of hazardous gas using 701 artificial neural network, particle swarm optimization and expectation 702 maximization. Atmos. Environ. 2018, 178, 158–163. [Google Scholar] [CrossRef]
  4. Ishida, H.; Nakayama, G.; Nakamoto, T.; Moriizumi, T. Controlling a gas/odor plume-tracking robot based on transient responses of gas sensors. IEEE Sens. J. 2005, 5, 537–545. [Google Scholar] [CrossRef]
  5. Xing, Y.; Vincent, T.A.; Fan, H.; Schaffernicht, E.; Bennetts, V.H.; Lilienthal, A.J.; Cole, M.; Gardner, J.W. FireNose on Mobile Robot in Harsh Environments. IEEE Sens. J. 2019, 19, 12418–12431. [Google Scholar] [CrossRef]
  6. Liang, J.; Wu, J.; Huang, H.; Xu, W.; Li, B.; Xi, F. Soft Sensitive Skin for Safety Control of a Nursing Robot Using Proximity and Tactile Sensors. IEEE Sens. J. 2020, 20, 3822–3830. [Google Scholar] [CrossRef]
  7. Tolmidis, A.T.; Petrou, L. Multi-objective optimization for dynamic task allocation in a multi-robot system. Eng. Appl. Artif. Intell. 2013, 26, 1458–1468. [Google Scholar] [CrossRef]
  8. Wu, J.; Wang, H.; Li, N.; Yao, P.; Huang, Y.; Yang, H. Path planning for solar-powered UAV in urban environment. Neurocomputing 2018, 275, 2055–2065. [Google Scholar] [CrossRef]
  9. Zhuang, Y.; Huang, H.; Sharma, S.; Xu, D.; Zhang, Q. Cooperative path planning of multiple autonomous underwater vehicles operating in dynamic ocean environment. ISA Trans. 2019, 94, 174–186. [Google Scholar] [CrossRef]
  10. Bai, C.; Kusi-Sarpong, S.; Sarkis, J. An implementation path for green information technology systems in the Ghanaian mining industry. J. Clean. Prod. 2017, 164, 1105–1123. [Google Scholar] [CrossRef]
  11. Li, R.-G.; Wu, H.-N. Multi-Robot Source Location of Scalar Fields by a Novel Swarm Search Mechanism with Collision/Obstacle Avoidance. IEEE Trans. Intell. Transport. Syst. 2022, 23, 249–264. [Google Scholar]
  12. Yan, X.; Zuo, H.; Hu, C.; Gong, W.; Sheng, V.S. Load Optimization Scheduling of Chip Mounter Based on Hybrid Adaptive Optimization Algorithm. Complex Syst. Model. Simul. 2023, 3, 1–11. [Google Scholar]
  13. Yi, X.; Zhu, A.; Li, C.; Yang, S.X. A novel bio-inspired approach with multi-resolution mapping for the path planning of multi-robot system in complex environments. J. Comput. Des. Eng. 2022, 9, 2343–2354. [Google Scholar]
  14. Deng, X.; Li, R.; Zhao, L.; Wang, K.; Gui, X. Multi-obstacle path planning and optimization for mobile robot. Expert Syst. Appl. 2021, 183, 115445. [Google Scholar]
  15. Nasrollahy, A.Z.; Javadi, H.H.S. Using Particle Swarm Optimization for Robot Path Planning in Dynamic Environments with Moving Obstacles and Target. In Proceedings of the 2009 Third UKSim European Symposium on Computer Modeling and Simulation, Athens, Greece, 25–27 November 2009; IEEE: New York, NY, USA, 2009; pp. 60–65. [Google Scholar]
  16. Li, Y.; Yue, T.; Ali, S.; Zhang, L. A multi-objective and cost-aware optimization of requirements assignment for review. In Proceedings of the 2017 IEEE Congress on Evolutionary Computation (CEC), Donostia, Spain, 5–8 June 2017; IEEE: New York, NY, USA, 2017; pp. 89–96. [Google Scholar]
  17. Almasri, M.M.; Alajlan, A.M.; Elleithy, K.M. Trajectory planning and collision avoidance algorithm for mobile robotics system. IEEE Sens. J. 2016, 16, 5021–5028. [Google Scholar] [CrossRef]
  18. Bryndin, E. Increased Sensitivity and Safety of Cognitive Robot by Developing Professional and Behavioral Skills. SJET 2020, 5, 187–196. [Google Scholar]
  19. Dudek, G.; Jenkin, M. Computational Principles of Mobile Robotics, 2nd ed.; Cambridge University Press: Cambridge, UK, 2010. [Google Scholar]
  20. Orozco-Rosas, U.; Montiel, O.; Sepúlveda, R. Mobile robot path planning using membrane evolutionary artificial potential field. Appl. Soft Comput. 2019, 77, 236–251. [Google Scholar]
  21. Alitappeh, R.J.; Jeddisaravi, K. Multi-robot exploration in task allocation problem. Appl. Intell. 2022, 52, 2189–2211. [Google Scholar] [CrossRef]
  22. Lemaire, T.; Alami, R.; Lacroix, S. A distributed tasks allocation scheme in multi-UAV context. In Proceedings of the IEEE International Conference on Robotics and Automation, New Orleans, LA, USA, 26 April 2004–1 May 2004; IEEE: New York, NY, USA, 2004; pp. 3622–3627. [Google Scholar]
  23. Zhao, S.; Chen, B.M.; Lee, T.H. Optimal sensor placement for target localisation and tracking in 2D and 3D. Int. J. Control. 2013, 86, 1687–1704. [Google Scholar]
  24. Trigui, S.; Cheikhrouhou, O.; Koubaa, A.; Baroudi, U.; Youssef, H. FL-MTSP: A fuzzy logic approach to solve the multi-objective multiple traveling salesman problem for multi-robot systems. Soft Comput. 2017, 21, 7351–7362. [Google Scholar]
  25. Hussein, A.; Adel, M.; Bakr, M.; Shehata, O.M.; Khamis, A. Multi-robot Task Allocation for Search and Rescue Missions. J. Phys. Conf. Ser. 2014, 570, 052006. [Google Scholar]
  26. Khani, M.; Ahmadi, A.; Hajary, H. Distributed task allocation in multi-agent environments using cellular learning automata. Soft Comput. 2019, 23, 1199–1218. [Google Scholar]
  27. Wang, B.; Li, S.; Guo, J.; Chen, Q. Car-like mobile robot path planning in rough terrain using multi-objective particle swarm optimization algorithm. Neurocomputing 2018, 282, 42–51. [Google Scholar]
  28. Ataei, M.; Yousefi-Koma, A. Three-dimensional optimal path planning for waypoint guidance of an autonomous underwater vehicle. Robot. Auton. Syst. 2015, 67, 23–32. [Google Scholar]
  29. Wang, Z.; Cai, J. The path-planning in radioactive environment of nuclear facilities using an improved particle swarm optimization algorithm. Nucl. Eng. Des. 2018, 326, 79–86. [Google Scholar]
  30. Milford, M.; Wyeth, G. Hybrid robot control and SLAM for persistent navigation and mapping. Robot. Auton. Syst. 2010, 58, 1096–1104. [Google Scholar]
  31. Olcay, E.; Lohmann, B. Extension of the Cucker-Dong Flocking with a Virtual Leader and a Reactive Control Law. In Proceedings of the 2019 18th European Control Conference (ECC), Naples, Italy, 25–28 June 2019; IEEE: New York, NY, USA, 2019; pp. 101–106. [Google Scholar]
  32. Guerra, M.; Efimov, D.; Zheng, G.; Perruquetti, W. Avoiding local minima in the potential field method using input-to-state stability. Control. Eng. Pract. 2016, 55, 174–184. [Google Scholar]
  33. Okamoto, M.; Akella, M.R. Novel potential-function-based control scheme for non-holonomic multi-agent systems to prevent the local minimum problem. Int. J. Syst. Sci. 2015, 46, 2150–2164. [Google Scholar]
  34. Lee, J.; Nam, Y.; Hong, S.; Cho, W. New Potential Functions with Random Force Algorithms Using Potential Field Method. J. Intell. Robot. Syst. 2012, 66, 303–319. [Google Scholar]
  35. Leonard, N.E.; Fiorelli, E. Virtual leaders, artificial potentials and coordinated control of groups. In Proceedings of the 40th IEEE Conference on Decision and Control (Cat. No.01CH37228), Orlando, FL, USA, 4–7 December 2001; IEEE: New York, NY, USA, 2001; pp. 2968–2973. [Google Scholar]
  36. Fax, J.A.; Murray, R.M. Information Flow and Cooperative Control of Vehicle Formations. IEEE Trans. Automat. Contr. 2004, 49, 1465–1476. [Google Scholar]
  37. Olcay, E.; Lohmann, B.; Akella, M.R. An information-driven algorithm in flocking systems for an improved obstacle avoidance. In Proceedings of the 45th Annual Conference of the IEEE Industrial Electronics Society, IECON, Lisbon, Portugal, 14–17 October 2019; IEEE: New York, NY, USA, 2019; Volume 1, pp. 298–304. [Google Scholar]
  38. Lee, W.; Choi, G.-H.; Kim, T. Visibility graph-based path-planning algorithm with quadtree representation. Appl. Ocean. Res. 2021, 117, 102887. [Google Scholar]
  39. Wu, Z.; Huang, M.; Zhao, A.; Lan, Z. Urban Traffic Planning and Traffic Flow Prediction based on ulchis gravity model and Dijkstra algorithm. J. Phys. Conf. Ser. 2021, 1972, 012080. [Google Scholar]
  40. Shah, B.C.; Gupta, S.K. Long-Distance Path Planning for Unmanned Surface Vehicles in Complex Marine Environment. IEEE J. Ocean. Eng. 2020, 45, 813–830. [Google Scholar]
  41. Chen, X. Dynamic Path Planning of the UAV Avoiding Static and Moving Obstacles. J. Intell. Robot. Syst. 2020, 99, 909–931. [Google Scholar]
  42. Koenig, S.; Likhachev, M. Fast replanning for navigation in unknown terrain. IEEE Trans. Robot. 2005, 21, 354–363. [Google Scholar]
  43. Wagner, G.; Choset, H. M*: A complete multirobot path planning algorithm with performance bounds. In Proceedings of the 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems, San Francisco, CA, USA, 25–30 September 2011; IEEE: New York, NY, USA, 2011; pp. 3260–3267. [Google Scholar]
  44. Wagner, G.; Choset, H. Subdimensional expansion for multirobot path planning. Artif. Intell. 2015, 219, 1–24. [Google Scholar]
  45. Sabir, Z.; Said, S.B.; Al-Mdallal, Q.; Bhat, S.A. A reliable stochastic computational procedure to solve the mathematical robotic model. Expert Syst. Appl. 2024, 238, 122224. [Google Scholar]
  46. Hao, K.; Zhao, J.; Li, Z.; Liu, Y.; Zhao, L. Dynamic path planning of a three-dimensional underwater AUV based on an adaptive genetic algorithm. Ocean. Eng. 2022, 263, 112421. [Google Scholar] [CrossRef]
  47. Cui, Y.; Hu, W.; Rahmani, A. Multi-robot path planning using learning-based Artificial Bee Colony algorithm. Eng. Appl. Artif. Intell. 2024, 129, 107579. [Google Scholar]
  48. Noormohammadi-Asl, A.; Taghirad, H.D. Multi-goal motion planning using traveling salesman problem in belief space. Inf. Sci. 2019, 471, 164–184. [Google Scholar]
  49. Zhu, T. Maritime patrol tasks assignment optimization of multiple USVs under endurance constraint. Ocean. Eng. 2023, 285, 115445. [Google Scholar] [CrossRef]
  50. Sea, V.; Sugiyama, A.; Sugawara, T. Frequency-Based Multi-agent Patrolling Model and Its Area Partitioning Solution Method for Balanced Workload. In Integration of Constraint Programming, Artificial Intelligence, and Operations Research; van Hoeve, W.-J., Ed.; Springer International Publishing: Cham, Switzerland, 2018; pp. 530–545. [Google Scholar]
  51. Lin, Z.; Yue, M.; Chen, G.; Sun, J. Path planning of mobile robot with PSO-based APF and fuzzy-based DWA subject to moving obstacles. Trans. Inst. Meas. Control. 2022, 44, 121–132. [Google Scholar] [CrossRef]
  52. Jose, K.; Pratihar, D.K. Task allocation and collision-free path planning of centralized multi-robots system for industrial plant inspection using heuristic methods. Robot. Auton. Syst. 2016, 80, 34–42. [Google Scholar] [CrossRef]
  53. Gao, J.; Zheng, X.; Liu, P.; Yang, P.; Yu, J.; Dai, Y. APF-IBRRT*: A Global Path Planning Algorithm for Obstacle Avoidance Robots With Improved Iterative Search Efficiency. IEEE Access 2024, 12, 124740–124750. [Google Scholar] [CrossRef]
  54. Lu, M.-K.; Ge, M.-F.; Ding, T.-F.; Liu, Z.-W. SDF-Based Reinforcement Learning for Adaptive Path Planning and Formation Control of Multi-Agent Systems. IEEE Internet Things J. 2025, 1. [Google Scholar] [CrossRef]
  55. Alharthi, R.; Noreen, I.; Khan, A.; Aljrees, T.; Riaz, Z.; Innab, N. Novel deep reinforcement learning based collision avoidance approach for path planning of robots in unknown environment. PLoS ONE 2025, 20, e0312559. [Google Scholar] [CrossRef]
  56. Naito, Y.; Jimbo, T.; Odashima, T.; Matsubara, T. Task-priority Intermediated Hierarchical Distributed Policies: Reinforcement Learning of Adaptive Multi-robot Cooperative Transport. In Proceedings of the 2025 IEEE/SICE International Symposium on System Integration (SII), Munich, Germany, 21–24 January 2025; IEEE: New York, NY, USA, 2025; pp. 1556–1562. [Google Scholar]
  57. Zhao, J.; Wang, Z.; Lv, Y.; Na, J.; Liu, C.; Zhao, Z. Data-Driven Learning for H∞ Control of Adaptive Cruise Control Systems. IEEE Trans. Veh. Technol. 2024, 73, 18348–18362. [Google Scholar] [CrossRef]
  58. Santiago, A.; Huacuja, H.J.F.; Dorronsoro, B.; Pecero, J.E.; Santillan, C.G.; Barbosa, J.J.G.; Monterrubio, J.C.S. A Survey of Decomposition Methods for Multi-objective Optimization. In Recent Advances on Hybrid Approaches for Designing Intelligent Systems; Castillo, O., Melin, P., Pedrycz, W., Kacprzyk, J., Eds.; Springer International Publishing: Cham, Switzerland, 2014; pp. 453–465. [Google Scholar]
  59. Liu, J.; Yang, J.; Liu, H.; Tian, X.; Gao, M. An improved ant colony algorithm for robot path planning. Soft Comput. 2017, 21, 5829–5839. [Google Scholar] [CrossRef]
  60. Masehian, E.; Sedighizadeh, D. Multi-Objective PSO- and NPSO-based Algorithms for Robot Path Planning. AECE 2010, 10, 69–76. [Google Scholar] [CrossRef]
  61. Huang, L.; Zhou, M.; Hao, K. Non-Dominated Immune-Endocrine Short Feedback Algorithm for Multi-Robot Maritime Patrolling. IEEE Trans. Intell. Transport. Syst. 2020, 21, 362–373. [Google Scholar] [CrossRef]
  62. Sharma, M.; Voruganti, H.K. Multi-objective optimization approach for coverage path planning of mobile robot. Robotica 2024, 42, 2125–2149. [Google Scholar]
  63. Botros, A.; Wilde, N.; Sadeghi, A.; Alonso-Mora, J.; Smith, S.L. Regret-Based Sampling of Pareto Fronts for Multi-objective Robot Planning Problems. IEEE Trans. Robot. 2024, 40, 3778–3794. [Google Scholar]
  64. Dai, L.-L.; Pan, Q.-K.; Miao, Z.-H.; Suganthan, P.N.; Gao, K.-Z. Multi-Objective Multi-Picking-Robot Task Allocation: Mathematical Model and Discrete Artificial Bee Colony Algorithm. IEEE Trans. Intell. Transport. Syst. 2024, 25, 6061–6073. [Google Scholar] [CrossRef]
  65. Gong, T.; Tuson, A.L. Differential Evolution for Binary Encoding. In Soft Computing in Industrial Applications; Springer: Berlin/Heidelberg, Germany, 2007; pp. 251–262. [Google Scholar]
  66. Pareto, V.; Cours, D. Economic Politique; Rouge: Lausanne, Switzerland, 1896. [Google Scholar]
  67. Yu, X.; Liu, N.; Huang, W.; Qian, X.; Zhang, T. A Node Deployment Algorithm Based on Van Der Waals Force in Wireless Sensor Networks. Int. J. Distrib. Sens. Netw. 2013, 9, 505710. [Google Scholar]
  68. Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  69. Li, C. Global path planning based on a bidirectional alternating search A* algorithm for mobile robots. Ind. Eng. 2022, 168, 108123. [Google Scholar]
  70. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef]
  71. Srinivas, N.; Deb, K. Muiltiobjective Optimization Using Nondominated Sorting in Genetic Algorithms. Evol. Comput. 1994, 2, 221–248. [Google Scholar] [CrossRef]
  72. Deb, K.; Pratap, A.; Agarwal, S.; Meyarivan, T. A fast and elitist multiobjective genetic algorithm: NSGA-II. IEEE Trans. Evol. Comput. 2002, 6, 182–197. [Google Scholar] [CrossRef]
  73. Gong, M.; Jiao, L.; Du, H.; Bo, L. Multiobjective Immune Algorithm with Nondominated Neighbor-Based Selection. Evol. Comput. 2008, 16, 225–255. [Google Scholar] [CrossRef]
  74. Su, Y.; Luo, N.; Lin, Q.; Li, X. Many-objective optimization by using an immune algorithm. Swarm Evol. Comput. 2022, 69, 101026. [Google Scholar]
  75. Yang, C.; Ding, J. Constrained dynamic multi-objective evolutionary optimization for operational indices of beneficiation process. J. Intell. Manuf. 2019, 30, 2701–2713. [Google Scholar]
Figure 1. Control architecture diagram of the multi-robot patrolling system.
Figure 1. Control architecture diagram of the multi-robot patrolling system.
Electronics 14 01222 g001
Figure 2. The abstract map of the expo park environment. P 1 to P 20 represent the patrolling points, R 1 to R 3 represent the patrolling robots, and v 1 to v 3 represent the speed of the patrolling robots.
Figure 2. The abstract map of the expo park environment. P 1 to P 20 represent the patrolling points, R 1 to R 3 represent the patrolling robots, and v 1 to v 3 represent the speed of the patrolling robots.
Electronics 14 01222 g002
Figure 3. The flow chart of VDWF-MOIA algorithm.
Figure 3. The flow chart of VDWF-MOIA algorithm.
Electronics 14 01222 g003
Figure 4. A new encoding scheme of a double antibody (with virtual points).
Figure 4. A new encoding scheme of a double antibody (with virtual points).
Electronics 14 01222 g004
Figure 5. Plan obstacle avoidance path from S to T through PCM-VRAOA: The length of path 1 is longer than the length of path 2, so path 2 is the final obstacle avoidance path chosen.
Figure 5. Plan obstacle avoidance path from S to T through PCM-VRAOA: The length of path 1 is longer than the length of path 2, so path 2 is the final obstacle avoidance path chosen.
Electronics 14 01222 g005
Figure 6. The diagram of the calculation of the global path cost matrix through PCM-VRAOA.
Figure 6. The diagram of the calculation of the global path cost matrix through PCM-VRAOA.
Electronics 14 01222 g006
Figure 7. The flow chart of PCM-VRAOA.
Figure 7. The flow chart of PCM-VRAOA.
Electronics 14 01222 g007
Figure 8. The flow chart of Van der Waals force mechanism.
Figure 8. The flow chart of Van der Waals force mechanism.
Electronics 14 01222 g008
Figure 9. The schematic diagram of the separating matching and crossing process. (a) Divide the first part of the genes into gene fragments according to the second part of the genes. (b) Perform two-point crossover on the matched gene fragments. (c) Add the remaining patrol points in order to the offspring antibody child. (d) Perform cross operation on the second part of genes.
Figure 9. The schematic diagram of the separating matching and crossing process. (a) Divide the first part of the genes into gene fragments according to the second part of the genes. (b) Perform two-point crossover on the matched gene fragments. (c) Add the remaining patrol points in order to the offspring antibody child. (d) Perform cross operation on the second part of genes.
Electronics 14 01222 g009aElectronics 14 01222 g009b
Figure 10. The heat map of pc and pm (HV indicator).
Figure 10. The heat map of pc and pm (HV indicator).
Electronics 14 01222 g010
Figure 11. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 1.
Figure 11. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 1.
Electronics 14 01222 g011
Figure 12. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 2.
Figure 12. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 2.
Electronics 14 01222 g012
Figure 13. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 3.
Figure 13. Comparison of HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 3.
Electronics 14 01222 g013
Figure 14. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 1 in 50 experimental tests.
Figure 14. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 1 in 50 experimental tests.
Electronics 14 01222 g014
Figure 15. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 2 in 50 experimental tests.
Figure 15. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 2 in 50 experimental tests.
Electronics 14 01222 g015
Figure 16. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 3 in 50 experimental tests.
Figure 16. Box plots of the HV indicator of VDWF-MOIA, NSGA-II, NNIA, and NSGA algorithms applied on Map 3 in 50 experimental tests.
Electronics 14 01222 g016
Figure 17. Examples of the multi-robot patrolling scenario on Map 1. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Figure 17. Examples of the multi-robot patrolling scenario on Map 1. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Electronics 14 01222 g017
Figure 18. Examples of the multi-robot patrolling scenario on Map 2. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Figure 18. Examples of the multi-robot patrolling scenario on Map 2. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Electronics 14 01222 g018
Figure 19. Examples of the multi-robot patrolling scenario on Map 3. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Figure 19. Examples of the multi-robot patrolling scenario on Map 3. (a) A pareto solution with a shorter total path length. (b) A pareto solution with a better load balancing value.
Electronics 14 01222 g019
Table 1. Comparison of different types of multi-robot path planning algorithms.
Table 1. Comparison of different types of multi-robot path planning algorithms.
AlgorithmTypeAdvantageDrawback
Dijkstra/A*graph-based searchensure the shortest pathhigh computational complexity
GAmetaheuristic algorithmstrong global search abilitycomplex parameter tuning
APFlocal planning algorithmstrong dynamic real-time performanceprone to fall into local optimum
SDF-FPPhierarchical reinforcement learningsuitable for unknown environmentslimited dynamic obstacle avoidance capability
APF-IBRRT*hybrid algorithmimprove the search efficiency in narrow environmentslarge memory consumption
Deep Q-learningdeep reinforcement learningadapt to complex environmentslong training time
Table 2. Parameter settings for maps.
Table 2. Parameter settings for maps.
MapPatrol Point NumberObstacle NumberRobot Number
Map 12023
Map 23034
Map 35056
Table 3. Analysis of the relationship between population size and running time. Fix pc = 0.9, pm = 0.1.
Table 3. Analysis of the relationship between population size and running time. Fix pc = 0.9, pm = 0.1.
PopsizeHVRunning Time
500.616725.97
1000.652648.75
1500.654761.11
2000.662577.46
Table 4. Comparison of the running times of the algorithms on different maps (in seconds).
Table 4. Comparison of the running times of the algorithms on different maps (in seconds).
MapMOIA w/PCM-VRAOAMOIA
w/A*
MOIA
w/BAS-A*
MOIA
w/RRT*
Map 150.94 ± 2.4016.61 ± 0.9016.53 ± 1.5266.39 ± 8.47
Map 2265.70 ± 6.49106.99 ± 5.2495.85 ± 7.42383.26 ± 31.65
Map 32302.03 ± 298.29470.79 ± 46.46437.56 ± 39.64855.12 ± 50.31
Table 5. Comparison of the total path length of the algorithms on different maps.
Table 5. Comparison of the total path length of the algorithms on different maps.
MapMOIA w/PCM-VRAOAMOIA
w/A*
MOIA
w/BAS-A*
MOIA
w/RRT*
Map 1592.11 ± 87.35781.23 ± 93.38706.70 ± 90.51824.83 ± 92.65
Map 2773.93 ± 148.771136.80 ± 143.67958.84 ± 135.711225.33 ± 136.31
Map 31193.24 ± 200.531390.96 ± 229.771287.47 ± 188.641446.53 ± 166.13
Table 6. Comparison of the load balancing degree of the algorithms on different maps.
Table 6. Comparison of the load balancing degree of the algorithms on different maps.
MapMOIA w/PCM-VRAOAMOIA
w/A*
MOIA
w/BAS-A*
MOIA
w/RRT*
Map 112.34 ± 6.1118.90 ± 6.5816.04 ± 5.5537.96 ± 8.53
Map 28.69 ± 4.9716.56 ± 3.6512.41 ± 5.6240.88 ± 11.28
Map 39.28 ± 5.2418.71 ± 4.9317.26 ± 5.3727.63 ± 10.34
Table 7. Parameters of applied algorithms.
Table 7. Parameters of applied algorithms.
ItemValueAlgorithm
Mutation probability0.1All
Crossover probability0.9All
Size of memory cell20VDWF-MOIA
Size of clone population80NNIA, MaIA
Maximum size of active population20NNIA
Maximum size of dominant population30NNIA
Table 8. t-Test results on HV indicator.
Table 8. t-Test results on HV indicator.
MapVDWF-MOIA vs. MaIAVDWF-MOIA vs. NSGAIIVDWF-MOIA vs. NNIAVDWF-MOIA vs. NSGA
Map 1 7.1844 × 10 20 2.2223 × 10 36 2.8432 × 10 42 4.0165 × 10 52
Map 2 3.3609 × 10 4 6.6566 × 10 14 6.6312 × 10 32 7.9931 × 10 25
Map 3 1.3159 × 10 3 1.6494 × 10 6 2.2426 × 10 31 1.5262 × 10 34
Table 9. Application result of multi-objective patrolling executed by the multi-robot system.
Table 9. Application result of multi-objective patrolling executed by the multi-robot system.
Map f 1 f 2
Map 1(a)485.3502.742
(b)501.0601.692
Map 2(a)646.6968.777
(b)683.7585.086
Map 3(a)902.71315.178
(b)957.18211.685
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Guo, T.; Huang, L.; Han, H. An Effective Path Planning Method Based on VDWF-MOIA for Multi-Robot Patrolling in Expo Parks. Electronics 2025, 14, 1222. https://doi.org/10.3390/electronics14061222

AMA Style

Guo T, Huang L, Han H. An Effective Path Planning Method Based on VDWF-MOIA for Multi-Robot Patrolling in Expo Parks. Electronics. 2025; 14(6):1222. https://doi.org/10.3390/electronics14061222

Chicago/Turabian Style

Guo, Tianyi, Li Huang, and Hua Han. 2025. "An Effective Path Planning Method Based on VDWF-MOIA for Multi-Robot Patrolling in Expo Parks" Electronics 14, no. 6: 1222. https://doi.org/10.3390/electronics14061222

APA Style

Guo, T., Huang, L., & Han, H. (2025). An Effective Path Planning Method Based on VDWF-MOIA for Multi-Robot Patrolling in Expo Parks. Electronics, 14(6), 1222. https://doi.org/10.3390/electronics14061222

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

Article Metrics

Back to TopTop