Next Article in Journal
Unoccupied-Aerial-Systems-Based Biophysical Analysis of Montmorency Cherry Orchards: A Comparative Study
Previous Article in Journal
Measurement-Based Tapped Delay Line Channel Modeling for Fixed-Wing Unmanned Aerial Vehicle Air-to-Ground Communications at S-Band
Previous Article in Special Issue
Deep Reinforcement Learning-Driven Collaborative Rounding-Up for Multiple Unmanned Aerial Vehicles in Obstacle Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Multi-Robot Path Planning Algorithm for Collaborative Mapping under Communication Constraints

by
Chengyu Zhou
,
Junxiang Li
,
Meiping Shi
and
Tao Wu
*
College of Intelligence Science and Technology, National University of Defense Technology, Changsha 410073, China
*
Author to whom correspondence should be addressed.
Drones 2024, 8(9), 493; https://doi.org/10.3390/drones8090493
Submission received: 7 August 2024 / Revised: 10 September 2024 / Accepted: 15 September 2024 / Published: 17 September 2024

Abstract

:
In extensive outdoor collaborative exploration tasks, multiple robots require efficient path planning methods to ensure rapid and comprehensive map construction. However, current collaborative mapping algorithms often integrate poorly with path planning, especially under limited communication conditions. Such conditions can complicate data exchange, leading to inefficiencies and missed areas in real-world environments. This paper introduces a path planning approach specifically designed for distributed collaborative mapping tasks, aimed at enhancing map completeness, mapping efficiency, and communication robustness under communication constraints. We frame the entire task as a k-Chinese Postman Problem (k-CPP) and optimize it using a genetic algorithm (GA). This method fully leverages topology maps to efficiently plan subpaths for multiple robots, ensuring thorough coverage of the mapping area without the need for prior navigation maps. Additionally, we incorporate communication constraints into our path planning to ensure stable data exchange among robots in environments with only short-range communication capabilities. Field experiment results highlight the superior performance of our method in terms of stability, efficiency, and robust inter-robot communication.

1. Introduction

With the rapid advancements in technology, automated and intelligent robotic systems are increasingly crucial in large-scale outdoor environments [1,2], particularly in fields such as disaster relief [3] and military reconnaissance [4]. In these applications, groups of robots can significantly enhance task efficiency and safety through collaborative efforts. However, when executing complex outdoor collaborative exploration and mapping tasks, these robotic groups face multiple technical challenges.
A core technical challenge in collaborative mapping tasks is establishing accurate measurement constraints or loop closures [5] among robots to achieve precise map stitching. In single-robot loop closure detection, initial pose estimates at the time of detection can be derived from odometry measurements [6]. In multi-robot SLAM systems, each sub-robot’s SLAM estimates are independent and stored under their own local coordinate systems. Therefore, the initial pose transformations between robots are unknown and can only be estimated through the perception data of two robots, combining local maps into a global situation. During this process, repetitive or simple scenes can cause problems in loop closure detection, affecting the integration of the map.
Another practical challenge in collaborative mapping is resource management [7]. In distributed collaborative mapping systems, the computational and communication capabilities of mobile robots are limited. When a large number of robots interact simultaneously, it can easily reach the communication bottleneck. In large-scale outdoor environments, factors such as building obstructions and weather conditions, along with the inherent distance limitations of communication systems, make it difficult for robots to maintain stable long-term communication between them. However, changes in environmental factors are not easily quantifiable and directly integrated into models. To simplify the problem and focus on the main challenge (i.e., maintaining effective communication connections between robots), we choose to focus on communication distance.
Furthermore, due to the lack of long-distance data exchange capabilities, traditional planning and exploration algorithms struggle to perceive unexplored areas. This limitation makes it difficult for robots to achieve efficient path coverage and data integration in vast outdoor environments. In this context, utilizing satellite imagery as a tool for global guidance becomes particularly important. Satellite imagery provides a macroscopic method for regional exploration [8], aiding planning algorithms to optimize exploration routes and guiding robots to areas not yet covered, thereby significantly improving the completeness and efficiency of mapping.
Facing the challenges of collaborative mapping, previous algorithms have mainly focused on multi-sensor fusion [9], robust loop closure detection methods [10], and building distributed mapping systems [11]. While these methods have achieved certain successes in improving the efficiency and accuracy of mapping algorithms, they often overlook the crucial role of path planning algorithms in guiding collaborative mapping tasks. If the initial planning can guide multiple robots to effectively meet and exchange data during the mapping process, stable loop closure detection zones can be formed, significantly reducing the processing pressure on backend collaborative optimization algorithms.
In this paper, we propose a path planning algorithm tightly coupled with the backend of collaborative mapping. Firstly, we focus on efficiently establishing a complete map, optimizing each robot’s path coverage through precise task assignments and planning. Secondly, to address the instability of loop closure detection locations, we have developed an algorithm that provides predetermined, loop closure-optimized meeting points for robots during the planning phase, ensuring the accuracy and effectiveness of path planning. Lastly, addressing the challenge of limited communication distance, we have designed specific constraints that allow for two or more robots to meet under certain spatiotemporal conditions for efficient data exchange.
The contributions of this study are reflected in the following aspects:
  • A multi-robot path planning framework and algorithm implementation tailored for collaborative mapping tasks are proposed. This algorithm introduces loop closure constraints at the planning stage, ensuring robots can meet at optimal positions to maintain map completeness and efficient mapping while also stabilizing inter-robot loop closure detection.
  • Communication improvement methods at the planning level are presented. By designing a communication strategy, we ensure that robots can maintain stable communication over long periods under conditions of a limited communication range, facilitating effective data exchange.
  • Experimental validation based on multi-scale maps is presented. Experiments have demonstrated the effectiveness of the path planning algorithm and its compatibility with collaborative mapping algorithms.
The structure of this paper is as follows: Section 2 will delve into the related work, analyze the limitations of existing technologies, and highlight the advantages of our method in comparison; Section 3 will detail the application of the improved algorithm, focusing on its implementation in the k-Chinese Postman Problem and the enhancements made to improve communication efficiency; Section 4 will demonstrate the application results of our method on real-world map data through comparisons with other existing technologies; and finally, Section 5 will summarize the main contributions of this study and discuss possible future research directions.

2. Related Work

2.1. Multi-Robot Cooperative Localization and Mapping

