arXiv:1008.4941v1 [cs.RO] 29 Aug 2010 Pairwise Optimal Discrete Coverage Control for Gossiping Robots Joseph W. Durham Ruggero Carli Francesco Bullo Abstract— We propose distributed algorithms to automati- cally deploy a group of robotic agents and provide coverage of a discretized environment represented by a graph. The classic Lloyd approach to coverage optimization involves separate centering and partitioning steps and converges to the set of centroidal Voronoi partitions. In this work we present a novel graph coverage algorithm which achieves better performance without this separation while requiring only pairwise “gossip” communication between agents. Our new algorithm provably converges to an element of the set of pairwise-optimal partitions, a subset of the set of centroidal Voronoi partitions. We illustrate that this new equilibrium set represents a significant perfor- mance improvement through numerical comparisons to existing Lloyd-type methods. Finally, we discuss ways to efficiently do the necessary computations. I. INTRODUCTION Coordinated networks of robots are already in use for environmental monitoring [1] and warehouse logistics [2]. In the near future, improvements to the capabilities of autonomous robots will enable robotic teams to revolutionize transportation and delivery of products to customers, search and rescue, and many other applications. All of these tasks share a common feature: the robots are asked to provide service over a space. The distributed territory partitioning problem for robotic networks consists of designing individual control and communication laws such that the team will divide a space into territories. Typically, partitioning is done so to optimize a cost function which measures the quality of service provided by the team. Coverage control additionally optimizes the positioning of robots inside a territory. This paper describes a distributed coverage control algo- rithm for a network of robots to optimize the response time of the team to service requests in an environment represented by a graph. Optimality is defined with reference to a cost function which depends on the locations of the agents and geodesic distances in the graph. As with all multiagent coordination applications, the challenge comes from reducing the communication requirements: the proposed algorithm requires only “gossip” communication, that is, asynchronous and unreliable pairwise communication. A broad discussion of partitioning and coverage control is presented in [3] which builds on the classic work of Lloyd [4] on algorithms for optimal quantizer design through “cen- tering and partitioning.” The relationship between discrete This material is based upon work supported in part by NSF grant CNS- 0834446, NSF grant IIS-0904501, and ARO MURI grant W911NF-05-1- 0219. J. W. Durham, R. Carli, and F. Bullo are with the Cen- ter for Control, Dynamical Systems and Computation, University of California at Santa Barbara, Santa Barbara, CA 93106, USA, {joey|carlirug|bullo}@engr.ucsb.edu. and continuous coverage control laws based on Euclidean distances is studied in [5]. Coverage control and partitioning of discrete sets are also related to the literature on the facility location or k-center problem [6]. Coverage control algorithms for non-convex environments are discussed in [7], [8], [9] while equitable partitioning is studied in [10]. Other works considering decentralized methods for coverage con- trol include [11] and [12]. In [13] the authors have showed how a group of robotic agents can optimize the partition of convex bounded subset of Rd using a Lloyd-type algorithm with pairwise “gossip” communication: only one pair of regions is updated at each step of the algorithm. This gossip approach to Lloyd optimization was extended in [14] to discretized non-convex environments more suitable for physical robots. There are three main contributions of this paper. First, we present a novel gossip coverage algorithm and prove it con- verges to an element in the set of pairwise-optimal partitions in finite time. This solution set is shown to be a strict subset of the set of centroidal Voronoi partitions, meaning the new algorithm has fewer local minima than Lloyd-type methods. Second, through realistic Player/Stage simulations we show that the set of pairwise-optimal partitions avoids many of the local minima which can trap Lloyd-type algorithms far from the global optimum. Third, we discuss how to efficiently compute our new pairwise coverage optimization. This paper is organized as follows. Section II defines the domain and goal of our algorithm, while III contains a review of Lloyd-type gossip algorithms from [14]. Section IV presents our new algorithm and its properties, while in VI we detail its computational requirements. In Section VII we provide numerical results and comparisons to prior methods, and we end with concluding remarks in VIII. In our notation, R≥0 denotes the set of non-negative real numbers and Z≥0 the set of non-negative integers. Given a set X, |X| denotes the number of elements in X. Given sets X, Y , their difference is X \ Y = {x ∈X | x /∈Y }. A set-valued map, denoted by T : X ⇒Y , associates to an element of X a subset of Y . II. PROBLEM FORMULATION The problem domain and goal we are considering is the same as that in [14]: given a group of N robotic agents with limited sensing and communication capabilities, and a dis- cretized environment, we want to apportion the environment into smaller regions and assign one region to each agent. The goal is to optimize the quality of coverage, as measured by a cost functional which depends on the current partition and the positions of the agents. Let the finite set Q be the discretized environment. We assume that the elements of Q, which can be thought of as locations, are connected by weighted edges. Let G = (Q, E, w) be an (undirected) weighted graph with edge set E ⊂Q × Q and weight map w : E →R>0; we let we > 0 be the weight of edge e. We assume that G is connected and think of the edge weights as distances between locations. In any weighted graph G there is a standard notion of distance between vertices defined as follows. A path in G is an ordered sequence of vertices such that any consecutive pair is an edge of G. The weight of a path is the sum of the weights of the edges in the path. Given vertices h and k in G, the distance between h and k, denoted dG(h, k), is the weight of the lowest weight path between them, or +∞if there is no path. If G is connected, then the distance between any two vertices is finite. By convention, dG(h, k) = 0 if h = k. Note that dG(h, k) = dG(k, h), for any h, k ∈Q. We will be partitioning Q into N connected subsets or territories to be covered by individual agents. To do so we need to define distances on induced subgraphs of G = (Q, E, w). Given I ⊂Q, the subgraph induced by the restriction of G to I, denoted G ∩I, is the graph with vertex set equal to I and with edge set containing all weighted edges of G where both vertices belong to I, i.e. (Q, E, w) ∩I = (Q ∩I, E ∩(I × I), w|I×I). The induced subgraph is a weighted graph with a notion of distance between vertices: given h, k ∈I, we write dI(h, k) := dG ∩I(h, k). Note that dI(h, k) ≥dG(h, k). We then define a connected subset of Q as a subset S ⊂Q such that S ̸= ∅and G ∩S is connected, with C(Q) denoting the set of such subsets. We can then define partitions of Q into connected sets as follows. Definition II.1 (Connected partitions) Given the graph G = (Q, E, w), we define a connected N−partition of Q as a collection p = {pi}N i=1 of N subsets of Q such that (i) SN i=1 pi = Q; (ii) pi ∩pj = ∅if i ̸= j; (iii) pi ̸= ∅for all i ∈{1, . . . , N}; (iv) pi ∈C(Q) for all i ∈{1, . . . , N}. Let P to be the set of such partitions. Remark II.2 When |Q| ≥N and G is connected, it is always possible to find a connected N−partition of Q. Pick N unique vertices from Q to seed the subsets, then iteratively grow each subset by adding unclaimed neighboring vertices. For our gossip algorithms we need to introduce the notion of adjacent subsets. Two distinct connected subsets pi, pj are said to be adjacent if there are two vertices qi, qj belonging, respectively, to pi and pj such that (qi, qj) ∈E. Observe that if pi and pj are adjacent then pi ∪pj ∈C(Q). Similarly, we say that robots i and j are adjacent or are neighbors if their subsets pi and pj are adjacent. Accordingly we next provide the definition of an adjacency graph, which we will use in the analysis of our gossip algorithms. Definition II.3 (Adjacency graph) For p ∈P, we define the adjacency graph between regions of partition p as G(p) = ({1, . . . , N}, E(p)), where (i, j) ∈E(p) if pi and pj are adjacent. On Q, we define a weight function to be a bounded positive function φ : Q →R>0 which assigns a positive weight to each element of Q. Given pi ∈C(Q), we define the one- center function H1 : pi →R≥0 as H1(h; pi) = X k∈pi dpi(h, k)φ(k). A technical assumption is then needed to define the generalized centroid of a connected subset. In what follows, we assume that a total order relation, <, is defined on Q: hence, we can also denote Q = {1, . . . , |Q|}. Definition II.4 (Centroid) Let Q be a totally ordered set, and pi ∈C(Q). We define generalized centroid of pi as Cd(pi) := min{argmin h∈pi H1(h; pi)}. In subsequent use we will drop the word “generalized” for brevity. Note that with this definition the centroid is well- defined, and also that the centroid of a region always belongs to the region. With a slight notational abuse, we define Cd : P →QN as the map which associates to a partition the vector of the centroids of its elements. With these notions we can introduce the multicenter func- tion Hmulticenter : P × QN →R≥0 defined by Hmulticenter(p, c) = N X i=1 H1(ci; pi). Our motivation for using this cost function is to optimize the response time of the robots to a task appearing randomly in Q according relative weights φ. We aim to minimize Hmulticenter with respect to both the partitions p and the points c so as to minimize the expected distance from this random vertex to the centroid of the partition the vertex is in. Among the ways of partitioning Q, there is one which is worth special attention. Given points c ∈QN such that if i ̸= j, then ci ̸= cj, the partition p ∈P is said to be a Voronoi partition of Q generated by c if, for each pi and all k ∈pi, we have ci ∈pi and dG(k, ci) ≤dG(k, cj), ∀j ̸= i. Proposition II.5 (Properties of multicenter function) Let p ∈P, c ∈QN, and let p∗be a Voronoi partition generated by c. Then Hmulticenter(p, Cd(p)) ≤Hmulticenter(p, c), Hmulticenter(p∗, c) ≤Hmulticenter(p, c). These statements motivate the following definition: a par- tition p ∈P is a centroidal Voronoi partition if p is a Voronoi partition generated by Cd(p). Based on the multicenter function, we define Hexpected : P →R≥0 by Hexpected(p) = Hmulticenter(p, Cd(p)) = N X i=1 X x∈pi dpi(x, Cd(pi))φ(x). Observe that Hexpected has the following property as an immediate consequence of Proposition II.5: given p ∈P, if p∗is a Voronoi partition generated by Cd(p) then Hexpected(p∗) ≤Hexpected(p). We are now in a position to state the goal of our algorithm: solving the optimization problem min p∈P Hexpected(p), using only pairwise territory exchanges between agents along the edges of E(p). In the literature this optimization is typically studied with either centralized control or with synchronous and reliable communication between several agents, see [3] and [9]. We believe these communication requirements are unrealistic for deployed robotic networks, and thus are interested in solutions requiring only pairwise gossip communication as first explored in [13] and [14]. III. LLOYD-TYPE GOSSIP GRAPH COVERAGE In this Section we briefly review the discretized Lloyd-type gossip coverage algorithm proposed in [14]. Lloyd-type Gossip Graph Coverage Algorithm At each time t ∈Z≥0, each agent i ∈{1, . . . , N} maintains in memory a connected subset pi(t). The collection p(0) = {p1(0), . . . , pN(0)} is an arbitrary connected N−partition of Q. At each t ∈Z≥0 a communicating pair, say (i, j) ∈ E(p(t)), is selected by a deterministic or stochastic process to be determined. Assume that i < j. Every agent k ̸∈{i, j} sets pk(t + 1) = pk(t), while i and j perform the following: 1: agent i transmits its subset pi(t) to j and vice-versa 2: both agents compute centroids Cd(pi) and Cd(pj), set u = pi ∪pj, and the sets Wi→j = {x ∈pi : du(x, Cd(pj)) < du(x, Cd(pi))} Wj→i = {x ∈pj : du(x, Cd(pi)) < du(x, Cd(pj))} Wi∼ =j = {x ∈pi ∪pj : du(x, Cd(pi)) = du(x, Cd(pj))} 3: if Wi→j ∪Wj→i = ∅then 4: pi(t + 1) := pi(t) and pj(t + 1) := pj(t) 5: else 6: pi(t + 1) := ((pi \ Wi→j) ∪Wj→i) ∪Wj∼ =i, pj(t + 1) := ((pj \ Wj→i) ∪Wi→j) \ (Wj∼ =i ∩pj) 7: end if Observe that Wi→j (resp. Wj→i) contains the cells of pi (resp. pj) which are closer to Cd(pj) (resp. Cd(pi)), whereas Wi∼ =j represents the set of the tied cells. In other words, when two robots exchange territory using this Lloyd-type algorithm, their updated regions {pi(t + 1), pj(t + 1)} are the Voronoi partition of the set pi(t)∪pj(t) generated by the centroids Cd(pi) and Cd(pj), with all tied cells assigned to the agent with the lower index. Now, for any pair (i, j) ∈{1, . . . , N}2, i ̸= j, we define the map Tij : P ⇒P as Tij(p) = ( p, if (i, j) /∈E(p) or Wi→j ∪Wj→i = ∅ {p1, . . . , bpi, . . . , bpj, . . . , pN}, otherwise, where bpi = ((pi \ Wi→j) ∪Wj→i) ∪Wj∼ =i, and bpj = ((pj \ Wj→i) ∪Wi→j) \ (Wj∼ =i ∩pj) . The dynamical system on the space of partitions is there- fore described by, for t ∈Z≥0, p(t + 1) = Tij(p(t)), for some (i, j) ∈E(p(t)), (1) together with a rule for which edge (i, j) is selected at each time. We also define the set-valued map T : P ⇒P by T (p) = {Tij(p) | (i, j) ∈E(p)}. (2) In Theorem (III.2) we summarize the convergence proper- ties of the Lloyd-type discretized gossip coverage algorithm. To do so, we need the following definition. Definition III.1 (Uniform and random persistency) Let X be a finite set. (i) A map σ : Z≥0 →X is uniformly persistent if there exists a duration ∆∈N such that, for each x ∈X, there exists an increasing sequence of times {tk}k∈Z≥0 ⊂Z≥0 satisfying tk+1 −tk ≤∆and σ(tk) = x for all k ∈Z≥0. (ii) A stochastic process σ : Z≥0 →X is randomly persistent if there exists a probability p ∈]0, 1[ such that, for each x ∈X and for each t ∈Z≥0 P  σ(t + 1) = x | σ(t), . . . , σ(1)  ≥p. Theorem III.2 (Convergence under persistent gossip) Consider the Lloyd-type discretized gossip coverage algorithm T and the evolutions p : Z≥0 →P defined by p(t + 1) = Tσ(t)(p(t)), for t ∈Z≥0, where σ : Z≥0 →{(i, j) ∈{1, . . ., N}2 | i ̸= j} is either a deterministic map or a stochastic process. Then the following statements hold: (i) if σ is a uniformly persistent map, then any evolution p converges in a finite number of steps to a centroidal Voronoi partition; and (ii) if σ is a randomly persistent stochastic process, then any evolution p converges almost surely in a finite number of steps to a centroidal Voronoi partition. Convergence to a centroidal Voronoi partition puts this pairwise optimization algorithm in the same class with centralized Lloyd methods. However, there can be a great number of possible centroidal Voronoi partitions for a given discretized environment and, in our experience, the algorithm too frequently converges to a suboptimal solution. This issue motivates the developments in the following Section. IV. PAIRWISE-OPTIMAL GOSSIP COVERAGE ALGORITHM In this section we present a novel gossip graph coverage algorithm which improves on the performance achievable by the Lloyd-type algorithm reviewed in the previous Section. First we introduce the following notational definition. Given p ∈P and distinct components pi and pj, let Ppi∪pj denote the set of all distinct pairs of vertices in pi ∪pj. We assume that the elements in Ppi∪pj are sorted lexicographi- cally. In formal terms, if pi ∪pj =  h1, . . . , h|pi∪pj| where hs < hs+1 for s = {1, . . . , |pi ∪pj| −1}, then Ppi∪pj =  (h1, h2), (h1, h3), . . . , (h1, h|pi∪pj|), (h2, h3), . . . . . . , (h|pi∪pj|−1, h|pi∪pj|) . Notice that |Ppi∪pj| = |pi∪pj| (|pi∪pj|−1) 2 . The pairwise-optimal discretized gossip coverage algo- rithm is defined as follows. Gossip Optimal Graph Coverage Algorithm At each time t ∈Z≥0, each agent i ∈{1, . . . , N} maintains in memory a connected subset pi(t). The collection p(0) = {p1(0), . . . , pN(0)} is an arbitrary connected N−partition of Q. At each t ∈Z≥0 a communicating pair, say (i, j) ∈ E(p(t)), is selected by a deterministic or stochastic process to be determined. Assume that i < j. Every agent k ̸∈{i, j} sets pk(t + 1) = pk(t), while i and j perform the following: 1: agent i transmits its subset pi(t) to j and vice-versa 2: both agents compute the set u = pi ∪pj, the function D : Pu →R>0 D((a, b)) = X h∈u min {du(h, a), du(h, b)} , and find the set SD = argmin(hs,hr)∈Pu {D(hs, hr)} 3: assuming SD is lexicographically ordered, both agents pick the first pair in SD, say (a∗, b∗) 4: both agents compute the sets Wa∗= {x ∈u : du(x, a∗) ≤du(x, b∗)} Wb∗= {x ∈u : du(x, b∗) < du(x, a∗)} 5: if H1(Cd(Wa∗); Wa∗) + H1(Cd(Wb∗); Wb∗) < H1(Cd(pi(t)); pi(t)) + H1(Cd(pj(t)); pj(t)) then 6: pi(t + 1) = Wa∗, pj(t + 1) = Wb∗ 7: else 8: pi(t + 1) = pi(t), pj(t + 1) = pj(t) 9: end if Remark IV.1 The lexicographic rule for picking (a∗, b∗) used here makes the dynamical system represented by the algorithm deterministic and well-defined. In practice any pair in SD can be chosen. The following Proposition characterizes a desirable prop- erty of the regions Wa∗and Wb∗. Proposition IV.2 The regions Wa∗and Wb∗as defined in Gossip Optimal Graph Coverage Algorithm, are connected. Thanks to Proposition IV.2 we have that, for any pair (i, j) ∈{1, . . . , N}2, i ̸= j, we can define the map Tij : P →P by Tij(p) = ( p, if (i, j) /∈E(p) {p1, . . . , bpi, . . . , bpj, . . . , pN}, otherwise, where bpi = Wa∗and bpj = Wb∗. Therefore, the dynamical system on the space of partitions can again be described in compact form by (1) and (2) but with this new Tij. To establish the convergence properties of the pairwise- optimal discretized gossip coverage algorithm we need the following definition. Definition IV.3 A partition p ∈P is said to be a pairwise- optimal partition if, for every (i, j) ∈E(p) H1(Cd(pi); pi) + H1(Cd(pj); pj) = min a,b∈pi∪pj    X k∈pi∪pj min  dpi∪pj(a, k), dpi∪pj(b, k)    The following Proposition characterizes the set of the pairwise-optimal partitions. Proposition IV.4 Let p ∈P be a pairwise-optimal partition. Then p is also a centroidal Voronoi partition. We are now ready to state the main result of this paper. Theorem IV.5 (Convergence under persistent gossip) Consider the pairwise-optimal discretized gossip coverage algorithm T and the evolutions p : Z≥0 →P defined by p(t + 1) = Tσ(t)(p(t)), for t ∈Z≥0, where σ : Z≥0 →{(i, j) ∈{1, . . ., N}2 | i ̸= j} is either a deterministic map or a stochastic process. Then the following statements hold: (i) if σ is a uniformly persistent map, then any evolution p converges in a finite number of steps to a pairwise- optimal partition; and (ii) if σ is a randomly persistent stochastic process, then any evolution p converges almost surely in a finite number of steps to a pairwise-optimal partition. In contrast to the Lloyd-type algorithm in Section III, this new pairwise-optimal algorithm converges to an element in the set of pairwise-optimal partitions. This result is a useful improvement as the set of pairwise-optimal partitions is a subset of the set of centroidal Voronoi partitions, so that the new algorithm can avoid many of the local minima in which Lloyd-type methods get stuck. We will demonstrate this improvement in Section VII. V. CONVERGENCE PROOFS In this Section we provide proofs of the results stated in the previous Section, starting with Proposition IV.2. Proof: [Proposition IV.2] To prove the statement of the Proposition we show that, given x ∈Wb∗, any shortest path in pi ∪pj connecting x to b∗completely belongs to Wb∗. We proceed by contradiction. Let sx,b∗denote a shortest path in pi ∪pj connecting x to b∗and let us assume that there exists m ∈sx,b∗such that m ∈Wa∗. For m to be in b∗means that dpi∪pj(m, b∗) < dpi∪pj(m, a∗). This implies that dpi∪pj(x, a∗) = dpi∪pj(m, a∗) + dpi∪pj(x, m) > dpi∪pj(m, b∗) + dpi∪pj(x, m) ≥dpi∪pj(x, b∗). This is a contradiction for x ∈b∗. Similar considerations hold for Wa∗. To prove Proposition IV.4 we need to review the notion of a centroidal Voronoi in pairs partition [14]. Definition V.1 Consider the connected graph G = (Q, E, w).. Let p ∈P and let G(p) be the associated adjacency graph. Then p ∈P is said to be centroidal Voronoi in pairs if, for any i ∈{1, . . . , N} we have that dpi∪pj(k, Cd(pi)) ≤dpi∪pj(k, Cd(pj)) (3) for all k ∈pi and for all j such that (i, j) ∈E(p). The following Lemma [14] states a useful equivalence property between the set of centroidal Voronoi in pairs partitions and the set of centroidal Voronoi partitions. Lemma V.2 A partition p ∈P is centroidal Voronoi in pairs if and only if it is centroidal Voronoi. We are now ready to prove Proposition IV.4. Proof: [Proposition IV.4] We will show that if a partition p ∈P is a pairwise-optimal partition then p is also centroidal Voronoi in pairs. Then from Lemma V.2 it will follow that p is also centroidal Voronoi. We proceed by contradiction. Let p ∈P be a pairwise- optimal partition, let pi and pj be two adjacent regions, and let us assume that there exists x ∈pi such that dpi∪pj(x, Cd(pi)) > dpi∪pj(x, Cd(pj)). (4) Let sx,Cd(pj) denote a shortest path in pi ∪pj connecting x to Cd(pj). Without loss of generality let us assume that sx,Cd(pj) = (x, y1, y2, . . . , ym, Cd(pj)), for a suitable m- tuple in pi ∪pj. Now let s(i) x,Cd(pj) denote the subset of sx,Cd(pj) consisting of only the vertices belonging to pi, i.e., s(i) x,Cd(pj) =  y ∈sx,Cd(pj)|y ∈pi . Observe that from (4) it follows that dpi∪pj(y, Cd(pi)) > dpi∪pj(y, Cd(pj)) for all y ∈s(i) x,Cd(pj). Therefore, by letting ¯pi = pi \ s(i) x,Cd(pj) and ¯pj = pj ∪s(i) x,Cd(pj) we have that H1(Cd(¯pi); ¯pi) + H1(Cd(¯pj); ¯pj) ≤H1(Cd(pi); ¯pi) + H1(Cd(pj); ¯pj) < H1(Cd(pi); pi) + H1(Cd(pj); pj). This last inequality contradicts the fact that p is a pairwise- optimal partition. To provide the proof of Theorem IV.5 we need the following intermediate result. Lemma V.3 Let T : P ⇒P be the point-to-set map defined for the Gossip Optimal Graph Coverage Algorithm. If p(t) ∈ P and p(t + 1) ∈T (p(t)) \ p(t), then Hexpected(p(t + 1)) < Hexpected(p(t)). Proof: Without loss of generality assume that (i, j) is the pair selected at time t. For simplicity let us denote p(t + 1) and p(t), respectively, by p+ and p. Then Hexpected(p+) −Hexpected(p) = H1(Cd(p+ i ); p+ i ) + H1(Cd(p+ j ); p+ j ) −(H1(Cd(pi); pi) + H1(Cd(pj); pj)). According to the definition of the Gossip Optimal Graph Coverage Algorithm we have that if p+ i ̸= pi, p+ j ̸= pj, then H1(Cd(p+ i ); p+ i ) + H1(Cd(p+ j ); p+ j ) < H1(Cd(pi); pi) + H1(Cd(pj); pj) from which the thesis follows. Now we can prove the main result of this paper. Proof: [Theorem IV.5] The proof of point (i) of the Theorem is based on on verifying the assumptions (i), (ii), (iii), (iv) of Theorem 4.3 from [13]. We start with the following topological consideration. Let A, B ⊂Q, A∆B be their symmetric difference, and let |A| be the “points counting measure” of A, that is the number of elements of A. Then if we define d∆(A, B) = |A∆B| , we have that d∆is a distance on the set of the subsets of Q, which we denote 2Q. Since the points counting measure takes integer values, 2Q a discrete topological space. Next, consider the product space (2Q)N and let q = {q1, . . . , qN} and ¯q = {¯q1, . . . , ¯qN} be two its elements. Then, thanks to results valid for product topological spaces, we have that the function d(N) ∆(q, ¯q) = PN i=1 d (qi, ¯qi) is a distance on (2Q)N. Hence, (2Q)N is also a discrete topological space. Observe that P is a subset of (2Q)N. Since 2Q, (2Q)N and P are finite, they are also trivially compact. Moreover, since the algorithm T : P ⇒P is well-defined, we have that P is strongly positively invariant. This fact implies that assumption (i) of Theorem 4.3 from [13] is satisfied. From Lemma V.3 it follows that assumption (ii) is also satisfied, with Hexpected playing the role of the function U. Next, the fact that all maps from a discrete space are continuous implies the continuity of the maps Tij and Hexpected, thus guaranteeing the validity of assumption (iii). Assumption (iv) holds true for the hypothesis made in the Fig. 1. At left, ten robots are positioned at the centroids of their initial partitions in a non-convex environment. The boundary of each agent’s partition is drawn in a different color. The middle shows the final solution of a centralized Lloyd optimization with a total cost of 624.1m. At right is a final solution for the pairwise-optimal discretized gossip coverage algorithm starting from the final centralized Lloyd solution, with an improved cost of 610.3m. statement of Theorem IV.5 that σ is a uniformly persistent map. Hence we are in the position to apply Theorem 4.3 from [13], and conclude convergence to the intersection of the equilibria of the maps Tij, which, according to the definition of Tij coincides with the set of the pairwise- optimal partitions. Hence, since that set is finite, we can argue that the system converges in finite time to one pairwise- optimal partition. A proof of (ii) in Theorem IV.5 can be made in a similar way using Theorem 4.5 from [13] inplace of 4.3. VI. SCALABILITY PROPERTIES In this Section we discuss how to compute the optimal new centroids (a∗, b∗) ∈Ppi∪pj for the Gossip Optimal Graph Coverage Algorithm, as well as a sampling method to greatly reduce the computational complexity. Determining (a∗, b∗) requires an exhaustive search over all possible pairs of vertices for a pair with the lowest cost to cover pi ∪pj. Using Johnson’s all pairs shortest paths algorithm as a first step to compute a pairwise distance matrix for pi∪pj, (a∗, b∗) can be found in O(|pi|3) with a memory requirement of O(|pi|2) (as pi ∪pj is of order |pi|). For mobile robots with limited onboard resources, these requirements may be too steep. In such circumstances, we propose instead to sample pairs of potential new centroids when applying the algorithm. The first sample pair would be the agents’ previous centroids, with the rest drawn at random from the set Ppi∪pj. For m sample pairs, this approach requires 2m calls to Dijkstra’s one-to-all shortest paths algorithm to find the pair with the lowest cost, for a total time complexity of O(m|pi| log(|pi|)) and a memory requirement of O(|pi|). It is also worth noting that if all edge weights in G are equal (i.e., for a regular grid discretization), then a breadth-first-search approach can replace Dijkstra and the time complexity drops to O(m|pi|). This sample-based approach greatly reduces the time and memory requirements, and will still converge to a pairwise-optimal partition. VII. SIMULATION RESULTS To demonstrate the utility of the proposed gossip coverage algorithm, we implemented it and other coverage algorithms using the open-source Player/Stage robot software system [15] and the Boost Graph Library (BGL) [16]. All results presented here were generated using Player 2.1.1, Stage 2.1.0, and BGL 1.34.1. A non-convex environment was specified with a bitmap and overlaid with a 0.1m resolution occupancy grid, producing a lattice-like graph with all edge weights equal to 0.1m. To compute distances on graphs with uniform edge weights we extended the BGL implementation of breadth-first-search with a distance recorder event visitor. Figure 1 provides one example of how convergence to the set of pairwise-optimal partitions represents an improvement over Lloyd-type methods. On the left is the non-convex environment used for all results in this Section, as well as an initial partition for 10 robots. The middle panel shows the result of a centralized Lloyd optimization where all agents iteratively update their centroid and partition based on the centroids of all other agents. The final equilibrium for this centralized method is a centroidal Voronoi partition with a total cost of 624.1m. However, this solution is not a pairwise-optimal partition. We started the pairwise-optimal discretized gossip coverage algorithm using this partition as the initial condition. After 70 pairwise exchanges between random agent pairs, the algorithm reached the pairwise- optimal partition at right which has a lower cost of 610.3. The best known 10-partition of this map has cost 610.0. Figure 2 compares 100 simulations of the Lloyd-type and pairwise-optimal discretized gossip coverage algorithms. We started each simulation from the initial partition in Fig. 1 and used different random sequences of agent pairs for each case. The new pairwise-optimal algorithm shows marked improvement over the Lloyd-type gossip algorithm, achieving a total cost within 2% of the best known cost in 85% of trials, while also avoiding the worst local minima. Figure 3 compares final cost histograms for 10 random initial conditions for the same environment. Each initial condition was created by selecting unique starting locations for the agents uniformly at random, and using these locations to generate a Voronoi partition. The histograms compare 20 simulations of Lloyd-type and the new pairwise-optimal gossip coverage starting from the same initial partition but 610 620 630 640 650 660 670 680 0 10 20 30 40 50 60 ag replacements Simulation count Final total cost (m) Fig. 2. Histograms of final total costs for 100 simulations of pairwise- optimal (gray) and Lloyd-type (black) gossip coverage. All runs started from the initial partition in Fig. 1 with different random sequences of agent pairs. The dashed red line shows the final cost using a centralized Lloyd algorithm. with different random orders of exchanges. The centralized Lloyd final cost for each initial condition is also shown. The new pairwise-optimal method outperforms both Lloyd- type methods for all 10 tests, although the Lloyd-type gossip method is close in two of the trials. These results illustrate that convergence to a pairwise-optimal partition represents a significant performance enhancement over classic Lloyd methods. Interestingly, the Lloyd-type gossip algorithm also substantially outperforms the centralized version in 8 of the trials. We speculate this is due to the gossip method taking trajectories through the space of connected N−partitions which are not possible for the centralized approach. VIII. CONCLUSIONS We have presented a novel distributed coverage control algorithm which requires only pairwise communication be- tween agents. The classic Lloyd approach to optimizing quantizer placement involves iteration of separate centering and Voronoi partitioning steps. In the graph coverage domain, the separation of centroid and partition optimization seems unnecessary computationally for gossip algorithms. More importantly, we have shown that improved performance can be achieved without this separation. Our new pairwise- optimal discretized gossip coverage algorithm provably con- verges to a subset of the centroidal Voronoi partitions which we labeled the set of pairwise-optimal partitions. Through numerical comparisons we demonstrated that this new subset of solutions avoids many of the local minima in which both gossip and centralized Lloyd-type algorithms can get stuck. REFERENCES [1] E. Fiorelli, N. E. Leonard, P. Bhatta, D. A. Paley, R. Bachmayer, and D. M. Fratantoni, “Multi-AUV control and adaptive sampling in Monterey Bay,” IEEE Journal of Oceanic Engineering, vol. 31, no. 4, pp. 935–948, 2006. [2] P. R. Wurman, R. D’Andrea, and M. Mountz, “Coordinating hundreds of cooperative, autonomous vehicles in warehouses,” AI Magazine, vol. 29, no. 1, pp. 9–20, 2008. [3] F. Bullo, J. Cort´es, and S. Mart´ınez, Distributed Control of Robotic Networks. Applied Mathematics Series, Princeton University Press, 2009. Available at http://www.coordinationbook.info. [4] S. P. Lloyd, “Least squares quantization in PCM,” IEEE Transactions on Information Theory, vol. 28, no. 2, pp. 129–137, 1982. Presented as Bell Laboratory Technical Memorandum at a 1957 Institute for Mathematical Statistics meeting. 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 620 640 660 680 700 0 10 20 PSfrag replacements Simulation count Final total cost (m) Fig. 3. Histograms of final costs for simulations starting from 10 random initial conditions for the environment in Fig. 1. The pairwise-optimal (gray) and Lloyd-type (black) gossip coverage algorithms each ran 20 times per initial condition using different random sequences of agent pairs. The dashed red line shows the final cost using a centralized Lloyd algorithm. [5] C. Gao, J. Cort´es, and F. Bullo, “Notes on averaging over acyclic digraphs and discrete coverage control,” Automatica, vol. 44, no. 8, pp. 2120–2127, 2008. [6] V. V. Vazirani, Approximation Algorithms. Springer, 2001. [7] M. Zhong and C. G. Cassandras, “Distributed coverage control in sensor network environments with polygonal obstacles,” in IFAC World Congress, (Seoul, Korea), pp. 4162–4167, July 2008. [8] C. H. Caicedo-N`u˜nez and M. ˇZefran, “Performing coverage on nonconvex domains,” in IEEE Conf. on Control Applications, (San Antonio, TX), pp. 1019–1024, Sept. 2008. [9] L. C. A. Pimenta, V. Kumar, R. C. Mesquita, and G. A. S. Pereira, “Sensing and coverage for a network of heterogeneous robots,” in IEEE Conf. on Decision and Control, (Canc´un, M´exico), pp. 3947– 3952, Dec. 2008. [10] O. Baron, O. Berman, D. Krass, and Q. Wang, “The equitable location problem on the plane,” European Journal of Operational Research, vol. 183, no. 2, pp. 578–590, 2007. [11] S. Yun, M. Schwager, and D. Rus, “Coordinating construction of truss structures using distributed equal-mass partitioning,” in International Symposium on Robotics Research, (Lucerne, Switzerland), Aug. 2009. [12] M. Schwager, D. Rus, and J. J. Slotine, “Decentralized, adaptive coverage control for networked robots,” International Journal of Robotics Research, vol. 28, no. 3, pp. 357–375, 2009. [13] F. Bullo, R. Carli, and P. Frasca, “Gossip coverage control for robotic networks: Dynamical systems on the the space of partitions,” Dec. 2009. Available at http://arxiv.org/abs/0903.3642. [14] J. W. Durham, R. Carli, P. Frasca, and F. Bullo, “Discrete partitioning and coverage control with gossip communication,” in ASME Dynamic Systems and Control Conference, (Hollywood, CA), Oct. 2009. [15] B. Gerkey, R. T. Vaughan, and A. Howard, “The Player/Stage Project.” http://playerstage.sourceforge.net, June 2008. Ver- sion 2.11. [16] J. G. Siek, L.-Q. Lee, and A. Lumsdaine, “Boost Graph Library.” http://www.boost.org, July 2007. Version 1.34.1. arXiv:1008.4941v1 [cs.RO] 29 Aug 2010 Pairwise Optimal Discrete Coverage Control for Gossiping Robots Joseph W. Durham Ruggero Carli Francesco Bullo Abstract— We propose distributed algorithms to automati- cally deploy a group of robotic agents and provide coverage of a discretized environment represented by a graph. The classic Lloyd approach to coverage optimization involves separate centering and partitioning steps and converges to the set of centroidal Voronoi partitions. In this work we present a novel graph coverage algorithm which achieves better performance without this separation while requiring only pairwise “gossip” communication between agents. Our new algorithm provably converges to an element of the set of pairwise-optimal partitions, a subset of the set of centroidal Voronoi partitions. We illustrate that this new equilibrium set represents a significant perfor- mance improvement through numerical comparisons to existing Lloyd-type methods. Finally, we discuss ways to efficiently do the necessary computations. I. INTRODUCTION Coordinated networks of robots are already in use for environmental monitoring [1] and warehouse logistics [2]. In the near future, improvements to the capabilities of autonomous robots will enable robotic teams to revolutionize transportation and delivery of products to customers, search and rescue, and many other applications. All of these tasks share a common feature: the robots are asked to provide service over a space. The distributed territory partitioning problem for robotic networks consists of designing individual control and communication laws such that the team will divide a space into territories. Typically, partitioning is done so to optimize a cost function which measures the quality of service provided by the team. Coverage control additionally optimizes the positioning of robots inside a territory. This paper describes a distributed coverage control algo- rithm for a network of robots to optimize the response time of the team to service requests in an environment represented by a graph. Optimality is defined with reference to a cost function which depends on the locations of the agents and geodesic distances in the graph. As with all multiagent coordination applications, the challenge comes from reducing the communication requirements: the proposed algorithm requires only “gossip” communication, that is, asynchronous and unreliable pairwise communication. A broad discussion of partitioning and coverage control is presented in [3] which builds on the classic work of Lloyd [4] on algorithms for optimal quantizer design through “cen- tering and partitioning.” The relationship between discrete This material is based upon work supported in part by NSF grant CNS- 0834446, NSF grant IIS-0904501, and ARO MURI grant W911NF-05-1- 0219. J. W. Durham, R. Carli, and F. Bullo are with the Cen- ter for Control, Dynamical Systems and Computation, University of California at Santa Barbara, Santa Barbara, CA 93106, USA, {joey|carlirug|bullo}@engr.ucsb.edu. and continuous coverage control laws based on Euclidean distances is studied in [5]. Coverage control and partitioning of discrete sets are also related to the literature on the facility location or k-center problem [6]. Coverage control algorithms for non-convex environments are discussed in [7], [8], [9] while equitable partitioning is studied in [10]. Other works considering decentralized methods for coverage con- trol include [11] and [12]. In [13] the authors have showed how a group of robotic agents can optimize the partition of convex bounded subset of Rd using a Lloyd-type algorithm with pairwise “gossip” communication: only one pair of regions is updated at each step of the algorithm. This gossip approach to Lloyd optimization was extended in [14] to discretized non-convex environments more suitable for physical robots. There are three main contributions of this paper. First, we present a novel gossip coverage algorithm and prove it con- verges to an element in the set of pairwise-optimal partitions in finite time. This solution set is shown to be a strict subset of the set of centroidal Voronoi partitions, meaning the new algorithm has fewer local minima than Lloyd-type methods. Second, through realistic Player/Stage simulations we show that the set of pairwise-optimal partitions avoids many of the local minima which can trap Lloyd-type algorithms far from the global optimum. Third, we discuss how to efficiently compute our new pairwise coverage optimization. This paper is organized as follows. Section II defines the domain and goal of our algorithm, while III contains a review of Lloyd-type gossip algorithms from [14]. Section IV presents our new algorithm and its properties, while in VI we detail its computational requirements. In Section VII we provide numerical results and comparisons to prior methods, and we end with concluding remarks in VIII. In our notation, R≥0 denotes the set of non-negative real numbers and Z≥0 the set of non-negative integers. Given a set X, |X| denotes the number of elements in X. Given sets X, Y , their difference is X \ Y = {x ∈X | x /∈Y }. A set-valued map, denoted by T : X ⇒Y , associates to an element of X a subset of Y . II. PROBLEM FORMULATION The problem domain and goal we are considering is the same as that in [14]: given a group of N robotic agents with limited sensing and communication capabilities, and a dis- cretized environment, we want to apportion the environment into smaller regions and assign one region to each agent. The goal is to optimize the quality of coverage, as measured by a cost functional which depends on the current partition and the positions of the agents. Let the finite set Q be the discretized environment. We assume that the elements of Q, which can be thought of as locations, are connected by weighted edges. Let G = (Q, E, w) be an (undirected) weighted graph with edge set E ⊂Q × Q and weight map w : E →R>0; we let we > 0 be the weight of edge e. We assume that G is connected and think of the edge weights as distances between locations. In any weighted graph G there is a standard notion of distance between vertices defined as follows. A path in G is an ordered sequence of vertices such that any consecutive pair is an edge of G. The weight of a path is the sum of the weights of the edges in the path. Given vertices h and k in G, the distance between h and k, denoted dG(h, k), is the weight of the lowest weight path between them, or +∞if there is no path. If G is connected, then the distance between any two vertices is finite. By convention, dG(h, k) = 0 if h = k. Note that dG(h, k) = dG(k, h), for any h, k ∈Q. We will be partitioning Q into N connected subsets or territories to be covered by individual agents. To do so we need to define distances on induced subgraphs of G = (Q, E, w). Given I ⊂Q, the subgraph induced by the restriction of G to I, denoted G ∩I, is the graph with vertex set equal to I and with edge set containing all weighted edges of G where both vertices belong to I, i.e. (Q, E, w) ∩I = (Q ∩I, E ∩(I × I), w|I×I). The induced subgraph is a weighted graph with a notion of distance between vertices: given h, k ∈I, we write dI(h, k) := dG ∩I(h, k). Note that dI(h, k) ≥dG(h, k). We then define a connected subset of Q as a subset S ⊂Q such that S ̸= ∅and G ∩S is connected, with C(Q) denoting the set of such subsets. We can then define partitions of Q into connected sets as follows. Definition II.1 (Connected partitions) Given the graph G = (Q, E, w), we define a connected N−partition of Q as a collection p = {pi}N i=1 of N subsets of Q such that (i) SN i=1 pi = Q; (ii) pi ∩pj = ∅if i ̸= j; (iii) pi ̸= ∅for all i ∈{1, . . . , N}; (iv) pi ∈C(Q) for all i ∈{1, . . . , N}. Let P to be the set of such partitions. Remark II.2 When |Q| ≥N and G is connected, it is always possible to find a connected N−partition of Q. Pick N unique vertices from Q to seed the subsets, then iteratively grow each subset by adding unclaimed neighboring vertices. For our gossip algorithms we need to introduce the notion of adjacent subsets. Two distinct connected subsets pi, pj are said to be adjacent if there are two vertices qi, qj belonging, respectively, to pi and pj such that (qi, qj) ∈E. Observe that if pi and pj are adjacent then pi ∪pj ∈C(Q). Similarly, we say that robots i and j are adjacent or are neighbors if their subsets pi and pj are adjacent. Accordingly we next provide the definition of an adjacency graph, which we will use in the analysis of our gossip algorithms. Definition II.3 (Adjacency graph) For p ∈P, we define the adjacency graph between regions of partition p as G(p) = ({1, . . . , N}, E(p)), where (i, j) ∈E(p) if pi and pj are adjacent. On Q, we define a weight function to be a bounded positive function φ : Q →R>0 which assigns a positive weight to each element of Q. Given pi ∈C(Q), we define the one- center function H1 : pi →R≥0 as H1(h; pi) = X k∈pi dpi(h, k)φ(k). A technical assumption is then needed to define the generalized centroid of a connected subset. In what follows, we assume that a total order relation, <, is defined on Q: hence, we can also denote Q = {1, . . . , |Q|}. Definition II.4 (Centroid) Let Q be a totally ordered set, and pi ∈C(Q). We define generalized centroid of pi as Cd(pi) := min{argmin h∈pi H1(h; pi)}. In subsequent use we will drop the word “generalized” for brevity. Note that with this definition the centroid is well- defined, and also that the centroid of a region always belongs to the region. With a slight notational abuse, we define Cd : P →QN as the map which associates to a partition the vector of the centroids of its elements. With these notions we can introduce the multicenter func- tion Hmulticenter : P × QN →R≥0 defined by Hmulticenter(p, c) = N X i=1 H1(ci; pi). Our motivation for using this cost function is to optimize the response time of the robots to a task appearing randomly in Q according relative weights φ. We aim to minimize Hmulticenter with respect to both the partitions p and the points c so as to minimize the expected distance from this random vertex to the centroid of the partition the vertex is in. Among the ways of partitioning Q, there is one which is worth special attention. Given points c ∈QN such that if i ̸= j, then ci ̸= cj, the partition p ∈P is said to be a Voronoi partition of Q generated by c if, for each pi and all k ∈pi, we have ci ∈pi and dG(k, ci) ≤dG(k, cj), ∀j ̸= i. Proposition II.5 (Properties of multicenter function) Let p ∈P, c ∈QN, and let p∗be a Voronoi partition generated by c. Then Hmulticenter(p, Cd(p)) ≤Hmulticenter(p, c), Hmulticenter(p∗, c) ≤Hmulticenter(p, c). These statements motivate the following definition: a par- tition p ∈P is a centroidal Voronoi partition if p is a Voronoi partition generated by Cd(p). Based on the multicenter function, we define Hexpected : P →R≥0 by Hexpected(p) = Hmulticenter(p, Cd(p)) = N X i=1 X x∈pi dpi(x, Cd(pi))φ(x). Observe that Hexpected has the following property as an immediate consequence of Proposition II.5: given p ∈P, if p∗is a Voronoi partition generated by Cd(p) then Hexpected(p∗) ≤Hexpected(p). We are now in a position to state the goal of our algorithm: solving the optimization problem min p∈P Hexpected(p), using only pairwise territory exchanges between agents along the edges of E(p). In the literature this optimization is typically studied with either centralized control or with synchronous and reliable communication between several agents, see [3] and [9]. We believe these communication requirements are unrealistic for deployed robotic networks, and thus are interested in solutions requiring only pairwise gossip communication as first explored in [13] and [14]. III. LLOYD-TYPE GOSSIP GRAPH COVERAGE In this Section we briefly review the discretized Lloyd-type gossip coverage algorithm proposed in [14]. Lloyd-type Gossip Graph Coverage Algorithm At each time t ∈Z≥0, each agent i ∈{1, . . . , N} maintains in memory a connected subset pi(t). The collection p(0) = {p1(0), . . . , pN(0)} is an arbitrary connected N−partition of Q. At each t ∈Z≥0 a communicating pair, say (i, j) ∈ E(p(t)), is selected by a deterministic or stochastic process to be determined. Assume that i < j. Every agent k ̸∈{i, j} sets pk(t + 1) = pk(t), while i and j perform the following: 1: agent i transmits its subset pi(t) to j and vice-versa 2: both agents compute centroids Cd(pi) and Cd(pj), set u = pi ∪pj, and the sets Wi→j = {x ∈pi : du(x, Cd(pj)) < du(x, Cd(pi))} Wj→i = {x ∈pj : du(x, Cd(pi)) < du(x, Cd(pj))} Wi∼ =j = {x ∈pi ∪pj : du(x, Cd(pi)) = du(x, Cd(pj))} 3: if Wi→j ∪Wj→i = ∅then 4: pi(t + 1) := pi(t) and pj(t + 1) := pj(t) 5: else 6: pi(t + 1) := ((pi \ Wi→j) ∪Wj→i) ∪Wj∼ =i, pj(t + 1) := ((pj \ Wj→i) ∪Wi→j) \ (Wj∼ =i ∩pj) 7: end if Observe that Wi→j (resp. Wj→i) contains the cells of pi (resp. pj) which are closer to Cd(pj) (resp. Cd(pi)), whereas Wi∼ =j represents the set of the tied cells. In other words, when two robots exchange territory using this Lloyd-type algorithm, their updated regions {pi(t + 1), pj(t + 1)} are the Voronoi partition of the set pi(t)∪pj(t) generated by the centroids Cd(pi) and Cd(pj), with all tied cells assigned to the agent with the lower index. Now, for any pair (i, j) ∈{1, . . . , N}2, i ̸= j, we define the map Tij : P ⇒P as Tij(p) = ( p, if (i, j) /∈E(p) or Wi→j ∪Wj→i = ∅ {p1, . . . , bpi, . . . , bpj, . . . , pN}, otherwise, where bpi = ((pi \ Wi→j) ∪Wj→i) ∪Wj∼ =i, and bpj = ((pj \ Wj→i) ∪Wi→j) \ (Wj∼ =i ∩pj) . The dynamical system on the space of partitions is there- fore described by, for t ∈Z≥0, p(t + 1) = Tij(p(t)), for some (i, j) ∈E(p(t)), (1) together with a rule for which edge (i, j) is selected at each time. We also define the set-valued map T : P ⇒P by T (p) = {Tij(p) | (i, j) ∈E(p)}. (2) In Theorem (III.2) we summarize the convergence proper- ties of the Lloyd-type discretized gossip coverage algorithm. To do so, we need the following definition. Definition III.1 (Uniform and random persistency) Let X be a finite set. (i) A map σ : Z≥0 →X is uniformly persistent if there exists a duration ∆∈N such that, for each x ∈X, there exists an increasing sequence of times {tk}k∈Z≥0 ⊂Z≥0 satisfying tk+1 −tk ≤∆and σ(tk) = x for all k ∈Z≥0. (ii) A stochastic process σ : Z≥0 →X is randomly persistent if there exists a probability p ∈]0, 1[ such that, for each x ∈X and for each t ∈Z≥0 P  σ(t + 1) = x | σ(t), . . . , σ(1)  ≥p. Theorem III.2 (Convergence under persistent gossip) Consider the Lloyd-type discretized gossip coverage algorithm T and the evolutions p : Z≥0 →P defined by p(t + 1) = Tσ(t)(p(t)), for t ∈Z≥0, where σ : Z≥0 →{(i, j) ∈{1, . . ., N}2 | i ̸= j} is either a deterministic map or a stochastic process. Then the following statements hold: (i) if σ is a uniformly persistent map, then any evolution p converges in a finite number of steps to a centroidal Voronoi partition; and (ii) if σ is a randomly persistent stochastic process, then any evolution p converges almost surely in a finite number of steps to a centroidal Voronoi partition. Convergence to a centroidal Voronoi partition puts this pairwise optimization algorithm in the same class with centralized Lloyd methods. However, there can be a great number of possible centroidal Voronoi partitions for a given discretized environment and, in our experience, the algorithm too frequently converges to a suboptimal solution. This issue motivates the developments in the following Section. IV. PAIRWISE-OPTIMAL GOSSIP COVERAGE ALGORITHM In this section we present a novel gossip graph coverage algorithm which improves on the performance achievable by the Lloyd-type algorithm reviewed in the previous Section. First we introduce the following notational definition. Given p ∈P and distinct components pi and pj, let Ppi∪pj denote the set of all distinct pairs of vertices in pi ∪pj. We assume that the elements in Ppi∪pj are sorted lexicographi- cally. In formal terms, if pi ∪pj =  h1, . . . , h|pi∪pj| where hs < hs+1 for s = {1, . . . , |pi ∪pj| −1}, then Ppi∪pj =  (h1, h2), (h1, h3), . . . , (h1, h|pi∪pj|), (h2, h3), . . . . . . , (h|pi∪pj|−1, h|pi∪pj|) . Notice that |Ppi∪pj| = |pi∪pj| (|pi∪pj|−1) 2 . The pairwise-optimal discretized gossip coverage algo- rithm is defined as follows. Gossip Optimal Graph Coverage Algorithm At each time t ∈Z≥0, each agent i ∈{1, . . . , N} maintains in memory a connected subset pi(t). The collection p(0) = {p1(0), . . . , pN(0)} is an arbitrary connected N−partition of Q. At each t ∈Z≥0 a communicating pair, say (i, j) ∈ E(p(t)), is selected by a deterministic or stochastic process to be determined. Assume that i < j. Every agent k ̸∈{i, j} sets pk(t + 1) = pk(t), while i and j perform the following: 1: agent i transmits its subset pi(t) to j and vice-versa 2: both agents compute the set u = pi ∪pj, the function D : Pu →R>0 D((a, b)) = X h∈u min {du(h, a), du(h, b)} , and find the set SD = argmin(hs,hr)∈Pu {D(hs, hr)} 3: assuming SD is lexicographically ordered, both agents pick the first pair in SD, say (a∗, b∗) 4: both agents compute the sets Wa∗= {x ∈u : du(x, a∗) ≤du(x, b∗)} Wb∗= {x ∈u : du(x, b∗) < du(x, a∗)} 5: if H1(Cd(Wa∗); Wa∗) + H1(Cd(Wb∗); Wb∗) < H1(Cd(pi(t)); pi(t)) + H1(Cd(pj(t)); pj(t)) then 6: pi(t + 1) = Wa∗, pj(t + 1) = Wb∗ 7: else 8: pi(t + 1) = pi(t), pj(t + 1) = pj(t) 9: end if Remark IV.1 The lexicographic rule for picking (a∗, b∗) used here makes the dynamical system represented by the algorithm deterministic and well-defined. In practice any pair in SD can be chosen. The following Proposition characterizes a desirable prop- erty of the regions Wa∗and Wb∗. Proposition IV.2 The regions Wa∗and Wb∗as defined in Gossip Optimal Graph Coverage Algorithm, are connected. Thanks to Proposition IV.2 we have that, for any pair (i, j) ∈{1, . . . , N}2, i ̸= j, we can define the map Tij : P →P by Tij(p) = ( p, if (i, j) /∈E(p) {p1, . . . , bpi, . . . , bpj, . . . , pN}, otherwise, where bpi = Wa∗and bpj = Wb∗. Therefore, the dynamical system on the space of partitions can again be described in compact form by (1) and (2) but with this new Tij. To establish the convergence properties of the pairwise- optimal discretized gossip coverage algorithm we need the following definition. Definition IV.3 A partition p ∈P is said to be a pairwise- optimal partition if, for every (i, j) ∈E(p) H1(Cd(pi); pi) + H1(Cd(pj); pj) = min a,b∈pi∪pj    X k∈pi∪pj min  dpi∪pj(a, k), dpi∪pj(b, k)    The following Proposition characterizes the set of the pairwise-optimal partitions. Proposition IV.4 Let p ∈P be a pairwise-optimal partition. Then p is also a centroidal Voronoi partition. We are now ready to state the main result of this paper. Theorem IV.5 (Convergence under persistent gossip) Consider the pairwise-optimal discretized gossip coverage algorithm T and the evolutions p : Z≥0 →P defined by p(t + 1) = Tσ(t)(p(t)), for t ∈Z≥0, where σ : Z≥0 →{(i, j) ∈{1, . . ., N}2 | i ̸= j} is either a deterministic map or a stochastic process. Then the following statements hold: (i) if σ is a uniformly persistent map, then any evolution p converges in a finite number of steps to a pairwise- optimal partition; and (ii) if σ is a randomly persistent stochastic process, then any evolution p converges almost surely in a finite number of steps to a pairwise-optimal partition. In contrast to the Lloyd-type algorithm in Section III, this new pairwise-optimal algorithm converges to an element in the set of pairwise-optimal partitions. This result is a useful improvement as the set of pairwise-optimal partitions is a subset of the set of centroidal Voronoi partitions, so that the new algorithm can avoid many of the local minima in which Lloyd-type methods get stuck. We will demonstrate this improvement in Section VII. V. CONVERGENCE PROOFS In this Section we provide proofs of the results stated in the previous Section, starting with Proposition IV.2. Proof: [Proposition IV.2] To prove the statement of the Proposition we show that, given x ∈Wb∗, any shortest path in pi ∪pj connecting x to b∗completely belongs to Wb∗. We proceed by contradiction. Let sx,b∗denote a shortest path in pi ∪pj connecting x to b∗and let us assume that there exists m ∈sx,b∗such that m ∈Wa∗. For m to be in b∗means that dpi∪pj(m, b∗) < dpi∪pj(m, a∗). This implies that dpi∪pj(x, a∗) = dpi∪pj(m, a∗) + dpi∪pj(x, m) > dpi∪pj(m, b∗) + dpi∪pj(x, m) ≥dpi∪pj(x, b∗). This is a contradiction for x ∈b∗. Similar considerations hold for Wa∗. To prove Proposition IV.4 we need to review the notion of a centroidal Voronoi in pairs partition [14]. Definition V.1 Consider the connected graph G = (Q, E, w).. Let p ∈P and let G(p) be the associated adjacency graph. Then p ∈P is said to be centroidal Voronoi in pairs if, for any i ∈{1, . . . , N} we have that dpi∪pj(k, Cd(pi)) ≤dpi∪pj(k, Cd(pj)) (3) for all k ∈pi and for all j such that (i, j) ∈E(p). The following Lemma [14] states a useful equivalence property between the set of centroidal Voronoi in pairs partitions and the set of centroidal Voronoi partitions. Lemma V.2 A partition p ∈P is centroidal Voronoi in pairs if and only if it is centroidal Voronoi. We are now ready to prove Proposition IV.4. Proof: [Proposition IV.4] We will show that if a partition p ∈P is a pairwise-optimal partition then p is also centroidal Voronoi in pairs. Then from Lemma V.2 it will follow that p is also centroidal Voronoi. We proceed by contradiction. Let p ∈P be a pairwise- optimal partition, let pi and pj be two adjacent regions, and let us assume that there exists x ∈pi such that dpi∪pj(x, Cd(pi)) > dpi∪pj(x, Cd(pj)). (4) Let sx,Cd(pj) denote a shortest path in pi ∪pj connecting x to Cd(pj). Without loss of generality let us assume that sx,Cd(pj) = (x, y1, y2, . . . , ym, Cd(pj)), for a suitable m- tuple in pi ∪pj. Now let s(i) x,Cd(pj) denote the subset of sx,Cd(pj) consisting of only the vertices belonging to pi, i.e., s(i) x,Cd(pj) =  y ∈sx,Cd(pj)|y ∈pi . Observe that from (4) it follows that dpi∪pj(y, Cd(pi)) > dpi∪pj(y, Cd(pj)) for all y ∈s(i) x,Cd(pj). Therefore, by letting ¯pi = pi \ s(i) x,Cd(pj) and ¯pj = pj ∪s(i) x,Cd(pj) we have that H1(Cd(¯pi); ¯pi) + H1(Cd(¯pj); ¯pj) ≤H1(Cd(pi); ¯pi) + H1(Cd(pj); ¯pj) < H1(Cd(pi); pi) + H1(Cd(pj); pj). This last inequality contradicts the fact that p is a pairwise- optimal partition. To provide the proof of Theorem IV.5 we need the following intermediate result. Lemma V.3 Let T : P ⇒P be the point-to-set map defined for the Gossip Optimal Graph Coverage Algorithm. If p(t) ∈ P and p(t + 1) ∈T (p(t)) \ p(t), then Hexpected(p(t + 1)) < Hexpected(p(t)). Proof: Without loss of generality assume that (i, j) is the pair selected at time t. For simplicity let us denote p(t + 1) and p(t), respectively, by p+ and p. Then Hexpected(p+) −Hexpected(p) = H1(Cd(p+ i ); p+ i ) + H1(Cd(p+ j ); p+ j ) −(H1(Cd(pi); pi) + H1(Cd(pj); pj)). According to the definition of the Gossip Optimal Graph Coverage Algorithm we have that if p+ i ̸= pi, p+ j ̸= pj, then H1(Cd(p+ i ); p+ i ) + H1(Cd(p+ j ); p+ j ) < H1(Cd(pi); pi) + H1(Cd(pj); pj) from which the thesis follows. Now we can prove the main result of this paper. Proof: [Theorem IV.5] The proof of point (i) of the Theorem is based on on verifying the assumptions (i), (ii), (iii), (iv) of Theorem 4.3 from [13]. We start with the following topological consideration. Let A, B ⊂Q, A∆B be their symmetric difference, and let |A| be the “points counting measure” of A, that is the number of elements of A. Then if we define d∆(A, B) = |A∆B| , we have that d∆is a distance on the set of the subsets of Q, which we denote 2Q. Since the points counting measure takes integer values, 2Q a discrete topological space. Next, consider the product space (2Q)N and let q = {q1, . . . , qN} and ¯q = {¯q1, . . . , ¯qN} be two its elements. Then, thanks to results valid for product topological spaces, we have that the function d(N) ∆(q, ¯q) = PN i=1 d (qi, ¯qi) is a distance on (2Q)N. Hence, (2Q)N is also a discrete topological space. Observe that P is a subset of (2Q)N. Since 2Q, (2Q)N and P are finite, they are also trivially compact. Moreover, since the algorithm T : P ⇒P is well-defined, we have that P is strongly positively invariant. This fact implies that assumption (i) of Theorem 4.3 from [13] is satisfied. From Lemma V.3 it follows that assumption (ii) is also satisfied, with Hexpected playing the role of the function U. Next, the fact that all maps from a discrete space are continuous implies the continuity of the maps Tij and Hexpected, thus guaranteeing the validity of assumption (iii). Assumption (iv) holds true for the hypothesis made in the Fig. 1. At left, ten robots are positioned at the centroids of their initial partitions in a non-convex environment. The boundary of each agent’s partition is drawn in a different color. The middle shows the final solution of a centralized Lloyd optimization with a total cost of 624.1m. At right is a final solution for the pairwise-optimal discretized gossip coverage algorithm starting from the final centralized Lloyd solution, with an improved cost of 610.3m. statement of Theorem IV.5 that σ is a uniformly persistent map. Hence we are in the position to apply Theorem 4.3 from [13], and conclude convergence to the intersection of the equilibria of the maps Tij, which, according to the definition of Tij coincides with the set of the pairwise- optimal partitions. Hence, since that set is finite, we can argue that the system converges in finite time to one pairwise- optimal partition. A proof of (ii) in Theorem IV.5 can be made in a similar way using Theorem 4.5 from [13] inplace of 4.3. VI. SCALABILITY PROPERTIES In this Section we discuss how to compute the optimal new centroids (a∗, b∗) ∈Ppi∪pj for the Gossip Optimal Graph Coverage Algorithm, as well as a sampling method to greatly reduce the computational complexity. Determining (a∗, b∗) requires an exhaustive search over all possible pairs of vertices for a pair with the lowest cost to cover pi ∪pj. Using Johnson’s all pairs shortest paths algorithm as a first step to compute a pairwise distance matrix for pi∪pj, (a∗, b∗) can be found in O(|pi|3) with a memory requirement of O(|pi|2) (as pi ∪pj is of order |pi|). For mobile robots with limited onboard resources, these requirements may be too steep. In such circumstances, we propose instead to sample pairs of potential new centroids when applying the algorithm. The first sample pair would be the agents’ previous centroids, with the rest drawn at random from the set Ppi∪pj. For m sample pairs, this approach requires 2m calls to Dijkstra’s one-to-all shortest paths algorithm to find the pair with the lowest cost, for a total time complexity of O(m|pi| log(|pi|)) and a memory requirement of O(|pi|). It is also worth noting that if all edge weights in G are equal (i.e., for a regular grid discretization), then a breadth-first-search approach can replace Dijkstra and the time complexity drops to O(m|pi|). This sample-based approach greatly reduces the time and memory requirements, and will still converge to a pairwise-optimal partition. VII. SIMULATION RESULTS To demonstrate the utility of the proposed gossip coverage algorithm, we implemented it and other coverage algorithms using the open-source Player/Stage robot software system [15] and the Boost Graph Library (BGL) [16]. All results presented here were generated using Player 2.1.1, Stage 2.1.0, and BGL 1.34.1. A non-convex environment was specified with a bitmap and overlaid with a 0.1m resolution occupancy grid, producing a lattice-like graph with all edge weights equal to 0.1m. To compute distances on graphs with uniform edge weights we extended the BGL implementation of breadth-first-search with a distance recorder event visitor. Figure 1 provides one example of how convergence to the set of pairwise-optimal partitions represents an improvement over Lloyd-type methods. On the left is the non-convex environment used for all results in this Section, as well as an initial partition for 10 robots. The middle panel shows the result of a centralized Lloyd optimization where all agents iteratively update their centroid and partition based on the centroids of all other agents. The final equilibrium for this centralized method is a centroidal Voronoi partition with a total cost of 624.1m. However, this solution is not a pairwise-optimal partition. We started the pairwise-optimal discretized gossip coverage algorithm using this partition as the initial condition. After 70 pairwise exchanges between random agent pairs, the algorithm reached the pairwise- optimal partition at right which has a lower cost of 610.3. The best known 10-partition of this map has cost 610.0. Figure 2 compares 100 simulations of the Lloyd-type and pairwise-optimal discretized gossip coverage algorithms. We started each simulation from the initial partition in Fig. 1 and used different random sequences of agent pairs for each case. The new pairwise-optimal algorithm shows marked improvement over the Lloyd-type gossip algorithm, achieving a total cost within 2% of the best known cost in 85% of trials, while also avoiding the worst local minima. Figure 3 compares final cost histograms for 10 random initial conditions for the same environment. Each initial condition was created by selecting unique starting locations for the agents uniformly at random, and using these locations to generate a Voronoi partition. The histograms compare 20 simulations of Lloyd-type and the new pairwise-optimal gossip coverage starting from the same initial partition but 610 620 630 640 650 660 670 680 0 10 20 30 40 50 60 ag replacements Simulation count Final total cost (m) Fig. 2. Histograms of final total costs for 100 simulations of pairwise- optimal (gray) and Lloyd-type (black) gossip coverage. All runs started from the initial partition in Fig. 1 with different random sequences of agent pairs. The dashed red line shows the final cost using a centralized Lloyd algorithm. with different random orders of exchanges. The centralized Lloyd final cost for each initial condition is also shown. The new pairwise-optimal method outperforms both Lloyd- type methods for all 10 tests, although the Lloyd-type gossip method is close in two of the trials. These results illustrate that convergence to a pairwise-optimal partition represents a significant performance enhancement over classic Lloyd methods. Interestingly, the Lloyd-type gossip algorithm also substantially outperforms the centralized version in 8 of the trials. We speculate this is due to the gossip method taking trajectories through the space of connected N−partitions which are not possible for the centralized approach. VIII. CONCLUSIONS We have presented a novel distributed coverage control algorithm which requires only pairwise communication be- tween agents. The classic Lloyd approach to optimizing quantizer placement involves iteration of separate centering and Voronoi partitioning steps. In the graph coverage domain, the separation of centroid and partition optimization seems unnecessary computationally for gossip algorithms. More importantly, we have shown that improved performance can be achieved without this separation. Our new pairwise- optimal discretized gossip coverage algorithm provably con- verges to a subset of the centroidal Voronoi partitions which we labeled the set of pairwise-optimal partitions. Through numerical comparisons we demonstrated that this new subset of solutions avoids many of the local minima in which both gossip and centralized Lloyd-type algorithms can get stuck. REFERENCES [1] E. Fiorelli, N. E. Leonard, P. Bhatta, D. A. Paley, R. Bachmayer, and D. M. Fratantoni, “Multi-AUV control and adaptive sampling in Monterey Bay,” IEEE Journal of Oceanic Engineering, vol. 31, no. 4, pp. 935–948, 2006. [2] P. R. Wurman, R. D’Andrea, and M. Mountz, “Coordinating hundreds of cooperative, autonomous vehicles in warehouses,” AI Magazine, vol. 29, no. 1, pp. 9–20, 2008. [3] F. Bullo, J. Cort´es, and S. Mart´ınez, Distributed Control of Robotic Networks. Applied Mathematics Series, Princeton University Press, 2009. Available at http://www.coordinationbook.info. [4] S. P. Lloyd, “Least squares quantization in PCM,” IEEE Transactions on Information Theory, vol. 28, no. 2, pp. 129–137, 1982. Presented as Bell Laboratory Technical Memorandum at a 1957 Institute for Mathematical Statistics meeting. 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 0 10 20 620 640 660 680 700 0 10 20 PSfrag replacements Simulation count Final total cost (m) Fig. 3. Histograms of final costs for simulations starting from 10 random initial conditions for the environment in Fig. 1. The pairwise-optimal (gray) and Lloyd-type (black) gossip coverage algorithms each ran 20 times per initial condition using different random sequences of agent pairs. The dashed red line shows the final cost using a centralized Lloyd algorithm. [5] C. Gao, J. Cort´es, and F. Bullo, “Notes on averaging over acyclic digraphs and discrete coverage control,” Automatica, vol. 44, no. 8, pp. 2120–2127, 2008. [6] V. V. Vazirani, Approximation Algorithms. Springer, 2001. [7] M. Zhong and C. G. Cassandras, “Distributed coverage control in sensor network environments with polygonal obstacles,” in IFAC World Congress, (Seoul, Korea), pp. 4162–4167, July 2008. [8] C. H. Caicedo-N`u˜nez and M. ˇZefran, “Performing coverage on nonconvex domains,” in IEEE Conf. on Control Applications, (San Antonio, TX), pp. 1019–1024, Sept. 2008. [9] L. C. A. Pimenta, V. Kumar, R. C. Mesquita, and G. A. S. Pereira, “Sensing and coverage for a network of heterogeneous robots,” in IEEE Conf. on Decision and Control, (Canc´un, M´exico), pp. 3947– 3952, Dec. 2008. [10] O. Baron, O. Berman, D. Krass, and Q. Wang, “The equitable location problem on the plane,” European Journal of Operational Research, vol. 183, no. 2, pp. 578–590, 2007. [11] S. Yun, M. Schwager, and D. Rus, “Coordinating construction of truss structures using distributed equal-mass partitioning,” in International Symposium on Robotics Research, (Lucerne, Switzerland), Aug. 2009. [12] M. Schwager, D. Rus, and J. J. Slotine, “Decentralized, adaptive coverage control for networked robots,” International Journal of Robotics Research, vol. 28, no. 3, pp. 357–375, 2009. [13] F. Bullo, R. Carli, and P. Frasca, “Gossip coverage control for robotic networks: Dynamical systems on the the space of partitions,” Dec. 2009. Available at http://arxiv.org/abs/0903.3642. [14] J. W. Durham, R. Carli, P. Frasca, and F. Bullo, “Discrete partitioning and coverage control with gossip communication,” in ASME Dynamic Systems and Control Conference, (Hollywood, CA), Oct. 2009. [15] B. Gerkey, R. T. Vaughan, and A. Howard, “The Player/Stage Project.” http://playerstage.sourceforge.net, June 2008. Ver- sion 2.11. [16] J. G. Siek, L.-Q. Lee, and A. Lumsdaine, “Boost Graph Library.” http://www.boost.org, July 2007. Version 1.34.1.