Multi-robot cooperative SLAM technology enables a group of robots to navigate through unknown environments, efficiently constructing complete maps of target areas through data exchange.
Table 1 summarizes the current mainstream collaborative mapping algorithms, highlighting differences in sensor types and platforms, loop closure detection methods, data interaction techniques, and integration with path planning algorithms. It is evident that most algorithms utilize multiple sensors mounted on heterogeneous platforms, such as unmanned vehicles or drones, including LIDAR, cameras, and IMUs, to achieve data fusion and precise mapping. Additionally, these algorithms employ various efficient and practical loop closure detection technologies, such as NetVLAD [12], Bag-of-Words, Scan Context [13], and LIDAR-Iris [14], enabling the algorithms to establish effective constraints independently of external inputs within multi-robot systems.
However, these algorithms typically require substantial time to search for potential loop closure areas during implementation. Especially in mapping areas with multiple regions of high redundancy, inaccurate loop closure detection can likely lead to incorrect loop constraints, resulting in mapping failures [15]. Although many such issues can be prevented through early stage path planning algorithms, few examples of the current collaborative mapping algorithms tightly integrate path planning with loop closure detection. This separation may limit improvements in overall task efficiency. Thus, tightly integrating path planning with mapping algorithms and optimizing the overall process of collaborative mapping is a crucial direction that requires further research in the field.
Table 1. Representative collaborative mapping algorithms.
Table 1. Representative collaborative mapping algorithms.
MethodsSensorsPlatformData InteractionData AssociationNavigation
DOOR-SLAM [16]StereoUAVDecentralizedNetVLAD descriptor [12]
Kimera-Multi [17]Stereo, IMUUGVDecentralizedBag-of-words
COVINS [18]Mono, IMUUAVCentralizedBag-of-words
[19]Stereo, IMU, GPSUAVCentralizedBag-of-words
DiSCo-SLAM [20]Lidar, IMUUGVDecentralizedScan Context descriptor [13]
LAMP 2.0 [21]LidarUGVCentralizedFlexible selection
Swarm-SLAM [22]Stereo, LidarUGVDecentralizedScan Context descriptor
DCL-SLAM [23]Lidar, IMUUGVDecentralizedLIDAR-Iris descriptor [14]
RDC-SLAM [24]LidarUGVDecentralizedDELIGHT descriptor [25]
MRSLAM [26]Lidar, IMUUGVDecentralizedRING++ descriptor [27]
[8]Lidar, IMU, GPSUGVDecentralizedScan Context descriptor

2.2. Multi-Robot Path Planning

Multi-robot path planning is a fundamental issue in practical robotic applications, such as warehouse automation [28], multi-robot formations [29], and inspection [30]. These applications require orchestrating each robot’s path to meet diverse needs and constraints [31].
Most current multi-robot path planning algorithms simplify the problem into well-studied issues based on specific constraints. For example, [32] uses an independence-checking A* algorithm to reduce the branching factor in the search process, simplifying the search space to quickly find the optimal solution in cooperative pathfinding. In [33], the latency issues in multi-robot cooperative path planning are addressed by using a Boolean satisfiability (SAT) solver as an optimization tool. This exploits the solver’s ability to quickly solve smaller instances, allowing for it to find optimal solutions promptly. As multi-robot path planning with collision-free constraints becomes more complex, [34] utilizes the Increasing Cost Tree Search (ICTS) algorithm, which leverages its multi-level search structure and state-space pruning capabilities to solve complex path planning problems in multi-agent systems, optimizing path costs while significantly enhancing the speed and precision of solving such problems.
Following this line of thought, this study delves into the core constraint issues within distributed collaborative mapping algorithms, with a particular focus on how to enhance communication quality and the stability of loop closure constraints while maintaining map integrity and mapping efficiency. To effectively address this issue, we introduce the k-Chinese Postman Problem (k-CPP) as the foundational optimization framework for path planning in multi-robot systems. The primary goal of the k-CPP is to determine a set of paths that ensures each robot covers its assigned must-visit nodes, thereby maximizing the system’s coverage efficiency. Additionally, the problem focuses on minimizing the total travel distance of all robots or, in certain applications, maximizing path efficiency.
For instance, [35] adopts the min–max k-Chinese Postman Problem (MM k-CPP) approach to solve the global coverage path planning problem for multi-autonomous UAVs inspecting linear infrastructure. This problem is structured as a variant of the MM k-CPP and tested with different starting positions. By assigning different costs to edges, the inspection time is optimized. In [36], a road-network search path planning algorithm is proposed to guide multiple autonomous vehicles efficiently to visit every identified road on the map. The authors introduced an approximation algorithm based on nearest insertion and auction to improve the solution process of the k-CPP, making it suitable for general types of road maps, including disconnected roads and the operational and physical constraints of unmanned aerial vehicles (UAVs). In [8], the solution process of the MM k-CPP to multi-robot path planning is applied for the first time, transforming the path planning problem into a graph optimization issue and implementing an end-to-end collision-free robotic navigation method without establishing a navigation map. In [37], the MSTC* algorithm is presented, which improves efficiency by considering physical constraints, like terrain traversability and load capacity. This method significantly outperforms the existing Spiral-STC-based approaches by optimizing workload distribution and minimizing coverage completion time.
Given the current challenges and needs in the field of distributed collaborative mapping and path planning, this paper proposes an innovative integrated approach. We tightly couple the k-Chinese Postman Problem (k-CPP) with the core requirements of collaborative mapping algorithms, focusing on optimizing path selection and information exchange strategies in multi-robot systems during distributed mapping tasks. This integrated strategy not only enhances the robots’ capability to share information more efficiently, updating and sharing map data effectively, but also ensures high precision in both path planning and mapping through precise path planning.

3. System Architecture

This study proposes a path planning method for distributed collaborative mapping tasks, as illustrated in Figure 1. This method utilizes satellite maps of outdoor environments as prior knowledge to guide k autonomous robots in exploring and reconstructing the environment. We model the multi-robot path planning issue as the k-Chinese Postman Problem (k-CPP), effectively addressing issues of map incompleteness and low mapping efficiency during the mapping process. Because this problem is NP-hard, our research introduces a genetic algorithm with loop closure and communication penalty factors to solve it. This method optimizes the solution to the k-Chinese Postman Problem (k-CPP), enhancing data association at predetermined loop closure locations and ensuring communication stability at critical meeting points.

3.1. Prior Information Processing

We use satellite maps as prior knowledge for the algorithm, guiding k robots in collaborative exploration of the area. The satellite maps clearly display roads, their intersections, and visible obstacles that block roads. When such obstacles are detected, we modify the road network by splitting the affected roads into two segments, and the robots are programmed to turn back when encountering these blockages. This allows for the extraction of latitude and longitude information to construct a road network topology map while effectively accounting for significant obstacles.
We define the road network topology graph G = ( V , E ) , as shown in Figure 2, as an undirected connected graph that provides the foundational framework for robot exploration. K ( K 2 ) represents the number of robots, the vertex set V = { v 1 , , v n } represents the n road intersections in the network, and the edge set E = { e 1 , , e m } represents the m passable roads in the network. Additionally, the loop closure edge set B = { b 1 , , b t } is a subset of the edge set E, identifying predetermined loop closure locations for the robots. These locations are specifically used to guide robots to form stable meeting points along appropriate paths. The specific location of each road intersection v i is provided by the Global Navigation Satellite System (GNSS), and each edge’s weight w m represents the estimated distance of the road.
To calculate the weight of an edge, we extract the latitude and longitude coordinates of the two nodes of the edge from the satellite map and use the Haversine formula from spherical trigonometry to calculate the length of the edge. We assume the two vertices of edge e m are v x and v y , with geographic coordinates ( l a t x , l o n x ) and ( l a t y , l o n y ) , respectively. Δ ϕ and Δ λ represent the differences in latitude and longitude between the two vertices, calculated as follows:
Δ ϕ = l a t y l a t x × π 180 , Δ λ = l o n y l o n x × π 180 .
We apply the Haversine formula:
a = sin 2 Δ ϕ 2 + cos ( ϕ 1 ) cos ( ϕ 2 ) sin 2 Δ λ 2 , c = 2 · arctan 2 a , 1 a .
Here, a represents the square of the half-chord length between the two points, and c is used to calculate the angular distance in radians.
The average radius of the Earth is approximately R = 6371 kilometers. Therefore, the great-circle distance d between two points is calculated as follows:
d = R · c .
We use d as the weight of the edges in the undirected graph, and we have designated the starting points of the robots at the nodes of the graph.

3.2. Mathematical Modeling

To achieve map-directed path planning, this study models the problem as a constrained min–max Cost k-Chinese Postman Problem (k-CPP) [38], which is a classic traversal problem in graph theory. In this model, each robot must find the shortest path within the connected graph G to ensure that all the edges are covered at least once. Additionally, according to the constraints, each robot’s subpath must include designated loop closure edges, which need to be traversed by two different robots. The set of all the possible solutions that meet the constraints is denoted as M = { P 1 , P 2 , } , where each solution set P = { s p 1 , s p 2 , , s p K } contains K subpaths for the robots. The set P forms a complete path covering all the edges of graph G with the shortest length of the longest subpath, as shown in Figure 3.
In this problem, to achieve the highest coverage efficiency, the objective function is set to find the solution set P o p t that minimizes the longest path. First, we identify the longest subpath in P:
L max ( P ) = max s p P e s p ω ( e ) · x e .
The complete formulation for this problem is given as follows, where P o p t M and L max ( P o p t ) meets the following condition:
L max ( P opt ) = min P M L max ( P ) .
Here, s p represents the robot’s subpath, w ( e ) denotes the cost (road length) of edge e in graph G within subpath s p , and x e is the number of times edge e is traversed in subpath s p .
The robot subpaths must also satisfy the following constraints.
Constraint 1: P must include each edge at least once to ensure that the map can be fully covered:
s p P x e 1 e E .
Here, E represents the set of edges in the undirected graph.
Constraint 2: This is to ensure that each robot’s path within the graph is connected, meaning that it is possible to travel continuously from the start to the end via the selected edges. For each robot’s path s p i , the following condition must be satisfied:
j = 1 n x i j p j = 1 n x j i p = 0 , i V , p { 1 , , K } .
Here, the decision variables x i j and x j i represent the edges leaving and entering node i, respectively, and can take values of 0 or 1. If x i j = 1 , then edge e i j is included in the optimal route for s p i ; if x i j = 0 , then edge e i j is not included in the route. This constraint ensures that for each node i, the number of edges leaving the node is equal to the number of edges entering it, thereby guaranteeing the connectivity of the path within the network. This balance is crucial for maintaining a continuous and feasible route for each robot, avoiding any breaks in their journey across the network.
Constraint 3: This is the common starting point for all robots. Assume s is the common starting point. For all p { 1 , , K } , it is required that
j = 1 n x s j p = 1 p { 1 , , K } , x s j p = 1 j V , p { 1 , , K } .
Here, x s j p indicates whether the edge from the common starting point s to vertex j is selected as part of the path for the p -th robot. If x s j p = 1 , then the edge is included; if x s j p = 0 , the edge is not included. This constraint ensures that each robot starts from the same point, ensuring a uniform initial position for all the robots.
The initial three constraints outlined are integral to the traditional k-Chinese Postman Problem (k-CPP), which ensure the basic functionality such as path continuity and coverage of all the required edges within the graph. These constraints form the foundational framework necessary for any effective path planning algorithm within a connected graph environment. Following these traditional constraints, we introduce additional, specific constraints tailored to address the unique demands of collaborative robotic mapping. These new constraints are designed to optimize inter-robot communication and coordination, reflecting the practical requirements of deploying multiple robots in complex and dynamic environments.
Constraint 4: To establish stable loop closure detection among robots, this project introduces the loop closure edge set B as a constraint for common edges between two robots, ensuring that for each edge b in the loop closure edge set B, it is included in the paths of at least two different robots:
s p P x b 2 b B .
Here, x b is the number of times the loop closure edge b is included in the subpaths.
Constraint 5: To ensure communication quality, the distance between two robots when reaching the anticipated loop closure edge b must be less than the communication distance threshold d c .
If robots traverse the loop closure edge b in the same direction, under the assumption that both robots travel at uniform and equal speed, the distance remains nearly constant, and it is only necessary to ensure that the distance is less than the communication threshold:
| | Dis ( b ) i Dis ( b ) j | | < d c .
If the robots traverse the loop closure edge b in opposite directions, the distance between the two robots will decrease gradually; it is necessary to ensure that the robots meet at the predetermined loop closure edge to exchange data:
| | Dis ( b ) i Dis ( b ) j | | < α · d c + w ( b ) .
Here, i j represents the indices of the subpaths that include the loop closure edge b where i j . D i s ( b ) i denotes the distance traveled by the robot on subpath i to reach the loop closure edge b, and α is an empirical parameter.
Compared to the traditional k-CPP, where a subpath s p is usually required to be a closed loop (i.e., the path’s start and endpoint are the same), our approach modifies this constraint to suit practical applications better. Recognizing that robots do not always need to return to their starting point to achieve complete network coverage, our algorithm relaxes the closed loop requirement to enhance overall efficiency. This adjustment allows for the closed path condition to be applied selectively, depending on the specific needs of the task. Consequently, the requirement for robots to return to the starting point after completing their mapping assignments can be flexibly included or excluded, thereby optimizing operational efficiency and adaptability.

3.3. Genetic Algorithm Framework

The k-Chinese Postman Problem (k-CPP) is NP-hard, resulting in a vast solution space that makes finding an optimal solution within realistic time constraints impractical. As a result, exhaustive search methods are not feasible, necessitating the use of heuristic algorithms. While various heuristic approaches perform well for the single-agent Chinese Postman Problem (CPP), the complexity of the solution space increases significantly in the k-CPP. Genetic algorithms (GAs), with their robust global search capabilities, can theoretically explore the entire solution space. By designing suitable gene encoding, the solution space can be effectively reduced, and specific constraints required for collaborative mapping can be incorporated via penalty functions.
Genetic algorithms are a widely used metaheuristic for optimization and search problems, simulating natural evolutionary processes such as genetic mutation, natural selection, and gene recombination to iteratively improve solutions. Initially, a random initial population, i.e., a series of possible path combinations, is generated. In each generation, it evaluates the fitness of each individual in the population, selecting the fitter individuals for reproduction. Selected individuals produce a new generation through crossover (gene recombination) and mutation (random gene alteration). This process is repeated until a predetermined number of iterations or a fitness threshold is reached. The algorithm framework of this paper is illustrated in Algorithm 1.
In implementing genetic algorithms, determining how to design genetic encoding and construct a fitness evaluation function is crucial, as these elements have a critical impact on the efficiency of the algorithm and the quality of the solutions it produces. To ensure a comprehensive understanding, we will detail the sequential processes involved, including genetic encoding, the selection of the initial population, the methods for calculating the fitness function, the criteria for population selection, and the techniques for gene recombination, with a particular emphasis on gene design and the fitness evaluation function.
Algorithm 1 Genetic algorithm for multi-robot path planning
Require: Road network graph G = ( V , E ) , loop edges B, number of robots R, population
  size P, maximum generations G m a x
Ensure: Optimal multi-robot path planning scheme
  1:  Initialize population P with chromosomes representing path allocations for R robots
  2:  for  g = 1 G m a x  do
  3:  for each chromosome c P  do
  4:     Compute fitness fitness ( c ) considering:
      - Total path coverage
      - Path length equality among robots
      - Communication link stability based on loop edges B
  5:  end for
  6:  Selection operation: Employ a rank-based selection to choose parent chromosomes
  7:  Crossover operation: Use ordered crossover to create offspring from parents
  8:  Mutation operation: Introduce mutations into the offspring to enhance diversity
  9:  Replace the least fit chromosomes in P with new offspring
10:  If any chromosome meets the desired fitness threshold, then break
11:  end for
12:  return Optimal chromosome representing the path allocation scheme
Genetic encoding should succinctly reflect the problem’s key variables. In this study, we employ genetic algorithms to address the task allocation problem for robots. Specifically, each road that needs to be traversed is viewed as an individual task assigned to a specific robot. Thus, genetic encoding is designed here to directly represent the paths of the robots in the undirected graph. During the operation of the genetic algorithm, through crossover operations, we can effectively build and adjust each robot’s task set to optimize the overall task distribution.
In the algorithm, the chromosome’s gene sequence is designed as a string (shown in Figure 4). Edge genes represent all edges in the undirected graph, loop closure edge genes represent predetermined meeting locations for two robots that need to be traversed by at least two robots, and boundary genes are used to differentiate subpaths between different robots. Unlike [39], the length of the chromosome is set to L = m + B + k 1 , where m is the number of edges in the graph, B is the number of loop closure edges, and k is the number of robots, with k 1 representing the number of boundary genes. This genetic encoding makes it easy for crossover and mutation operators to produce new solutions.
Based on the structure of genetic encoding, we have adopted a specific method for gene initialization to ensure that each subpath contains at least one edge gene at initialization, thus establishing a correct genetic structure. The procedure involves initially randomizing the edge genes and then randomly inserting delimiter genes, ensuring they do not appear at the beginning or end of the sequence or adjacent to one another. This approach guarantees that the initial population covers all possible correct gene combinations, which not only prevents the omission of solutions but also helps to accelerate the convergence speed of the algorithm.
Designing the fitness function is a critical step in solving optimization problems, requiring careful consideration of the problem’s goals and related constraints. In this study, the fitness function primarily targets two objectives: minimizing the length of the longest subpath and optimizing the communication distance when robots reach expected meeting points. Because Constraints 1 and 2 have been considered during the genetic design phase, the fitness function focuses on these two optimization objectives.
Specifically, the fitness function evaluates the maximum length of each robot’s path to ensure the overall task efficiency, aiming to reduce the total time required to complete all the tasks. Additionally, the function considers the communication distance of robots at predetermined meeting points, ensuring effective communication at these critical points to enhance task execution reliability and collaborative efficiency.
Unlike [8], the fitness function in this paper is set as the sum of the longest subpath length plus a communication penalty factor C, where a smaller value of the fitness function indicates shorter planned paths and higher system operational efficiency. This combination has been proven in experiments to not only filter out optimal paths that meet constraints but also balance the lengths between subpaths:
F = max s p P e s p ω ( e ) · x e + C .
Here, F represents the fitness of a gene, and C is the communication penalty factor. The penalty factor C is calculated based on the following formula:
C = 0 , if d com d thresh / 2 β · d com , if d thresh / 2 < d com d thresh γ + λ · d com d thresh , if d com > d thresh
where d com represents the actual distance between the robots when they meet to exchange data; d thresh is the distance threshold; and β , γ , and λ are constants that control the penalty behavior. When the distance between robots is less than or equal to half of the threshold d thresh / 2 , no penalty is applied. When the distance falls between half the threshold and the threshold itself, a smaller penalty is applied with the factor β . If the distance exceeds the threshold, a larger penalty starting with γ is applied, with an additional linear increase determined by λ . In this penalty function, d thresh / 2 serves as an empirical parameter, selected based on practical experience and system requirements.
In this study, the penalty factor C ensures that two robots can successfully meet on designated road sections to exchange critical frame data. This is achieved by checking whether the path set P meets Constraint 5, that is, whether the robots achieve spatiotemporal coincidence on the loop closure section. If this condition is met, the path set is considered valid; if not, a larger penalty is applied to the path set, thereby reducing its probability of selection in the genetic algorithm.
When calculating fitness, we first need to determine the connections between discrete task segments represented by genes. Because the genes represent specific road segments, it is necessary to calculate the shortest path from one edge to another to achieve effective segment connection. This is performed by transforming the problem into a shortest path problem from one path point to another, allowing for the use of Dijkstra’s algorithm to find the shortest paths between these points.
After calculating the fitness of the population in our genetic algorithm, considering that fitness values are generally large and densely distributed, we adopt the rank selection method to optimize the selection process. This method sorts all the genes in descending order of fitness and determines the selection probability of each gene based on its rank, ensuring that individuals with higher fitness have a higher chance of being carried over to the next generation. Additionally, we implement an elitism preservation mechanism, which, by directly preserving the best-performing individuals in each iteration, not only accelerates the convergence speed of the algorithm but also enhances the stability and genetic diversity of the population. This approach ensures that high-fitness individuals are not lost during the random selection process.
For solving the k-Chinese Postman Problem (k-CPP), our chromosome operations need to avoid the repetition of genetic factors. For this, our study uses the ordered crossover (OX) method for chromosome exchange as shown in Figure 5, ensuring that each crossover results in new chromosomes that maintain gene uniqueness, thus generating effective and diverse next-generation solutions.
In this study, our approach fully leverages the advantages of genetic algorithm gene design, which aligns with the intuitive requirements of multi-robot path planning. We treat the k-CPP as a discrete path allocation problem, where each edge (path) in the graph is considered a task to be assigned to a robot. The crossover operation in the genetic algorithm resembles the recombination of task paths. When constructing the solution space, we only consider covering each path once, without accounting for the connections between two discrete segments, which effectively reduces the size of the solution space. By incorporating specific constraints of collaborative mapping, loop paths can be easily introduced in the gene design, and communication constraints can be integrated into the fitness function, resulting in more efficient multi-robot path planning.

4. Experimental Results

In this section, we conducted tests on the algorithm’s performance using maps of different scales. Specifically, for small-scale map testing, we utilized the Town10 map from the Carla simulation system [40], as shown in Figure 6a. For large-scale outdoor testing, we selected the map of the National Intelligent Vehicle (Changsha) Testing Area, as shown in Figure 6b. Subsequent experiments verified the mapping effectiveness of the planned paths within the Carla simulation system on the Town10 map. The experiments were conducted on a laptop equipped with an Intel i7-8700H CPU, 16GB DDR4 RAM, and an NVIDIA GeForce GTX 1660ti graphics card.

4.1. Experimental Setup

To comprehensively verify our algorithm’s performance on different scale maps, we chose two testing environments, as described in Table 2:
In the experiments, we primarily used a formation of three robots and applied a genetic algorithm (GA) to optimize and divide the robots’ paths. Moreover, to assess the integration of the planning algorithm with the mapping algorithm, we conducted collaborative mapping experiments in the Carla simulation environment, where we collected timestamp-consistent sensor data, including LIDAR, IMU, and GPS.

4.2. Performance and Convergence of Genetic Algorithm on Different Scale Maps

In the experiments on the Carla Town10 map, we validated the convergence of the genetic algorithm (GA) for single-robot path planning. We used the method described in [41] as a benchmark, which determines the optimal solution for single-robot path planning by finding the shortest Eulerian circuit, resulting in a total distance of 1705 m. The results demonstrated that the genetic algorithm could rapidly and effectively converge to this optimal solution, confirming its efficiency and accuracy in handling single-robot path planning problems.
The experimental results revealed that the genetic algorithm exhibited good convergence characteristics, both in single-robot and three-robot scenarios. As shown in Figure 7, with increasing iterations, the ’Iteration Best’ and ’Global Best’ path lengths in both experimental setups tended to stabilize, proving that GA is feasible for optimizing multi-robot paths.
To explore the relationship between the number of robots and the efficiency of collaborative mapping, we conducted a series of experiments using the extensive satellite map of the National Intelligent Connected Vehicle (Changsha) Testing Area. Through these experiments, we aimed to analyze changes in the total path length, the average path length, and the length of the longest subpath as the number of robots increased from 1 to 10, as illustrated in Figure 8.
The results indicate a significant downward trend in the length of the longest subpath as the number of robots increased. This reduction reflects an improvement in the efficiency of the multi-robot system in executing collaborative mapping tasks. In the three-robot experiment, the algorithm successfully optimized the longest subpath length to approximately one-third of the optimal path length for a single robot, achieving a good balance between cost and efficiency. However, it is noteworthy that once the number of robots reaches a certain level, the rate of decrease in the longest subpath length slows down. This suggests that adding more robots has diminishing marginal benefits for enhancing the overall mapping efficiency of the system.
Furthermore, both the average path length and the longest subpath length remained relatively stable as the number of robots increased, showing only minor fluctuations. This stability indicates that the genetic algorithm performs well in balancing the task distribution as more robots are added, with each robot’s workload becoming more equal, thereby improving the overall efficiency and fairness of the path planning.

4.3. Comparison with MSTC*

In this experiment, we conducted experimental validation of the robot exploration efficiency using two different scale maps: Carla Town10 and the Intelligent Vehicle Testing Area. In both environments, the experimental assumption was that robots start from the same point and need to cover the entire path and then return to the starting point. We employed a full-coverage planning algorithm that directly finds paths and balances subpath lengths to enhance exploration efficiency.
Benchmark algorithms, such as the Minimum Spanning Tree Coverage (MSTC) algorithm [37], typically involve the initial segmentation of the road network and balancing the lengths of subnetworks. However, our approach avoids such segmentation and instead plans directly across the entire path, which not only simplifies the computational process but also significantly improves the efficiency of path coverage. As can be seen from Table 3, on the Carla Town10 map, our method reduced the maximum subpath length by about half compared to the MSTC, and both the total length and average length were significantly reduced. On the larger Intelligent Vehicle Testing Area map, this advantage was equally evident. This validates the effectiveness of our algorithm in enhancing robot exploration efficiency on maps of different scales.

4.4. Communication Performance Test

To validate the effectiveness of the proposed path planning algorithm in enhancing the stability of communication between robots, we designed a communication constraint ablation experiment and evaluated the improvements in communication efficiency as well as the impact on the performance of the original algorithm in a simulation environment. As shown in Figure 9, the experiment set a stable communication distance threshold of 50 m (within the circle), and two robots had to enter each other’s communication area to be considered capable of stable communication.
The experiment was conducted in the Carla simulation environment, with three robots starting from the same point and returning to it after following their respective paths. Each robot moved at a speed of 5 m per second along the paths planned by our algorithm, which were converted into sequences of GPS points and implemented through a local planning algorithm for path tracking. Throughout the journey, we continuously monitored and recorded the distance between the robots, specifically tallying the cumulative time they spent in a stable communication state.
To comprehensively evaluate the impact of communication constraints, we defined the following two key performance indicators.
Stable Communication Time (SCT): The actual time that robots maintain communication within the set communication distance threshold. This indicator reflects the effectiveness of communication constraints in enhancing the stability of inter-robot communication.
Path Efficiency (PE): The length of the longest single-robot path required to complete the task, considering communication constraints. This metric assesses the impact of communication constraints on the efficiency of robots traversing the map.
In the Carla simulation environment, with three robots as the subjects, we designed and conducted five sets of experiments to compare and analyze changes in the communication time between the robots and mapping efficiency (longest subpath length). The results, summarized in Table 4, reflect the differences before and after the introduction of the communication constraints. Under the conditions with communication constraints, the experiments showed a significant increase in the average stable communication time between the robots, from 16.9 s in the control group to 33.3 s, nearly doubling the time. However, the average length of the longest subpath slightly increased from 817 m to 872 m, with only about a 6% decrease in path efficiency. This outcome indicates that while communication constraints significantly enhance the duration of stable communication, they have a minimal impact on the performance of the original algorithm.

4.5. Path Planning with Mapping

To comprehensively assess the integration effects of the path planning algorithm with the collaborative mapping algorithm, we conducted mapping experiments in the Carla simulation environment. In the experiments, the global path planning algorithm was responsible for generating paths covering the range of the satellite map, ensuring that autonomous vehicles could efficiently traverse all key areas. The local planning algorithm was used for precise control, guiding the autonomous vehicles according to the global path for actual navigation. The experimental results, as shown in Figure 10, confirmed that the global path planning algorithm proposed in this paper effectively directs autonomous vehicles in the Carla simulation environment, achieving the goal of stably establishing a complete point cloud map.
We calculated the Absolute Trajectory Error (ATE) for each robot’s trajectory, as shown in Table 5. As expected, under the assumption that each robot’s estimated position is consistent, the merged map achieved good global consistency.

5. Conclusions

This study proposes a novel multi-robot path planning method tailored for distributed collaborative mapping tasks, operating under communication constraints. We model the global path planning problem as the K-Chinese Postman Problem (K-CPP), integrating loop and communication constraints to effectively address challenges related to map completeness, mapping efficiency, and inter-robot communication. Compared to traditional genetic algorithm approaches to multi-robot planning, this study adopts a more efficient gene encoding scheme, which effectively reduces the solution space size, optimizes the fitness function, and balances path efficiency and uniformity. Additionally, this study designs a penalty function tailored to the specific constraints required for collaborative mapping. Through extensive validation on multi-scale maps and experiments in the Carla simulation environment, our results demonstrate significant efficiency improvements over existing methods, such as the Minimum Spanning Tree Coverage (MSTC*) algorithm. Specifically, our method not only enhances communication efficiency but also integrates more effectively with collaborative mapping algorithms.
Our current approach primarily focuses on global path planning, providing overall guidance for robot navigation. However, there needs to be a local planning layer between global path planning and collaborative mapping algorithms to handle avoidance of minor or temporary obstacles. This is a limitation of our approach, as it lacks the ability to address dynamic factors in real-world environments. In the future, we will integrate local planning algorithms into the system to enhance its completeness. Additionally, in most cases, inter-robot obstacle avoidance can be achieved by guiding robots to meet on wider roads. However, this approach faces challenges in environments consisting of narrow roads. We plan to further optimize our planning strategy to achieve effective inter-robot avoidance while ensuring communication. Lastly, considering that robot communication in real-world environments is affected not only by distance but also by signal strength and environmental interference, we plan to introduce a more detailed communication model in the future. This model will incorporate communication strength and other relevant factors to more comprehensively simulate and optimize inter-robot collaborative communication, making our path planning method more robust and better suited to complex and variable real-world environments.

Author Contributions

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

Funding

The paper is funded by National Natural Science Foundation of China (NSFC) grant 62103431, U21A20518.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available on request from the author Chengyu Zhou ([email protected]). Part of the data are not publicly available due to our laboratory’s confidentiality agreement and policies.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Zhang, H.; Chen, X.; Lu, H.; Xiao, J. Distributed and Collaborative Monocular Simultaneous Localization and Mapping for Multi-Robot Systems in Large-Scale Environments. Int. J. Adv. Robot. Syst. 2018, 15, 3. [Google Scholar] [CrossRef]
  2. Foster, A.J.I.; Gianni, M.; Aly, A.; Samani, H.; Sharma, S. Multi-Robot Coverage Path Planning for the Inspection of Offshore Wind Farms: A Review. Drones 2024, 8, 10. [Google Scholar] [CrossRef]
  3. Tian, Y.; Liu, K.; Ok, K.; Tran, L.; Allen, D.; Roy, N.; How, J.P. Search and Rescue Under the Forest Canopy Using Multiple UAVs. Int. J. Robot. Res. 2020, 39, 1201–1221. [Google Scholar] [CrossRef]
  4. Parker, L.E. Distributed Intelligence: Overview of the Field and Its Application in Multirobot Systems. J. Phys. Agents (JoPha) 2008, 2, 5–14. [Google Scholar] [CrossRef]
  5. Saeedi, S.; Trentini, M.; Seto, M.; Li, H. Multiple-Robot Simultaneous Localization and Mapping: A Review. J. Field Robot. 2016, 33, 3–46. [Google Scholar] [CrossRef]
  6. Shan, T.; Englot, B.; Meyers, D.; Wang, W.; Ratti, C.; Rus, D. LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 25–29 October 2020; pp. 5135–5142. [Google Scholar]
  7. Lajoie, P.-Y.; Ramtoula, B.; Wu, F.; Beltrame, G. Towards Collaborative Simultaneous Localization and Mapping: A Survey of the Current Research Landscape. Field Robot. 2022, 2, 971–1000. [Google Scholar] [CrossRef]
  8. Xie, H.; Zhang, D.; Hu, X.; Zhou, M.; Cao, Z. Autonomous Multi-robot Navigation and Cooperative Mapping in Partially Unknown Environments. IEEE Trans. Instrum. Meas. 2023, 72, 4508712. [Google Scholar] [CrossRef]
  9. Cramariuc, A.; Bernreiter, L.; Tschopp, F.; Fehr, M.; Reijgwart, V.; Nieto, J.; Siegwart, R.; Cadena, C. MapLab 2.0—A Modular and Multi-Modal Mapping Framework. IEEE Robot. Autom. Lett. 2023, 8, 520–527. [Google Scholar] [CrossRef]
  10. Dellenbach, P.; Deschaud, J.-E.; Jacquet, B.; Goulette, F. CT-ICP: Real-time Elastic LiDAR Odometry with Loop Closure. In Proceedings of the 2022 International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; pp. 5580–5586. [Google Scholar]
  11. Xu, H.; Liu, P.; Chen, X.; Shen, S. D2 SLAM: Decentralized and Distributed Collaborative Visual-Inertial SLAM System for Aerial Swarm. IEEE Trans. Robot. 2024, 40, 3445–3464. [Google Scholar] [CrossRef]
  12. Arandjelovic, R.; Gronat, P.; Torii, A.; Pajdla, T.; Sivic, J. NetVLAD: CNN Architecture for Weakly Supervised Place Recognition. In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Las Vegas, NV, USA, 27–30 June 2016; pp. 5297–5307. [Google Scholar]
  13. Kim, G.; Kim, A. Scan Context: Egocentric Spatial Descriptor for Place Recognition Within 3D Point Cloud Map. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 4802–4809. [Google Scholar]
  14. Wang, Y.; Sun, Z.; Xu, C.Z.; Sarma, S.E.; Yang, J.; Kong, H. LiDAR Iris for Loop-Closure Detection. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 25–29 October 2020; pp. 5769–5775. [Google Scholar]
  15. Choudhary, S.; Carlone, L.; Nieto, C.; Rogers, J.; Christensen, H.; Dellaert, F. Distributed Trajectory Estimation with Privacy and Communication Constraints: A Two-stage Distributed Gauss-Seidel Approach. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 5261–5268. [Google Scholar]
  16. Lajoie, P.Y.; Ramtoula, B.; Chang, Y.; Carlone, L.; Beltrame, G. DOOR-SLAM: Distributed, Online, and Outlier Resilient SLAM for Robotic Teams. IEEE Robot. Autom. Lett. 2020, 5, 1656–1663. [Google Scholar] [CrossRef]
  17. Tian, Y.; Chang, Y.; Arias, F.H.; Nieto-Granda, C.; How, J.P. Kimera-multi: Robust, Distributed, Dense Metric-Semantic SLAM for Multi-robot Systems. IEEE Trans. Robot. 2022, 38, 2022–2038. [Google Scholar] [CrossRef]
  18. Schmuck, P.; Ziegler, T.; Karrer, M.; Perraudin, J.; Chli, M. COVINS: Visual-Inertial SLAM for Centralized Collaboration. In Proceedings of the IEEE International Symposium on Mixed and Augmented Reality Adjunct (ISMAR-Adjunct), Bari, Italy, 4–8 October 2021; pp. 171–176. [Google Scholar]
  19. Bartolomei, L.; Karrer, M.; Chli, M. Multi-robot Coordination with Agent-Server Architecture for Autonomous Navigation in Partially Unknown Environments. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 25–29 October 2020; pp. 1516–1522. [Google Scholar]
  20. Huang, Y.; Shan, T.; Chen, F.; Englot, B. DiSCo-SLAM: Distributed Scan Context-Enabled Multirobot LiDAR SLAM with Two-Stage Global-Local Graph Optimization. IEEE Robot. Autom. Lett. 2022, 7, 1150–1157. [Google Scholar] [CrossRef]
  21. Chang, Y.; Ebadi, K.; Denniston, C.E.; Ginting, M.F.; Rosinol, A.; Reinke, A.; Palieri, M.; Shi, J.; Chatterjee, A.; Morrell, B. LAMP 2.0: A Robust Multirobot SLAM System for Operation in Challenging Large-Scale Underground Environments. IEEE Robot. Autom. Lett. 2022, 7, 9175–9182. [Google Scholar] [CrossRef]
  22. Lajoie, P.Y.; Beltrame, G. Swarm-SLAM: Sparse Decentralized Collaborative Simultaneous Localization and Mapping Framework for Multi-robot Systems. IEEE Robot. Autom. Lett. 2023, 9, 475–482. [Google Scholar] [CrossRef]
  23. Zhong, S.; Qi, Y.; Chen, Z.; Wu, J.; Chen, H.; Liu, M. DCL-SLAM: A Distributed Collaborative LiDAR SLAM Framework for a Robotic Swarm. IEEE Sensors J. 2023, 24, 4786–4797. [Google Scholar] [CrossRef]
  24. Xie, Y.; Zhang, Y.; Chen, L.; Cheng, H.; Tu, W.; Cao, D.; Li, Q. RDC-SLAM: A Real-Time Distributed Cooperative SLAM System Based on 3D LiDAR. IEEE Trans. Intell. Transp. Syst. 2021, 23, 14721–14730. [Google Scholar] [CrossRef]
  25. Cop, K.P.; Borges, P.V.K.; Dubé, R. Delight: An Efficient Descriptor for Global Localisation Using LiDAR Intensities. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, Australia, 21–25 May 2018; pp. 3653–3660. [Google Scholar]
  26. Xu, X.; Lu, S. MR_SLAM. 2023. Available online: https://github.com/MaverickPeter/MR_SLAM (accessed on 13 September 2024).
  27. Xu, X.; Lu, S.; Wu, J.; Lu, H.; Zhu, Q.; Liao, Y.; Xiong, R.; Wang, Y. Ring++: Roto-translation-invariant Gram for Global Localization on a Sparse Scan Map. IEEE Trans. Robot. 2023, 39, 4616–4635. [Google Scholar] [CrossRef]
  28. Wurman, P.R.; D’Andrea, R.; Mountz, M. Coordinating Hundreds of Cooperative, Autonomous Vehicles in Warehouses. AI Mag. 2008, 29, 9–19. [Google Scholar]
  29. Li, J.; Sun, K.; Ma, H.; Felner, A.; Kumar, T.K.S.; Koenig, S. Moving Agents in Formation in Congested Environments. In Proceedings of the 19th International Joint Conference on Autonomous Agents and MultiAgent Systems (AAMAS ’20), Auckland, New Zealand, 9–13 May 2020; Carnegie Mellon University: Pittsburgh, PA, USA, 2020; pp. 726–734. [Google Scholar]
  30. Li, J.; Jin, S.; Wang, C.; Xue, J.; Wang, X. Weld Line Recognition and Path Planning with Spherical Tank Inspection Robots. J. Field Robot. 2022, 39, 131–152. [Google Scholar] [CrossRef]
  31. Wang, H.; Chen, W. Multi-robot Path Planning with Due Times. IEEE Robot. Autom. Lett. 2022, 7, 4829–4836. [Google Scholar] [CrossRef]
  32. Standley, T. Finding Optimal Solutions to Cooperative Pathfinding Problems. In Proceedings of the AAAI Conference on Artificial Intelligence, Atlanta, GA, USA,, 11–15 July 2010; AAAI Press: Palo Alto, CA, USA, 2010; Volume 24, pp. 173–178. [Google Scholar]
  33. Surynek, P. Towards Optimal Cooperative Path Planning in Hard Setups Through Satisfiability Solving. In Pacific Rim International Conference on Artificial Intelligence; Springer: Berlin/Heidelberg, Germany, 2012; pp. 564–576. [Google Scholar]
  34. Sharon, G.; Stern, R.; Goldenberg, M.; Felner, A. The Increasing Cost Tree Search for Optimal Multi-Agent Pathfinding. Artif. Intell. 2013, 195, 470–495. [Google Scholar] [CrossRef]
  35. Matlekovic, L.; Schneider-Kamp, P. Constraint Programming Approach to Coverage-Path Planning for Autonomous Multi-UAV Infrastructure Inspection. Drones 2023, 7, 563. [Google Scholar] [CrossRef]
  36. Oh, H.; Kim, S.; Tsourdos, A.; White, B.A. Coordinated Road-Network Search Route Planning by a Team of UAVs. Int. J. Syst. Sci. 2014, 45, 825–840. [Google Scholar] [CrossRef]
  37. Tang, J.; Sun, C.; Zhang, X. MSTC*:Multi-robot Coverage Path Planning under Physical Constrain. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 5 June 2021; pp. 2518–2524. [Google Scholar]
  38. Frederickson, G.N.; Hecht, M.S.; Kim, C.E. Approximation Algorithms for Some Routing Problems. SIAM J. Comput. 1978, 7, 178–193. [Google Scholar] [CrossRef]
  39. Liu, S.; Liu, S.J.; Harris, N.; La, H.M. A Genetic Algorithm for MinMax K-Chinese Postman Problem with Applications to Bridge Inspection. In Proceedings of the International Conference on Structural Health Monitoring of Intelligent Infrastructure, St. Louis, MO, USA, 4–7 August 2019; pp. 882–889. [Google Scholar]
  40. Dosovitskiy, A.; Ros, G.; Codevilla, F.; Lopez, A.; Koltun, V. CARLA: An Open Urban Driving Simulator. In Conference on Robot Learning; PMLR: Cambridge MA, USA, 2017; pp. 1–16. [Google Scholar]
  41. LeBlanc, M.; Balsam, A. Chinese-Postman. Available online: https://github.com/supermitch/Chinese-Postman (accessed on 13 September 2024).
Figure 1. Architecture of our multi-robot path planning framework, illustrating its integration with collaborative mapping algorithms. Initially, road networks are extracted from a satellite map to create an undirected graph. Based on this graph, subpaths are assigned to each robot. As robots follow their designated paths, they each construct a submap. Finally, these submaps are consolidated into a global map through the collaborative mapping algorithm.
Figure 1. Architecture of our multi-robot path planning framework, illustrating its integration with collaborative mapping algorithms. Initially, road networks are extracted from a satellite map to create an undirected graph. Based on this graph, subpaths are assigned to each robot. As robots follow their designated paths, they each construct a submap. Finally, these submaps are consolidated into a global map through the collaborative mapping algorithm.
Drones 08 00493 g001
Figure 2. Construction of the road network topology graph.
Figure 2. Construction of the road network topology graph.
Drones 08 00493 g002
Figure 3. Mathematical modeling. (a) The undirected road network graph extracted from satellite images, serving as the system input. (b) An example of the subpaths planned for multiple robots serves as the system output.
Figure 3. Mathematical modeling. (a) The undirected road network graph extracted from satellite images, serving as the system input. (b) An example of the subpaths planned for multiple robots serves as the system output.
Drones 08 00493 g003
Figure 4. Gene representation and route splitting. The chromosome’s genes include three types: edge genes (white), loop closure edge genes (yellow), and boundary genes (orange).
Figure 4. Gene representation and route splitting. The chromosome’s genes include three types: edge genes (white), loop closure edge genes (yellow), and boundary genes (orange).
Drones 08 00493 g004
Figure 5. An example of ordered crossover (OX). The process starts by randomly choosing a segment from the first parent and copying it directly to the child. Next, it continues to fill the child chromosome with genes from the second parent that are not already present, wrapping around to the beginning of the chromosome.
Figure 5. An example of ordered crossover (OX). The process starts by randomly choosing a segment from the first parent and copying it directly to the child. Next, it continues to fill the child chromosome with genes from the second parent that are not already present, wrapping around to the beginning of the chromosome.
Drones 08 00493 g005
Figure 6. Testing map.
Figure 6. Testing map.
Drones 08 00493 g006
Figure 7. The convergence process of the genetic algorithm. (a) The Town10 single-robot optimization process; (b) the Town10 three-robot optimization process.
Figure 7. The convergence process of the genetic algorithm. (a) The Town10 single-robot optimization process; (b) the Town10 three-robot optimization process.
Drones 08 00493 g007
Figure 8. The relationship between the number of robots and the total path length, longest subpath length, and average subpath length.
Figure 8. The relationship between the number of robots and the total path length, longest subpath length, and average subpath length.
Drones 08 00493 g008
Figure 9. Assumption of stable communication between robots.
Figure 9. Assumption of stable communication between robots.
Drones 08 00493 g009
Figure 10. Path planning with mapping. (a) The robot motion trajectories and (b) map fusion. The trajectory estimated and map generated by each robot are drawn in different colors.
Figure 10. Path planning with mapping. (a) The robot motion trajectories and (b) map fusion. The trajectory estimated and map generated by each robot are drawn in different colors.
Drones 08 00493 g010
Table 2. Representative collaborative mapping algorithms.
Table 2. Representative collaborative mapping algorithms.
MapMap AttributesMap Size (m)Number of NodesNumber of EdgesNetwork Length (m)
Carla Town 10Small-scale Map170 × 20013181533
National Intelligent Vehicle Testing AreaLarge-scale Map1000 × 60020305071
Table 3. Performance comparison in two different scales of maps.
Table 3. Performance comparison in two different scales of maps.
MapMethodMax Subpath
(m)
Max Reduction
(%)
Avg Length
(m)
Avg Reduction
(%)
Total Length
(m)
Carla Town10MSTC*14681304.63914
Ours74649.2740.643.22222
Intelligent VehicleMSTC*30542831.38494
Testing AreaOurs198934.91858.634.35576
Table 4. Comparison of communication constraint and control groups.
Table 4. Comparison of communication constraint and control groups.
Group Test No.Communication Constraint GroupControl Group
R1 and R2
SCT (s)
R1 and R3
SCT (s)
R2 and R3
SCT (s)
PE (m)R1 and R2
SCT (s)
R1 and R3
SCT (s)
R2 and R3
SCT (s)
PE (m)
120634188451130746
221482584223819884
336352282862129840
44328178846411872
5362542924273122746
Average33.3872.416.9817.6
Table 5. Results of metric ATE (m).
Table 5. Results of metric ATE (m).
MetricDuration (s)Dist (m)Min (m)Max (m)RMSE (m)
Robot12185960.190.440.33
Robot22216130.250.830.45
Robot32396350.130.560.34
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

Zhou, C.; Li, J.; Shi, M.; Wu, T. Multi-Robot Path Planning Algorithm for Collaborative Mapping under Communication Constraints. Drones 2024, 8, 493. https://doi.org/10.3390/drones8090493

AMA Style

Zhou C, Li J, Shi M, Wu T. Multi-Robot Path Planning Algorithm for Collaborative Mapping under Communication Constraints. Drones. 2024; 8(9):493. https://doi.org/10.3390/drones8090493

Chicago/Turabian Style

Zhou, Chengyu, Junxiang Li, Meiping Shi, and Tao Wu. 2024. "Multi-Robot Path Planning Algorithm for Collaborative Mapping under Communication Constraints" Drones 8, no. 9: 493. https://doi.org/10.3390/drones8090493

Article Metrics

Back to TopTop