A Certifiably Correct Algorithm for Synchronization over the Special Euclidean Group David M. Rosen⋆1, Luca Carlone2, Afonso S. Bandeira3, and John J. Leonard1 1 Computer Science and Artificial Intelligence Laboratory, Massachusetts Institute of Technology, Cambridge, MA 02139, USA 2 Laboratory for Information and Decision Systems, Massachusetts Institute of Technology, Cambridge, MA 02139, USA 3 Department of Mathematics and Center for Data Science, Courant Institute of Mathematical Sciences, New York University, New York, NY 10012, USA Abstract. Many important geometric estimation problems naturally take the form of synchronization over the special Euclidean group: es- timate the values of a set of unknown poses x1, . . . , xn ∈SE(d) given noisy measurements of a subset of their pairwise relative transforms x−1 i xj. Examples of this class include the foundational problems of pose- graph simultaneous localization and mapping (SLAM) (in robotics) and camera pose estimation (in computer vision), among others. This prob- lem is typically formulated as a maximum-likelihood estimation that requires solving a nonconvex nonlinear program, which is computation- ally intractable in general. Nevertheless, in this paper we present an algorithm that is able to efficiently recover certifiably globally optimal solutions of this estimation problem in a non-adversarial noise regime. The crux of our approach is the development of a semidefinite relaxation of the maximum-likelihood estimation whose minimizer provides the ex- act MLE so long as the magnitude of the noise corrupting the avail- able measurements falls below a certain critical threshold; furthermore, whenever exactness obtains, it is possible to verify this fact a posteriori, thereby certifying the optimality of the recovered estimate. We develop a specialized optimization scheme for solving large-scale instances of this semidefinite relaxation by exploiting its low-rank, geometric, and graph- theoretic structure to reduce it to an equivalent optimization problem on a low-dimensional Riemannian manifold, and then design a Riemannian truncated-Newton trust-region method to solve this reduction efficiently. We combine this fast optimization approach with a simple rounding pro- cedure to produce our algorithm, SE-Sync. Experimental evaluation on a variety of simulated and real-world pose-graph SLAM datasets shows that SE-Sync is capable of recovering globally optimal solutions when the available measurements are corrupted by noise up to an order of mag- nitude greater than that typically encountered in robotics applications, and does so at a computational cost that scales comparably with that of direct Newton-type local search techniques. ⋆Corresponding author. Email: dmrosen@mit.edu arXiv:1611.00128v3 [cs.RO] 10 Feb 2017 1 Introduction Over the coming decades, the increasingly widespread adoption of robotic tech- nology in areas such as transportation, medicine, and disaster response has tremendous potential to increase productivity, alleviate suffering, and preserve life. At the same time, however, these high-impact applications often place au- tonomous systems in safety- and life-critical roles, where misbehavior or un- detected failures can carry dire consequences [43]. While empirical evaluation has traditionally been a driving force in the design and implementation of au- tonomous systems, safety-critical applications such as these demand algorithms that come with clearly-delineated performance guarantees. This paper presents one such algorithm, SE-Sync, an efficient and certifiably correct method for solv- ing the fundamental problem of pose estimation. Formally, we consider the synchronization problem of estimating a collec- tion of unknown poses1 based upon a set of relative measurements between them. This estimation problem lies at the core of many fundamental percep- tual problems in robotics; for example, simultaneous localization and mapping (SLAM) [28] and multi-robot localization [3]. Closely-related formulations also arise in structure from motion [23, 30] and camera network calibration [40] (in computer vision), sensor network localization [33], and cryo-electron microscopy [37]. These synchronization problems are typically formulated as instances of maximum-likelihood estimation under an assumed probability distribution for the measurement noise. This formulation is attractive from a theoretical stand- point due to the powerful analytical framework and strong performance guaran- tees that maximum-likelihood estimation affords [20]. However, this formal rigor comes at the expense of computational tractability, as the maximum-likelihood formulation leads to a nonconvex optimization problem that is difficult to solve. Related Work. In the context of SLAM, the pose synchronization prob- lem is commonly solved using iterative numerical optimization methods, e.g. Gauss-Newton [26–28], gradient descent [22, 32], or trust region methods [34]. This approach is particularly attractive because the rapid convergence speed of second-order numerical optimization methods [31], together with their ability to exploit the measurement sparsity that typically occurs in naturalistic problem instances [18], enables these techniques to scale efficiently to large problem sizes while maintaining real-time operation. However, this computational expedience comes at the expense of reliability, as their restriction to local search renders these methods vulnerable to convergence to suboptimal critical points, even for relatively small noise levels [14, 35]. This observation, together with the fact that suboptimal critical points usually correspond to egregiously wrong trajectory estimates, has motivated two general lines of research. The first addresses the initialization problem, i.e., how to compute a suitable initial guess for iterative refinement; examples of this effort are [12, 15, 35]. The second aims at a deeper 1 A pose is a position and orientation in d-dimensional Euclidean space; this is an element of the special Euclidean group SE(d) ∼= Rd ⋊SO(d). understanding of the global structure of the pose synchronization problem (e.g. number of local minima, convergence basin), see for example [24, 25, 44]. Contribution. In our previous work [13, 14, 16], we demonstrated that La- grangian duality provides an effective means of certifying the optimality of an in-hand solution for the pose synchronization problem, and could in principle be used to directly compute such certifiably optimal solutions by solving a La- grangian relaxation. However, this relaxation turns out to be a semidefinite pro- gram (SDP), and while there do exist mature general-purpose SDP solvers, their high per-iteration computational cost limits their practical utility to instances of this relaxation involving only a few hundred poses,2 whereas real-world pose synchronization problems are typically one to two orders of magnitude larger. The main contribution of the present paper is the development of a spe- cialized structure-exploiting optimization procedure that is capable of efficiently solving large-scale instances of the semidefinite relaxation in practice. This pro- cedure provides a means of recovering certifiably globally optimal solutions of the pose synchronization problem from the semidefinite relaxation within a non- adversarial noise regime in which minimizers of the latter correspond to exact so- lutions of the former. Our overall pose synchronization method, SE-Sync, is thus a certifiably correct algorithm [4], meaning that it is able to efficiently recover globally optimal solutions of generally intractable problems within a restricted range of operation, and certify the optimality of the solutions so obtained. Ex- perimental evaluation on a variety of simulated and real-world pose-graph SLAM datasets shows that our relaxation remains exact when the available measure- ments are corrupted by noise up to an order of magnitude greater than that typically encountered in application, and that within this regime, SE-Sync is able to recover globally optimal solutions from this relaxation at a computa- tional cost comparable with that of direct Newton-type local search techniques. 2 Problem formulation The SE(d) synchronization problem consists of estimating the values of a set of n unknown poses x1, . . . , xn ∈SE(d) given noisy measurements of m of their pairwise relative transforms xij ≜x−1 i xj (i ̸= j). We model the set of available measurements using an undirected graph G = (V, E) in which the nodes i ∈V are in one-to-one correspondence with the unknown poses xi and the edges {i, j} ∈E are in one-to-one correspondence with the set of available measurements, and we assume without loss of generality that G is connected.3 We let −→ G = (V, −→ E ) be a directed graph obtained from G by fixing an orientation for each of its edges, 2 This encompasses the most commonly-used interior-point-based SDP software li- braries, including SDPA, SeDuMi, SDPT3, CSDP, and DSDP. 3 If G is not connected, then the problem of estimating the unknown poses x1, . . . , xn decomposes into a set of independent estimation problems that are in one-to-one correspondence with the connected components of G; thus, the general case is always reducible to the case of connected graphs. and assume that a noisy measurement ˜xij of each relative pose xij = (tij, Rij) is obtained by sampling from the following probabilistic generative model: ˜tij = ¯tij + tϵ ij, tϵ ij ∼N 0, τ −1 ij Id  , ˜Rij = ¯RijRϵ ij, Rϵ ij ∼Langevin (Id, κij) , ∀(i, j) ∈−→ E . (1) Here ¯xij = (¯tij, ¯Rij) is the true (latent) value of xij, N(µ, Σ) denotes the standard multivariate Gaussian distribution with mean µ ∈Rd and covariance Σ ⪰0, and Langevin(M, κ) denotes the isotropic Langevin distribution on SO(d) with mode M ∈SO(d) and concentration parameter κ ≥0 (this is the distribu- tion on SO(d) whose probability density function is given by: p(R; M, κ) = 1 cd(κ) exp κ tr(M TR)  (2) with respect to the Haar measure [17]).4 Finally, we define ˜xji ≜˜x−1 ij , κji ≜κij, τji ≜τij, and ˜Rji ≜˜RT ij for all (i, j) ∈−→ E . Given a set of noisy measurements ˜xij sampled from the generative model (1), a straightforward computation shows that a maximum-likelihood estimate ˆxMLE ∈SE(d)n for the poses x1, . . . , xn is obtained as a minimizer of: Problem 1 (Maximum-likelihood estimation for SE(d) synchronization). p∗ MLE = min ti∈Rd Ri∈SO(d) X (i,j)∈− → E κij∥Rj −Ri ˜Rij∥2 F + τij tj −ti −Ri˜tij 2 2 (3) Unfortunately, Problem 1 is a high-dimensional, nonconvex nonlinear pro- gram, and is therefore computationally hard to solve in general. Consequently, our strategy in this paper will be to approximate this problem using a (con- vex) semidefinite relaxation [42], and then exploit this relaxation to search for solutions of the original (hard) problem. 3 Forming the semidefinite relaxation In this section we develop the semidefinite relaxation that we will solve in place of the maximum-likelihood estimation Problem 1.5 To that end, our first step will be to rewrite Problem 1 in a simpler and more compact form that emphasizes the structural correspondences between the optimization problem (3) and several simple graph-theoretic objects that can be constructed from the set of available measurements ˜xij and the graphs G and −→ G. 4 We use a directed graph to model the measurements ˜xij sampled from (1) because the distribution of the noise corrupting the latent values ¯xij is not invariant under SE(d)’s group inverse operation. Consequently, we must keep track of which state xi was the “base frame” for each measurement. 5 Due to space limitations, we omit all derivations and proofs; please see the extended version of this paper [36] for detailed derivations and additional results. We define the translational weight graph W τ = (V, E, {τij}) to be the weighted undirected graph with node set V, edge set E, and edge weights τij for {i, j} ∈E. The Laplacian L(W τ) of W τ is then: L(W τ)ij =      P {i,k}∈E τik, i = j, −τij, {i, j} ∈E, 0, {i, j} /∈E. (4) Similarly, let L( ˜Gρ) denote the connection Laplacian for the rotational syn- chronization problem determined by the measurements ˜Rij and measurement weights κij for (i, j) ∈−→ E ; this is the symmetric (d × d)-block-structured matrix determined by (cf. [38, 45]): L( ˜Gρ) ∈Sym(dn) L( ˜Gρ)ij ≜        P {i,k}∈E κik  Id, i = j, −κij ˜Rij, {i, j} ∈E, 0d×d, {i, j} /∈E. (5) We also define a few matrices constructed from the set of translational obser- vations ˜tij. We let ˜V ∈Rn×dn be the (1 × d)-block-structured matrix with (i, j)-blocks determined by: ˜Vij ≜      P {k∈V|(j,k)∈− → E } τjk˜tT jk, i = j, −τji˜tT ji, (j, i) ∈−→ E , 01×d, otherwise, (6) ˜T ∈Rm×dn denote the (1 × d)-block-structured matrix with rows and columns indexed by e ∈−→ E and k ∈V, respectively, and whose (e, k)-block is given by: ˜Tek ≜ ( −˜tT kj, e = (k, j) ∈−→ E , 01×d, otherwise, (7) and Ω≜Diag(τe1, . . . , τem) ∈Sym(m) denote the diagonal matrix indexed by the directed edges e ∈−→ E , and whose eth element gives the precision of the translational measurement ˜tij corresponding to that edge. Finally, we also aggregate the rotational and translational state estimates into the block matrices R ≜ R1 · · · Rn  ∈SO(d)n ⊂Rd×dn and t ≜ t1 . . . tn  ∈Rdn. With these definitions in hand, let us return to Problem 1. We observe that for a fixed value of the rotational states R1, . . . , Rn, this problem reduces to the unconstrained minimization of a quadratic form in the translational variables t1, . . . , tn ∈Rd, for which we can find a closed-form solution using a generalized Schur complement [21, Proposition 4.2]. This observation enables us to ana- lytically eliminate the translational states from the optimization problem (3), thereby obtaining the simplified but equivalent maximum-likelihood estimation: Problem 2 (Simplified maximum-likelihood estimation). p∗ MLE = min R∈SO(d)n tr( ˜QRTR) (8a) ˜Q = L( ˜Gρ) + ˜T TΩ 1 2 ΠΩ 1 2 ˜T. (8b) Furthermore, given any minimizer R∗of Problem 2, we can recover a correspond- ing optimal value t∗for t according to: t∗= −vec  R∗˜V TL(W τ)† . (9) In (8b) Π ∈Rm×m is the matrix of the orthogonal projection operator onto ker(A(−→ G)Ω 1 2 ) ⊆Rm×m, where A(−→ G) ∈Rn×m is the incidence matrix of the directed graph −→ G. Although Π is generically dense, by exploiting the fact that it is derived from a sparse graph, we have been able to show that it admits the sparse decomposition: Π = Im −Ω 1 2 ¯A(−→ G)TL−TL−1 ¯A(−→ G)Ω 1 2 (10) where ¯A(−→ G)Ω 1 2 = LQ1 is a thin LQ decomposition of ¯A(−→ G)Ω 1 2 and ¯A(−→ G) is the reduced incidence matrix of −→ G. Note that expression (10) requires only the sparse lower-triangular factor L, which can be easily and efficiently obtained in practice. Decomposition (10) will play a critical role in the implementation of our efficient optimization. Now we derive the semidefinite relaxation of Problem 2 that we will solve in practice, exploiting the simplified form (8). We begin by relaxing the condition R ∈SO(d)n to R ∈O(d)n. The advantage of this latter version is that O(d) is defined by a set of (quadratic) orthonormality constraints, so the orthogonally- relaxed version of Problem 2 is a quadratically constrained quadratic program; consequently, its Lagrangian dual relaxation is a semidefinite program [29]: Problem 3 (Semidefinite relaxation for SE(d) synchronization). p∗ SDP = min 0⪯Z∈Sym(dn) tr( ˜QZ) s.t. BlockDiagd×d(Z) = Diag(Id, . . . , Id) (11) At this point it is instructive to compare the semidefinite relaxation (11) with the simplified maximum-likelihood estimation (8). For any R ∈SO(d)n, the product Z = RTR is positive semidefinite and has identity matrices along its (d × d)-block-diagonal, and so is a feasible point of (11); in other words, (11) can be regarded as a relaxation of the maximum-likelihood estimation obtained by expanding (8)’s feasible set. This immediately implies that p∗ SDP ≤p∗ MLE. Furthermore, if it happens that a minimizer Z∗of Problem 3 admits a decompo- sition of the form Z∗= R∗TR∗for some R∗∈SO(d)n, then it is straightforward to verify that this R∗is also a minimizer of Problem 2, and so provides a globally optimal solution of the maximum-likelihood estimation Problem 1 via (9). The crucial fact that justifies our interest in Problem 3 is that (as demonstrated em- pirically in our prior work [14] and investigated in a simpler setting in [5]) this problem has a unique minimizer of just this form so long as the noise corrupting the available measurements ˜xij is not too large. More precisely, we prove:6 Proposition 1. Let ¯ Q be the matrix of the form (8b) constructed using the true (latent) relative transforms ¯xij in (1). There exists a constant β ≜β( ¯ Q) > 0 (depending upon ¯ Q) such that, if ∥˜Q − ¯ Q∥2 < β, then: (i) The semidefinite relaxation Problem 3 has a unique solution Z∗, and (ii) Z∗= R∗TR∗, where R∗∈SO(d)n is a minimizer of the maximum-likelihood estimation Problem 2. 4 The SE-Sync algorithm 4.1 Solving the semidefinite relaxation As a semidefinite program, Problem 3 can in principle be solved in polynomial- time using interior-point methods [39, 42]. In practice, however, the high compu- tational cost of general-purpose semidefinite programming algorithms prevents these methods from scaling effectively to problems in which the dimension of the decision variable Z is greater than a few thousand [39]. Unfortunately, typical instances of Problem 3 that are encountered in robotics and computer vision ap- plications are one to two orders of magnitude larger than this maximum effective problem size, and are therefore well beyond the reach of these general-purpose methods. Consequently, in this subsection we develop a specialized optimization procedure for solving large-scale instances of Problem 3 efficiently. Simplifying Problem 3 The dominant computational cost when applying general-purpose semidefinite programming methods to solve Problem 3 is the need to store and manipulate expressions involving the (large, dense) matrix variable Z. However, in the typical case that exactness holds, we know that the actual solution Z∗of Problem 3 that we seek has a very concise description in the factored form Z∗= R∗TR∗for R∗∈SO(d)n. More generally, even in those cases where exactness fails, minimizers Z∗of Problem 3 generically have a rank r not much greater than d, and therefore admit a symmetric rank decomposition Z∗= Y ∗TY ∗for Y ∗∈Rr×dn with r ≪dn. In a pair of papers, Burer and Monteiro [10, 11] proposed an elegant general approach to exploit the fact that large-scale semidefinite programs often admit such low-rank solutions: simply replace every instance of the decision variable Z with a rank-r product of the form Y TY to produce a rank-restricted version of the original problem. This substitution has the two-fold effect of (i) dramatically 6 Please see the extended version of this paper [36] for the proof. reducing the size of the search space and (ii) rendering the positive semidefinite- ness constraint redundant, since Y TY ⪰0 for any choice of Y . The resulting rank-restricted form of the problem is thus a low-dimensional nonlinear pro- gram, rather than a semidefinite program. Furthermore, following Boumal [6] we observe that after replacing Z in Prob- lem 3 with Y TY for Y = Y1 · · · Yn  ∈Rr×dn, the block-diagonal constraints in our specific problem of interest (11) are equivalent to Y T i Yi = Id, for all i ∈[n], i.e., the columns of each block Yi ∈Rr×d form an orthonormal frame. In general, the set of all orthonormal k-frames in Rp (k ≤n): St(k, p) ≜  Y ∈Rp×k | Y TY = Ik (12) forms a smooth compact matrix manifold, called the Stiefel manifold, which can be equipped with a Riemannian metric induced by its embedding into the ambi- ent space Rp×k [2, Sec. 3.3.2]. Together, these observations enable us to reduce Problem 3 to an equivalent unconstrained Riemannian optimization problem defined on a product of Stiefel manifolds: Problem 4 (Rank-restricted semidefinite relaxation, Riemannian optimization form). p∗ SDPLR = min Y ∈St(d,r)n tr( ˜QY TY ). (13) This is the optimization problem that we will actually solve in practice. Ensuring optimality While the reduction from Problem 3 to Problem 4 dra- matically reduces the size of the optimization problem that needs to be solved, it comes at the expense of (re)introducing the quadratic orthonormality constraints (12). It may therefore not be clear whether anything has really been gained by relaxing Problem 2 to Problem 4, since it appears that we may have simply re- placed one difficult nonconvex optimization problem with another. The following remarkable result (adapted from Boumal et al. [9]) justifies this approach: Proposition 2 (A sufficient condition for global optimality in Problem 4). If Y ∈St(d, r)n is a (row) rank-deficient second-order critical point7 of Problem 4, then Y is a global minimizer of Problem 4 and Z∗= Y TY is a solution of the dual semidefinite relaxation Problem 3. Proposition 2 immediately suggests a procedure for obtaining solutions Z∗of Problem 3 by applying a Riemannian optimization method to search successively higher levels of the rank-restricted hierarchy of relaxations (13) until a rank- deficient second-order critical point is obtained.8 This algorithm is referred to as the Riemannian Staircase [6, 9]. 7 That is, a point satisfying grad F(Y ) = 0 and Hess F(Y ) ⪰0 (cf. (14)–(17)). 8 Note that since every Y ∈St(d, r)n is row rank-deficient for r > dn, this procedure is guaranteed to recover an optimal solution after searching at most dn + 1 levels of the hierarchy (13). A Riemannian optimization method for Problem 4 Proposition 2 pro- vides a means of obtaining global minimizers of Problem 3 by locally searching for second-order critical points of Problem 4. To that end, in this subsection we design a Riemannian optimization method that will enable us to rapidly identify these critical points in practice. Equations (8b) and (10) provide an efficient means of computing products with ˜Q by performing a sequence of sparse matrix multiplications and sparse triangular solves (i.e., without the need to form the dense matrix ˜Q directly). These operations are sufficient to evaluate the objective appearing in Problem 4, as well as the corresponding gradient and Hessian-vector products when con- sidered as a function on the ambient Euclidean space Rr×dn: F(Y ) ≜tr( ˜QY TY ), ∇F(Y ) = 2Y ˜Q, ∇2F(Y )[ ˙Y ] = 2 ˙Y ˜Q. (14) Furthermore, there are simple relations between the ambient Euclidean gradient and Hessian-vector products in (14) and their corresponding Riemannian coun- terparts when F(·) is viewed as a function restricted to St(d, r)n ⊂Rr×dn. With reference to the orthogonal projection operator [19, eq. (2.3)]: ProjY : TY Rr×dn →TY (St(d, r)n) ProjY (X) = X −Y SymBlockDiagd×d(Y TX) (15) the Riemannian gradient grad F(Y ) is simply the orthogonal projection of the ambient Euclidean gradient ∇F(Y ) (cf. [2, eq. (3.37)]): grad F(Y ) = ProjY ∇F(Y ). (16) Similarly, the Riemannian Hessian-vector product Hess F(Y )[ ˙Y ] can be obtained as the orthogonal projection of the ambient directional derivative of the gradient vector field grad F(Y ) in the direction of ˙Y (cf. [2, eq. (5.15)]). A straightforward computation shows that this is given by: Hess F(Y )[ ˙Y ] = ProjY (∇2F(Y )[ ˙Y ] −˙Y SymBlockDiagd×d(Y T∇F(Y ))). (17) Together, equations (8b), (10), and (14)–(17) provide an efficient means of computing F(Y ), grad F(Y ), and Hess F(Y )[ ˙Y ]. Consequently, we propose to employ the truncated-Newton Riemannian Trust-Region (RTR) method [1, 8] to efficiently compute high-precision estimates of second-order critical points of Problem 4 in practice. 4.2 Rounding the solution In the previous subsection, we described an efficient algorithmic approach for computing minimizers Y ∗∈St(d, r)n of Problem 4 that correspond to solutions Z∗= Y ∗TY ∗of Problem 3. However, our ultimate goal is to extract an optimal solution of Problem 2 from Z∗whenever exactness holds, and a feasible approx- imate solution otherwise. In this subsection, we develop a rounding procedure satisfying these criteria. Algorithm 1 Rounding procedure for solutions of Problem 4 Input: An optimal solution Y ∗∈St(d, r)n of Problem 4. Output: A feasible point ˆR ∈SO(d)n. 1: function RoundSolution(Y ∗) 2: Compute a rank-d truncated singular value decomposition UdΞdV T d for Y ∗ and assign ˆR ←ΞdV T d . 3: Set N+ ←|{ ˆRi | det( ˆRi) > 0}|. 4: if N+ < ⌈n 2 ⌉then 5: ˆR ←Diag(1, . . . , 1, −1) ˆR. 6: end if 7: for i = 1, . . . , n do 8: Set ˆRi ←NearestRotation( ˆRi). ▷See e.g. [41] 9: end for 10: return ˆR 11: end function To begin, let us consider the (typical) case in which exactness obtains; here Y ∗TY ∗= Z∗= R∗TR∗for some optimal solution R∗∈SO(d)n of Problem 2. Since rank(R∗) = d, this implies that rank(Y ∗) = d as well. Consequently, letting Y ∗= UdΞdV T d denote a (rank-d) thin singular value decomposition of Y ∗, and defining ¯Y ≜ΞdV T d ∈Rd×dn, it follows that ¯Y T ¯Y = Z∗= R∗TR∗. This last equality implies that the d × d block-diagonal of ¯Y T ¯Y satisfies ¯Y T i ¯Yi = Id for all i ∈[n], i.e. ¯Y ∈O(d)n. Similarly, comparing the elements of the first block rows of ¯Y T ¯Y and R∗TR∗shows that ¯Y T 1 ¯Yj = R∗ 1R∗ j for all j ∈[n]. Left- multiplying this set of equalities by ¯Y1 and letting A = ¯Y1R∗ 1 shows ¯Y = AR∗for some A ∈O(d). Since any product of the form AR∗with A ∈SO(d) is also an optimal solution of Problem 2 (by gauge symmetry), this shows that ¯Y is optimal provided that ¯Y ∈SO(d) specifically. Furthermore, if this is not the case, we can always make it so by left-multiplying ¯Y by any orientation-reversing element of O(d), for example Diag(1, . . . , 1, −1). This argument provides a means of recovering an optimal solution of Problem 2 from Y ∗whenever exactness holds. Moreover, this procedure straightforwardly generalizes to the case that exactness fails, thereby producing a convenient rounding scheme (Algorithm 1). 4.3 The complete algorithm Combining the efficient optimization approach of Section 4.1 with the rounding procedure of Section 4.2 produces SE-Sync (Algorithm 2), our proposed algo- rithm for synchronization over the special Euclidean group. When applied to an instance of SE(d) synchronization, SE-Sync returns a feasible point ˆx ∈SE(d)n for the maximum-likelihood estimation Problem 1 together with the lower bound p∗ SDP ≤p∗ MLE on Problem 1’s optimal value. Furthermore, in the typical case that Problem 3 is exact, the returned estimate ˆx = (ˆt, ˆR) attains this lower bound (i.e. F( ˜Q ˆRT ˆR) = p∗ SDP), which thus serves as a computational certificate of ˆx’s correctness. Algorithm 2 The SE-Sync algorithm Input: An initial point Y ∈St(d, r0)n, r0 ≥d + 1. Output: A feasible estimate ˆx ∈SE(d)n for the maximum-likelihood estimation Prob- lem 1, and a lower bound p∗ SDP ≤p∗ MLE for Problem 1’s optimal value. 1: function SE-Sync(Y ) 2: Set Y ∗←RiemannianStaircase(Y ). ▷Solve Problems 3 & 4 3: Set p∗ SDP ←F( ˜QY ∗TY ∗). ▷Z∗= Y ∗TY ∗ 4: Set ˆR ←RoundSolution(Y ∗). 5: Recover the optimal translational estimates ˆt corresponding to ˆR via (9). 6: Set ˆx ←(ˆt, ˆR). 7: return {p∗ SDP, ˆx} 8: end function 5 Experimental results In this section, we evaluate SE-Sync’s performance on a variety of simulated and real-world 3D pose-graph SLAM datasets; specifically, we rerun the experiments considered in our previous work on solution verification [14] in order to establish a meaningful baseline with previously published results. We use a MATLAB im- plementation of SE-Sync that takes advantage of the truncated-Newton RTR [1] method supplied by Manopt [7]. Furthermore, for the purposes of these experi- ments, we fix r = 5 in the Riemannian Staircase,9 and initialize SE-Sync using a randomly sampled point on St(3, 5)n. As a basis for comparison, we also consider the performance of two Gauss- Newton-based alternatives: one initialized using the common odometric initial- ization (“GN-odom”), and another using the (state-of-the-art) chordal initializa- tion [15, 30] (“GN-chord”). Additionally, since the goal of this project is to pro- duce a certifiably correct algorithm for SE(d) synchronization, we also track the cost of applying the a posteriori solution verification method V2 from our pre- vious work [14] to verify the estimates recovered by the Gauss-Newton method with chordal initialization (“GN-chord-v2”). 5.1 Cube experiments In this first set of experiments, we simulate a robot traveling along a 3D grid world consisting of s3 poses arranged in a cubical lattice. Random loop closures are added between nearby nonsequential poses on the trajectory with probability pLC, and relative measurements are obtained by contaminating translational ob- servations with zero-mean isotropic Gaussian noise with a standard deviation of σT and rotational observations with the exponential of an element of so(3) sam- pled from a mean-zero isotropic Gaussian with standard deviation σR. Statistics are computed over 30 runs, varying each of the parameters s, pLC, σT , and σR individually. Results for these experiments are shown in Figs. 1–4. 9 We have found empirically that this is sufficient to enable the recovery of an opti- mal solution whenever exactness holds, and that when exactness fails, the rounded approximate solutions ˆR obtained by continuing up the staircase are not ultimately appreciably better than those obtained by terminating at r = 5. # nodes 3 3 5 3 7 3 9 3 11 3 13 3 15 3 Objective value 0 2000 4000 6000 8000 10000 GN-odom GN-chord SE-Sync # nodes 3 3 5 3 7 3 9 3 11 3 13 3 15 3 Computation time [s] 0 10 20 30 40 50 60 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 1. Varying s while holding pLC = .1, σR = .1 rad, σT = .5 m. pLC 0.2 0.4 0.6 0.8 1 Objective value 1000 2000 3000 4000 5000 6000 7000 8000 GN-odom GN-chord SE-Sync pLC 0.2 0.4 0.6 0.8 1 Computation time [s] 0 10 20 30 40 50 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 2. Varying pLC while holding s = 10, σR = .1 rad, σT = .5 m. σT 0.2 0.4 0.6 0.8 1 1.2 Objective value 800 1000 1200 1400 1600 1800 2000 GN-odom GN-chord SE-Sync σT 0.2 0.4 0.6 0.8 1 1.2 Computation time [s] 0 5 10 15 20 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 3. Varying σT while holding s = 10, pLC = .1, σR = .1 rad. σR 0 0.05 0.1 0.15 0.2 0.25 0.3 Objective value 800 1000 1200 1400 1600 1800 2000 2200 GN-odom GN-chord SE-Sync σR 0.05 0.1 0.15 0.2 0.25 0.3 Computation time [s] 0 5 10 15 20 25 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 4. Varying σR while holding s = 10, pLC = .1, σT = .5 m. Overall, these results indicate that SE-Sync is capable of converging to a certifiably globally optimal solution from a random starting point in a time that is comparable to (or in these cases, even faster than) a standard implementation of a purely local search technique initialized with a state-of-the-art method. This speed differential is particularly pronounced when comparing our (natively cer- tifiably correct) algorithm against the Gauss-Newton method with verification. Furthermore, this remains true across a wide variety of operationally-relevant conditions. The one exception to this general rule appears to be in the high- rotational-noise regime (Fig. 4), where the exactness of the relaxation breaks down (consistent with our earlier findings in [14]) and SE-Sync is unable to re- cover a good solution. Interestingly, the chordal initialization + Gauss-Newton method appears to perform remarkably well in this regime, although here it is no longer possible to certify the correctness of its results (as the certification procedure depends upon the same semidefinite relaxation as does SE-Sync). 5.2 Large-scale SLAM datasets Next, we apply SE-Sync to the large-scale SLAM datasets considered in our previous work [14]. We are interested in both the quality of the solutions that SE-Sync obtains, as well as its computational speed when applied to challenging large-scale instances of the SLAM problem. Results are summarized in Table 1. # Nodes # Meas. fGN odom. fGN init. fSE−sync SE-Sync time SE-Sync optimal? sphere 2500 4949 5.802 · 102 5.760 · 102 5.759 · 102 6.95 ✓ sphere-a 2200 8647 3.041 · 106 1.249 · 106 1.249 · 106 3.61 ✓ torus 5000 9048 2.767 · 104 1.211 · 104 1.211 · 104 24.50 ✓ cube 8000 22236 2.747 · 105 4.216 · 104 4.216 · 104 132.44 ✓ garage 1661 6275 6.300 · 10−1 6.300 · 10−1 6.299 · 10−1 203.30 ✓ cubicle 5750 16869 6.248 · 102 6.248 · 102 6.248 · 102 181.12 ✓ Table 1. Summary of results for large-scale real-world datasets. These results confirm that the Riemannian optimization scheme developed in Section 4.1 enables SE-Sync to scale effectively to large problem sizes, and that the semidefinite relaxation Problem 3 remains exact even in these challenging real-world examples. 6 Conclusion In this paper we developed SE-Sync, a certifiably correct algorithm for syn- chronization over the special Euclidean group. This method exploits the same semidefinite relaxation used in our procedure [14] to verify in-hand optimal solu- tions, but improves upon this prior work by enabling the efficient direct computa- tion of such solutions through the use of a specialized, structure-exploiting low- dimensional Riemannian optimization approach. Experimental evaluation shows that SE-Sync is capable of recovering certifiably optimal solutions of pose-graph SLAM problems in challenging large-scale examples, and does so at a computa- tional cost comparable with that of direct Newton-type local search techniques. Bibliography [1] P.-A. Absil, C.G. Baker, and K.A. Gallivan. Trust-region methods on Rie- mannian manifolds. Found. Comput. Math., 7(3):303–330, July 2007. [2] P.-A. Absil, R. Mahony, and R. Sepulchre. Optimization Algorithms on Matrix Manifolds. Princeton University Press, 2008. [3] R. Aragues, L. Carlone, G. Calafiore, and C. Sagues. Multi-agent localiza- tion from noisy relative pose measurements. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 364–369, Shanghai, China, May 2011. [4] A.S. Bandeira. A note on probably certifiably correct algorithms. Comptes Rendus Mathematique, 354(3):329–333, 2016. [5] A.S. Bandeira, N. Boumal, and A. Singer. Tightness of the maximum likeli- hood semidefinite relaxation for angular synchronization. Math. Program., 2016. [6] N. Boumal. A Riemannian low-rank method for optimization over semidefinite matrices with block-diagonal constraints. arXiv preprint: arXiv:1506.00575v2, 2015. [7] N. Boumal, B. Mishra, P.-A. Absil, and R. Sepulchre. Manopt, a MAT- LAB toolbox for optimization on manifolds. Journal of Machine Learning Research, 15(1):1455–1459, 2014. [8] N. Boumal, P.-A. Absil, and C. Cartis. Global rates of convergence for nonconvex optimization on manifolds. arXiv preprint: arXiv:1605.08101v1, 2016. [9] N. Boumal, V. Voroninski, and A.S. Bandeira. The non-convex Burer- Monteiro approach works on smooth semidefinite programs. arXiv preprint arXiv:1606.04970v1, June 2016. [10] S. Burer and R.D.C. Monteiro. A nonlinear programming algorithm for solving semidefinite programs via low-rank factorization. Math. Program., 95:329–357, 2003. [11] S. Burer and R.D.C. Monteiro. Local minima and convergence in low-rank semidefinite programming. Math. Program., 103:427–444, 2005. [12] L. Carlone and A. Censi. From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimiza- tion. IEEE Trans. on Robotics, 30(2):475–492, April 2014. [13] L. Carlone and F. Dellaert. Duality-based verification techniques for 2D SLAM. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 4589–4596, Seattle, WA, May 2015. [14] L. Carlone, D.M. Rosen, G. Calafiore, J.J. Leonard, and F. Dellaert. La- grangian duality in 3D SLAM: Verification techniques and optimal solu- tions. In IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS), Hamburg, Germany, September 2015. [15] L. Carlone, R. Tron, K. Daniilidis, and F. Dellaert. Initialization techniques for 3D SLAM: A survey on rotation estimation and its use in pose graph optimization. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 4597–4605, Seattle, WA, May 2015. [16] L. Carlone, G.C. Calafiore, C. Tommolillo, and F. Dellaert. Planar pose graph optimization: Duality, optimal solutions, and verification. IEEE Trans. on Robotics, 32(3):545–565, June 2016. [17] A. Chiuso, G. Picci, and S. Soatto. Wide-sense estimation on the special orthogonal group. Communications in Information and Systems, 8(3):185– 200, 2008. [18] F. Dellaert and M. Kaess. Square Root SAM: Simultaneous localization and mapping via square root information smoothing. Intl. J. of Robotics Research, 25(12):1181–1203, December 2006. [19] A. Edelman, T.A. Arias, and S.T. Smith. The geometry of algorithms with orthogonality constraints. SIAM J. Matrix Anal. Appl., 20(2):303– 353, October 1998. [20] T.S. Ferguson. A Course in Large Sample Theory. Chapman & Hall/CRC, Boca Raton, FL, 1996. [21] J. Gallier. The Schur complement and symmetric positive semidefinite (and definite) matrices. unpublished note, available online: http://www.cis. upenn.edu/~jean/schur-comp.pdf, December 2010. [22] G. Grisetti, C. Stachniss, and W. Burgard. Nonlinear constraint network optimization for efficient map learning. IEEE Trans. on Intelligent Trans- portation Systems, 10(3):428–439, September 2009. [23] R. Hartley, J. Trumpf, Y. Dai, and H. Li. Rotation averaging. Intl. J. of Computer Vision, 103(3):267–305, July 2013. [24] S. Huang, Y. Lai, U. Frese, and G. Dissanayake. How far is SLAM from a linear least squares problem? In IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS), pages 3011–3016, Taipei, Taiwan, October 2010. [25] S. Huang, H. Wang, U. Frese, and G. Dissanayake. On the number of local minima to the point feature based SLAM problem. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 2074–2079, St. Paul, MN, May 2012. [26] M. Kaess, H. Johannsson, R. Roberts, V. Ila, J.J. Leonard, and F. Dellaert. iSAM2: Incremental smoothing and mapping using the Bayes tree. Intl. J. of Robotics Research, 31(2):216–235, February 2012. [27] R. K¨ummerle, G. Grisetti, H. Strasdat, K. Konolige, and W. Burgard. g2o: A general framework for graph optimization. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 3607–3613, Shanghai, China, May 2011. [28] F. Lu and E. Milios. Globally consistent range scan alignment for environ- mental mapping. Autonomous Robots, 4:333–349, April 1997. [29] Z.-Q. Luo, W.-K. Ma, A. So, Y. Ye, and S. Zhang. Semidefinite relaxation of quadratic optimization problems. IEEE Signal Processing Magazine, 27 (3):20–34, May 2010. [30] D. Martinec and T. Pajdla. Robust rotation and translation estimation in multiview reconstruction. In IEEE Intl. Conf. on Computer Vision and Pattern Recognition (CVPR), pages 1–8, Minneapolis, MN, June 2007. [31] J. Nocedal and S.J. Wright. Numerical Optimization. Springer Sci- ence+Business Media, New York, 2nd edition, 2006. [32] E. Olson, J.J. Leonard, and S. Teller. Fast iterative alignment of pose graphs with poor initial estimates. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 2262–2269, Orlando, FL, May 2006. [33] J.R. Peters, D. Borra, B.E. Paden, and F. Bullo. Sensor network localization on the group of three-dimensional displacements. SIAM J. Control Optim., 53(6):3534–3561, 2015. [34] D.M. Rosen, M. Kaess, and J.J. Leonard. RISE: An incremental trust-region method for robust online sparse least-squares estimation. IEEE Trans. on Robotics, 30(5):1091–1108, October 2014. [35] D.M. Rosen, C. DuHadway, and J.J. Leonard. A convex relaxation for approximate global optimization in simultaneous localization and mapping. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 5822–5829, Seattle, WA, May 2015. [36] D.M. Rosen, L. Carlone, A.S. Bandeira, and J.J. Leonard. SE-Sync: A certifiably correct algorithm for synchronization over the special Euclidean group. Technical Report MIT-CSAIL-TR-2017-002, Computer Science and Artificial Intelligence Laboratory, Massachusetts Institute of Technology, Cambridge, MA, February 2017. [37] A. Singer and Y. Shkolnisky. Three-dimensional structure determination from common lines in cryo-EM by eigenvectors and semidefinite program- ming. SIAM J. Imaging Sci., 4(2):543–572, 2011. [38] A. Singer and H.-T. Wu. Vector diffusion maps and the connection Lapla- cian. Comm. Pure Appl. Math., 65:1067–1144, 2012. [39] M.J. Todd. Semidefinite optimization. Acta Numerica, 10:515–560, 2001. [40] R. Tron and R. Vidal. Distributed 3-D localization of camera sensor net- works from 2-D image measurements. IEEE Trans. on Automatic Control, 59(12):3325–3340, December 2014. [41] S. Umeyama. Least-squares estimation of transformation parameters be- tween two point patterns. IEEE Trans. on Pattern Analysis and Machine Intelligence, 13(4):376–380, 1991. [42] V. Vandenberghe and S. Boyd. Semidefinite programming. SIAM Review, 38(1):49–95, March 1996. [43] B. Vlasic and N.E. Boudette. As U.S. investigates fatal Tesla crash, com- pany defends Autopilot system. The New York Times, July 12, 2016. Re- trieved from http://www.nytimes.com. [44] H. Wang, G. Hu, S. Huang, and G. Dissanayake. On the structure of non- linearities in pose graph SLAM. In Robotics: Science and Systems (RSS), Sydney, Australia, July 2012. [45] L. Wang and A. Singer. Exact and stable recovery of rotations for robust synchronization. Information and Inference, September 2013. A Certifiably Correct Algorithm for Synchronization over the Special Euclidean Group David M. Rosen⋆1, Luca Carlone2, Afonso S. Bandeira3, and John J. Leonard1 1 Computer Science and Artificial Intelligence Laboratory, Massachusetts Institute of Technology, Cambridge, MA 02139, USA 2 Laboratory for Information and Decision Systems, Massachusetts Institute of Technology, Cambridge, MA 02139, USA 3 Department of Mathematics and Center for Data Science, Courant Institute of Mathematical Sciences, New York University, New York, NY 10012, USA Abstract. Many important geometric estimation problems naturally take the form of synchronization over the special Euclidean group: es- timate the values of a set of unknown poses x1, . . . , xn ∈SE(d) given noisy measurements of a subset of their pairwise relative transforms x−1 i xj. Examples of this class include the foundational problems of pose- graph simultaneous localization and mapping (SLAM) (in robotics) and camera pose estimation (in computer vision), among others. This prob- lem is typically formulated as a maximum-likelihood estimation that requires solving a nonconvex nonlinear program, which is computation- ally intractable in general. Nevertheless, in this paper we present an algorithm that is able to efficiently recover certifiably globally optimal solutions of this estimation problem in a non-adversarial noise regime. The crux of our approach is the development of a semidefinite relaxation of the maximum-likelihood estimation whose minimizer provides the ex- act MLE so long as the magnitude of the noise corrupting the avail- able measurements falls below a certain critical threshold; furthermore, whenever exactness obtains, it is possible to verify this fact a posteriori, thereby certifying the optimality of the recovered estimate. We develop a specialized optimization scheme for solving large-scale instances of this semidefinite relaxation by exploiting its low-rank, geometric, and graph- theoretic structure to reduce it to an equivalent optimization problem on a low-dimensional Riemannian manifold, and then design a Riemannian truncated-Newton trust-region method to solve this reduction efficiently. We combine this fast optimization approach with a simple rounding pro- cedure to produce our algorithm, SE-Sync. Experimental evaluation on a variety of simulated and real-world pose-graph SLAM datasets shows that SE-Sync is capable of recovering globally optimal solutions when the available measurements are corrupted by noise up to an order of mag- nitude greater than that typically encountered in robotics applications, and does so at a computational cost that scales comparably with that of direct Newton-type local search techniques. ⋆Corresponding author. Email: dmrosen@mit.edu arXiv:1611.00128v3 [cs.RO] 10 Feb 2017 1 Introduction Over the coming decades, the increasingly widespread adoption of robotic tech- nology in areas such as transportation, medicine, and disaster response has tremendous potential to increase productivity, alleviate suffering, and preserve life. At the same time, however, these high-impact applications often place au- tonomous systems in safety- and life-critical roles, where misbehavior or un- detected failures can carry dire consequences [43]. While empirical evaluation has traditionally been a driving force in the design and implementation of au- tonomous systems, safety-critical applications such as these demand algorithms that come with clearly-delineated performance guarantees. This paper presents one such algorithm, SE-Sync, an efficient and certifiably correct method for solv- ing the fundamental problem of pose estimation. Formally, we consider the synchronization problem of estimating a collec- tion of unknown poses1 based upon a set of relative measurements between them. This estimation problem lies at the core of many fundamental percep- tual problems in robotics; for example, simultaneous localization and mapping (SLAM) [28] and multi-robot localization [3]. Closely-related formulations also arise in structure from motion [23, 30] and camera network calibration [40] (in computer vision), sensor network localization [33], and cryo-electron microscopy [37]. These synchronization problems are typically formulated as instances of maximum-likelihood estimation under an assumed probability distribution for the measurement noise. This formulation is attractive from a theoretical stand- point due to the powerful analytical framework and strong performance guaran- tees that maximum-likelihood estimation affords [20]. However, this formal rigor comes at the expense of computational tractability, as the maximum-likelihood formulation leads to a nonconvex optimization problem that is difficult to solve. Related Work. In the context of SLAM, the pose synchronization prob- lem is commonly solved using iterative numerical optimization methods, e.g. Gauss-Newton [26–28], gradient descent [22, 32], or trust region methods [34]. This approach is particularly attractive because the rapid convergence speed of second-order numerical optimization methods [31], together with their ability to exploit the measurement sparsity that typically occurs in naturalistic problem instances [18], enables these techniques to scale efficiently to large problem sizes while maintaining real-time operation. However, this computational expedience comes at the expense of reliability, as their restriction to local search renders these methods vulnerable to convergence to suboptimal critical points, even for relatively small noise levels [14, 35]. This observation, together with the fact that suboptimal critical points usually correspond to egregiously wrong trajectory estimates, has motivated two general lines of research. The first addresses the initialization problem, i.e., how to compute a suitable initial guess for iterative refinement; examples of this effort are [12, 15, 35]. The second aims at a deeper 1 A pose is a position and orientation in d-dimensional Euclidean space; this is an element of the special Euclidean group SE(d) ∼= Rd ⋊SO(d). understanding of the global structure of the pose synchronization problem (e.g. number of local minima, convergence basin), see for example [24, 25, 44]. Contribution. In our previous work [13, 14, 16], we demonstrated that La- grangian duality provides an effective means of certifying the optimality of an in-hand solution for the pose synchronization problem, and could in principle be used to directly compute such certifiably optimal solutions by solving a La- grangian relaxation. However, this relaxation turns out to be a semidefinite pro- gram (SDP), and while there do exist mature general-purpose SDP solvers, their high per-iteration computational cost limits their practical utility to instances of this relaxation involving only a few hundred poses,2 whereas real-world pose synchronization problems are typically one to two orders of magnitude larger. The main contribution of the present paper is the development of a spe- cialized structure-exploiting optimization procedure that is capable of efficiently solving large-scale instances of the semidefinite relaxation in practice. This pro- cedure provides a means of recovering certifiably globally optimal solutions of the pose synchronization problem from the semidefinite relaxation within a non- adversarial noise regime in which minimizers of the latter correspond to exact so- lutions of the former. Our overall pose synchronization method, SE-Sync, is thus a certifiably correct algorithm [4], meaning that it is able to efficiently recover globally optimal solutions of generally intractable problems within a restricted range of operation, and certify the optimality of the solutions so obtained. Ex- perimental evaluation on a variety of simulated and real-world pose-graph SLAM datasets shows that our relaxation remains exact when the available measure- ments are corrupted by noise up to an order of magnitude greater than that typically encountered in application, and that within this regime, SE-Sync is able to recover globally optimal solutions from this relaxation at a computa- tional cost comparable with that of direct Newton-type local search techniques. 2 Problem formulation The SE(d) synchronization problem consists of estimating the values of a set of n unknown poses x1, . . . , xn ∈SE(d) given noisy measurements of m of their pairwise relative transforms xij ≜x−1 i xj (i ̸= j). We model the set of available measurements using an undirected graph G = (V, E) in which the nodes i ∈V are in one-to-one correspondence with the unknown poses xi and the edges {i, j} ∈E are in one-to-one correspondence with the set of available measurements, and we assume without loss of generality that G is connected.3 We let −→ G = (V, −→ E ) be a directed graph obtained from G by fixing an orientation for each of its edges, 2 This encompasses the most commonly-used interior-point-based SDP software li- braries, including SDPA, SeDuMi, SDPT3, CSDP, and DSDP. 3 If G is not connected, then the problem of estimating the unknown poses x1, . . . , xn decomposes into a set of independent estimation problems that are in one-to-one correspondence with the connected components of G; thus, the general case is always reducible to the case of connected graphs. and assume that a noisy measurement ˜xij of each relative pose xij = (tij, Rij) is obtained by sampling from the following probabilistic generative model: ˜tij = ¯tij + tϵ ij, tϵ ij ∼N 0, τ −1 ij Id  , ˜Rij = ¯RijRϵ ij, Rϵ ij ∼Langevin (Id, κij) , ∀(i, j) ∈−→ E . (1) Here ¯xij = (¯tij, ¯Rij) is the true (latent) value of xij, N(µ, Σ) denotes the standard multivariate Gaussian distribution with mean µ ∈Rd and covariance Σ ⪰0, and Langevin(M, κ) denotes the isotropic Langevin distribution on SO(d) with mode M ∈SO(d) and concentration parameter κ ≥0 (this is the distribu- tion on SO(d) whose probability density function is given by: p(R; M, κ) = 1 cd(κ) exp κ tr(M TR)  (2) with respect to the Haar measure [17]).4 Finally, we define ˜xji ≜˜x−1 ij , κji ≜κij, τji ≜τij, and ˜Rji ≜˜RT ij for all (i, j) ∈−→ E . Given a set of noisy measurements ˜xij sampled from the generative model (1), a straightforward computation shows that a maximum-likelihood estimate ˆxMLE ∈SE(d)n for the poses x1, . . . , xn is obtained as a minimizer of: Problem 1 (Maximum-likelihood estimation for SE(d) synchronization). p∗ MLE = min ti∈Rd Ri∈SO(d) X (i,j)∈− → E κij∥Rj −Ri ˜Rij∥2 F + τij tj −ti −Ri˜tij 2 2 (3) Unfortunately, Problem 1 is a high-dimensional, nonconvex nonlinear pro- gram, and is therefore computationally hard to solve in general. Consequently, our strategy in this paper will be to approximate this problem using a (con- vex) semidefinite relaxation [42], and then exploit this relaxation to search for solutions of the original (hard) problem. 3 Forming the semidefinite relaxation In this section we develop the semidefinite relaxation that we will solve in place of the maximum-likelihood estimation Problem 1.5 To that end, our first step will be to rewrite Problem 1 in a simpler and more compact form that emphasizes the structural correspondences between the optimization problem (3) and several simple graph-theoretic objects that can be constructed from the set of available measurements ˜xij and the graphs G and −→ G. 4 We use a directed graph to model the measurements ˜xij sampled from (1) because the distribution of the noise corrupting the latent values ¯xij is not invariant under SE(d)’s group inverse operation. Consequently, we must keep track of which state xi was the “base frame” for each measurement. 5 Due to space limitations, we omit all derivations and proofs; please see the extended version of this paper [36] for detailed derivations and additional results. We define the translational weight graph W τ = (V, E, {τij}) to be the weighted undirected graph with node set V, edge set E, and edge weights τij for {i, j} ∈E. The Laplacian L(W τ) of W τ is then: L(W τ)ij =      P {i,k}∈E τik, i = j, −τij, {i, j} ∈E, 0, {i, j} /∈E. (4) Similarly, let L( ˜Gρ) denote the connection Laplacian for the rotational syn- chronization problem determined by the measurements ˜Rij and measurement weights κij for (i, j) ∈−→ E ; this is the symmetric (d × d)-block-structured matrix determined by (cf. [38, 45]): L( ˜Gρ) ∈Sym(dn) L( ˜Gρ)ij ≜        P {i,k}∈E κik  Id, i = j, −κij ˜Rij, {i, j} ∈E, 0d×d, {i, j} /∈E. (5) We also define a few matrices constructed from the set of translational obser- vations ˜tij. We let ˜V ∈Rn×dn be the (1 × d)-block-structured matrix with (i, j)-blocks determined by: ˜Vij ≜      P {k∈V|(j,k)∈− → E } τjk˜tT jk, i = j, −τji˜tT ji, (j, i) ∈−→ E , 01×d, otherwise, (6) ˜T ∈Rm×dn denote the (1 × d)-block-structured matrix with rows and columns indexed by e ∈−→ E and k ∈V, respectively, and whose (e, k)-block is given by: ˜Tek ≜ ( −˜tT kj, e = (k, j) ∈−→ E , 01×d, otherwise, (7) and Ω≜Diag(τe1, . . . , τem) ∈Sym(m) denote the diagonal matrix indexed by the directed edges e ∈−→ E , and whose eth element gives the precision of the translational measurement ˜tij corresponding to that edge. Finally, we also aggregate the rotational and translational state estimates into the block matrices R ≜ R1 · · · Rn  ∈SO(d)n ⊂Rd×dn and t ≜ t1 . . . tn  ∈Rdn. With these definitions in hand, let us return to Problem 1. We observe that for a fixed value of the rotational states R1, . . . , Rn, this problem reduces to the unconstrained minimization of a quadratic form in the translational variables t1, . . . , tn ∈Rd, for which we can find a closed-form solution using a generalized Schur complement [21, Proposition 4.2]. This observation enables us to ana- lytically eliminate the translational states from the optimization problem (3), thereby obtaining the simplified but equivalent maximum-likelihood estimation: Problem 2 (Simplified maximum-likelihood estimation). p∗ MLE = min R∈SO(d)n tr( ˜QRTR) (8a) ˜Q = L( ˜Gρ) + ˜T TΩ 1 2 ΠΩ 1 2 ˜T. (8b) Furthermore, given any minimizer R∗of Problem 2, we can recover a correspond- ing optimal value t∗for t according to: t∗= −vec  R∗˜V TL(W τ)† . (9) In (8b) Π ∈Rm×m is the matrix of the orthogonal projection operator onto ker(A(−→ G)Ω 1 2 ) ⊆Rm×m, where A(−→ G) ∈Rn×m is the incidence matrix of the directed graph −→ G. Although Π is generically dense, by exploiting the fact that it is derived from a sparse graph, we have been able to show that it admits the sparse decomposition: Π = Im −Ω 1 2 ¯A(−→ G)TL−TL−1 ¯A(−→ G)Ω 1 2 (10) where ¯A(−→ G)Ω 1 2 = LQ1 is a thin LQ decomposition of ¯A(−→ G)Ω 1 2 and ¯A(−→ G) is the reduced incidence matrix of −→ G. Note that expression (10) requires only the sparse lower-triangular factor L, which can be easily and efficiently obtained in practice. Decomposition (10) will play a critical role in the implementation of our efficient optimization. Now we derive the semidefinite relaxation of Problem 2 that we will solve in practice, exploiting the simplified form (8). We begin by relaxing the condition R ∈SO(d)n to R ∈O(d)n. The advantage of this latter version is that O(d) is defined by a set of (quadratic) orthonormality constraints, so the orthogonally- relaxed version of Problem 2 is a quadratically constrained quadratic program; consequently, its Lagrangian dual relaxation is a semidefinite program [29]: Problem 3 (Semidefinite relaxation for SE(d) synchronization). p∗ SDP = min 0⪯Z∈Sym(dn) tr( ˜QZ) s.t. BlockDiagd×d(Z) = Diag(Id, . . . , Id) (11) At this point it is instructive to compare the semidefinite relaxation (11) with the simplified maximum-likelihood estimation (8). For any R ∈SO(d)n, the product Z = RTR is positive semidefinite and has identity matrices along its (d × d)-block-diagonal, and so is a feasible point of (11); in other words, (11) can be regarded as a relaxation of the maximum-likelihood estimation obtained by expanding (8)’s feasible set. This immediately implies that p∗ SDP ≤p∗ MLE. Furthermore, if it happens that a minimizer Z∗of Problem 3 admits a decompo- sition of the form Z∗= R∗TR∗for some R∗∈SO(d)n, then it is straightforward to verify that this R∗is also a minimizer of Problem 2, and so provides a globally optimal solution of the maximum-likelihood estimation Problem 1 via (9). The crucial fact that justifies our interest in Problem 3 is that (as demonstrated em- pirically in our prior work [14] and investigated in a simpler setting in [5]) this problem has a unique minimizer of just this form so long as the noise corrupting the available measurements ˜xij is not too large. More precisely, we prove:6 Proposition 1. Let ¯ Q be the matrix of the form (8b) constructed using the true (latent) relative transforms ¯xij in (1). There exists a constant β ≜β( ¯ Q) > 0 (depending upon ¯ Q) such that, if ∥˜Q − ¯ Q∥2 < β, then: (i) The semidefinite relaxation Problem 3 has a unique solution Z∗, and (ii) Z∗= R∗TR∗, where R∗∈SO(d)n is a minimizer of the maximum-likelihood estimation Problem 2. 4 The SE-Sync algorithm 4.1 Solving the semidefinite relaxation As a semidefinite program, Problem 3 can in principle be solved in polynomial- time using interior-point methods [39, 42]. In practice, however, the high compu- tational cost of general-purpose semidefinite programming algorithms prevents these methods from scaling effectively to problems in which the dimension of the decision variable Z is greater than a few thousand [39]. Unfortunately, typical instances of Problem 3 that are encountered in robotics and computer vision ap- plications are one to two orders of magnitude larger than this maximum effective problem size, and are therefore well beyond the reach of these general-purpose methods. Consequently, in this subsection we develop a specialized optimization procedure for solving large-scale instances of Problem 3 efficiently. Simplifying Problem 3 The dominant computational cost when applying general-purpose semidefinite programming methods to solve Problem 3 is the need to store and manipulate expressions involving the (large, dense) matrix variable Z. However, in the typical case that exactness holds, we know that the actual solution Z∗of Problem 3 that we seek has a very concise description in the factored form Z∗= R∗TR∗for R∗∈SO(d)n. More generally, even in those cases where exactness fails, minimizers Z∗of Problem 3 generically have a rank r not much greater than d, and therefore admit a symmetric rank decomposition Z∗= Y ∗TY ∗for Y ∗∈Rr×dn with r ≪dn. In a pair of papers, Burer and Monteiro [10, 11] proposed an elegant general approach to exploit the fact that large-scale semidefinite programs often admit such low-rank solutions: simply replace every instance of the decision variable Z with a rank-r product of the form Y TY to produce a rank-restricted version of the original problem. This substitution has the two-fold effect of (i) dramatically 6 Please see the extended version of this paper [36] for the proof. reducing the size of the search space and (ii) rendering the positive semidefinite- ness constraint redundant, since Y TY ⪰0 for any choice of Y . The resulting rank-restricted form of the problem is thus a low-dimensional nonlinear pro- gram, rather than a semidefinite program. Furthermore, following Boumal [6] we observe that after replacing Z in Prob- lem 3 with Y TY for Y = Y1 · · · Yn  ∈Rr×dn, the block-diagonal constraints in our specific problem of interest (11) are equivalent to Y T i Yi = Id, for all i ∈[n], i.e., the columns of each block Yi ∈Rr×d form an orthonormal frame. In general, the set of all orthonormal k-frames in Rp (k ≤n): St(k, p) ≜  Y ∈Rp×k | Y TY = Ik (12) forms a smooth compact matrix manifold, called the Stiefel manifold, which can be equipped with a Riemannian metric induced by its embedding into the ambi- ent space Rp×k [2, Sec. 3.3.2]. Together, these observations enable us to reduce Problem 3 to an equivalent unconstrained Riemannian optimization problem defined on a product of Stiefel manifolds: Problem 4 (Rank-restricted semidefinite relaxation, Riemannian optimization form). p∗ SDPLR = min Y ∈St(d,r)n tr( ˜QY TY ). (13) This is the optimization problem that we will actually solve in practice. Ensuring optimality While the reduction from Problem 3 to Problem 4 dra- matically reduces the size of the optimization problem that needs to be solved, it comes at the expense of (re)introducing the quadratic orthonormality constraints (12). It may therefore not be clear whether anything has really been gained by relaxing Problem 2 to Problem 4, since it appears that we may have simply re- placed one difficult nonconvex optimization problem with another. The following remarkable result (adapted from Boumal et al. [9]) justifies this approach: Proposition 2 (A sufficient condition for global optimality in Problem 4). If Y ∈St(d, r)n is a (row) rank-deficient second-order critical point7 of Problem 4, then Y is a global minimizer of Problem 4 and Z∗= Y TY is a solution of the dual semidefinite relaxation Problem 3. Proposition 2 immediately suggests a procedure for obtaining solutions Z∗of Problem 3 by applying a Riemannian optimization method to search successively higher levels of the rank-restricted hierarchy of relaxations (13) until a rank- deficient second-order critical point is obtained.8 This algorithm is referred to as the Riemannian Staircase [6, 9]. 7 That is, a point satisfying grad F(Y ) = 0 and Hess F(Y ) ⪰0 (cf. (14)–(17)). 8 Note that since every Y ∈St(d, r)n is row rank-deficient for r > dn, this procedure is guaranteed to recover an optimal solution after searching at most dn + 1 levels of the hierarchy (13). A Riemannian optimization method for Problem 4 Proposition 2 pro- vides a means of obtaining global minimizers of Problem 3 by locally searching for second-order critical points of Problem 4. To that end, in this subsection we design a Riemannian optimization method that will enable us to rapidly identify these critical points in practice. Equations (8b) and (10) provide an efficient means of computing products with ˜Q by performing a sequence of sparse matrix multiplications and sparse triangular solves (i.e., without the need to form the dense matrix ˜Q directly). These operations are sufficient to evaluate the objective appearing in Problem 4, as well as the corresponding gradient and Hessian-vector products when con- sidered as a function on the ambient Euclidean space Rr×dn: F(Y ) ≜tr( ˜QY TY ), ∇F(Y ) = 2Y ˜Q, ∇2F(Y )[ ˙Y ] = 2 ˙Y ˜Q. (14) Furthermore, there are simple relations between the ambient Euclidean gradient and Hessian-vector products in (14) and their corresponding Riemannian coun- terparts when F(·) is viewed as a function restricted to St(d, r)n ⊂Rr×dn. With reference to the orthogonal projection operator [19, eq. (2.3)]: ProjY : TY Rr×dn →TY (St(d, r)n) ProjY (X) = X −Y SymBlockDiagd×d(Y TX) (15) the Riemannian gradient grad F(Y ) is simply the orthogonal projection of the ambient Euclidean gradient ∇F(Y ) (cf. [2, eq. (3.37)]): grad F(Y ) = ProjY ∇F(Y ). (16) Similarly, the Riemannian Hessian-vector product Hess F(Y )[ ˙Y ] can be obtained as the orthogonal projection of the ambient directional derivative of the gradient vector field grad F(Y ) in the direction of ˙Y (cf. [2, eq. (5.15)]). A straightforward computation shows that this is given by: Hess F(Y )[ ˙Y ] = ProjY (∇2F(Y )[ ˙Y ] −˙Y SymBlockDiagd×d(Y T∇F(Y ))). (17) Together, equations (8b), (10), and (14)–(17) provide an efficient means of computing F(Y ), grad F(Y ), and Hess F(Y )[ ˙Y ]. Consequently, we propose to employ the truncated-Newton Riemannian Trust-Region (RTR) method [1, 8] to efficiently compute high-precision estimates of second-order critical points of Problem 4 in practice. 4.2 Rounding the solution In the previous subsection, we described an efficient algorithmic approach for computing minimizers Y ∗∈St(d, r)n of Problem 4 that correspond to solutions Z∗= Y ∗TY ∗of Problem 3. However, our ultimate goal is to extract an optimal solution of Problem 2 from Z∗whenever exactness holds, and a feasible approx- imate solution otherwise. In this subsection, we develop a rounding procedure satisfying these criteria. Algorithm 1 Rounding procedure for solutions of Problem 4 Input: An optimal solution Y ∗∈St(d, r)n of Problem 4. Output: A feasible point ˆR ∈SO(d)n. 1: function RoundSolution(Y ∗) 2: Compute a rank-d truncated singular value decomposition UdΞdV T d for Y ∗ and assign ˆR ←ΞdV T d . 3: Set N+ ←|{ ˆRi | det( ˆRi) > 0}|. 4: if N+ < ⌈n 2 ⌉then 5: ˆR ←Diag(1, . . . , 1, −1) ˆR. 6: end if 7: for i = 1, . . . , n do 8: Set ˆRi ←NearestRotation( ˆRi). ▷See e.g. [41] 9: end for 10: return ˆR 11: end function To begin, let us consider the (typical) case in which exactness obtains; here Y ∗TY ∗= Z∗= R∗TR∗for some optimal solution R∗∈SO(d)n of Problem 2. Since rank(R∗) = d, this implies that rank(Y ∗) = d as well. Consequently, letting Y ∗= UdΞdV T d denote a (rank-d) thin singular value decomposition of Y ∗, and defining ¯Y ≜ΞdV T d ∈Rd×dn, it follows that ¯Y T ¯Y = Z∗= R∗TR∗. This last equality implies that the d × d block-diagonal of ¯Y T ¯Y satisfies ¯Y T i ¯Yi = Id for all i ∈[n], i.e. ¯Y ∈O(d)n. Similarly, comparing the elements of the first block rows of ¯Y T ¯Y and R∗TR∗shows that ¯Y T 1 ¯Yj = R∗ 1R∗ j for all j ∈[n]. Left- multiplying this set of equalities by ¯Y1 and letting A = ¯Y1R∗ 1 shows ¯Y = AR∗for some A ∈O(d). Since any product of the form AR∗with A ∈SO(d) is also an optimal solution of Problem 2 (by gauge symmetry), this shows that ¯Y is optimal provided that ¯Y ∈SO(d) specifically. Furthermore, if this is not the case, we can always make it so by left-multiplying ¯Y by any orientation-reversing element of O(d), for example Diag(1, . . . , 1, −1). This argument provides a means of recovering an optimal solution of Problem 2 from Y ∗whenever exactness holds. Moreover, this procedure straightforwardly generalizes to the case that exactness fails, thereby producing a convenient rounding scheme (Algorithm 1). 4.3 The complete algorithm Combining the efficient optimization approach of Section 4.1 with the rounding procedure of Section 4.2 produces SE-Sync (Algorithm 2), our proposed algo- rithm for synchronization over the special Euclidean group. When applied to an instance of SE(d) synchronization, SE-Sync returns a feasible point ˆx ∈SE(d)n for the maximum-likelihood estimation Problem 1 together with the lower bound p∗ SDP ≤p∗ MLE on Problem 1’s optimal value. Furthermore, in the typical case that Problem 3 is exact, the returned estimate ˆx = (ˆt, ˆR) attains this lower bound (i.e. F( ˜Q ˆRT ˆR) = p∗ SDP), which thus serves as a computational certificate of ˆx’s correctness. Algorithm 2 The SE-Sync algorithm Input: An initial point Y ∈St(d, r0)n, r0 ≥d + 1. Output: A feasible estimate ˆx ∈SE(d)n for the maximum-likelihood estimation Prob- lem 1, and a lower bound p∗ SDP ≤p∗ MLE for Problem 1’s optimal value. 1: function SE-Sync(Y ) 2: Set Y ∗←RiemannianStaircase(Y ). ▷Solve Problems 3 & 4 3: Set p∗ SDP ←F( ˜QY ∗TY ∗). ▷Z∗= Y ∗TY ∗ 4: Set ˆR ←RoundSolution(Y ∗). 5: Recover the optimal translational estimates ˆt corresponding to ˆR via (9). 6: Set ˆx ←(ˆt, ˆR). 7: return {p∗ SDP, ˆx} 8: end function 5 Experimental results In this section, we evaluate SE-Sync’s performance on a variety of simulated and real-world 3D pose-graph SLAM datasets; specifically, we rerun the experiments considered in our previous work on solution verification [14] in order to establish a meaningful baseline with previously published results. We use a MATLAB im- plementation of SE-Sync that takes advantage of the truncated-Newton RTR [1] method supplied by Manopt [7]. Furthermore, for the purposes of these experi- ments, we fix r = 5 in the Riemannian Staircase,9 and initialize SE-Sync using a randomly sampled point on St(3, 5)n. As a basis for comparison, we also consider the performance of two Gauss- Newton-based alternatives: one initialized using the common odometric initial- ization (“GN-odom”), and another using the (state-of-the-art) chordal initializa- tion [15, 30] (“GN-chord”). Additionally, since the goal of this project is to pro- duce a certifiably correct algorithm for SE(d) synchronization, we also track the cost of applying the a posteriori solution verification method V2 from our pre- vious work [14] to verify the estimates recovered by the Gauss-Newton method with chordal initialization (“GN-chord-v2”). 5.1 Cube experiments In this first set of experiments, we simulate a robot traveling along a 3D grid world consisting of s3 poses arranged in a cubical lattice. Random loop closures are added between nearby nonsequential poses on the trajectory with probability pLC, and relative measurements are obtained by contaminating translational ob- servations with zero-mean isotropic Gaussian noise with a standard deviation of σT and rotational observations with the exponential of an element of so(3) sam- pled from a mean-zero isotropic Gaussian with standard deviation σR. Statistics are computed over 30 runs, varying each of the parameters s, pLC, σT , and σR individually. Results for these experiments are shown in Figs. 1–4. 9 We have found empirically that this is sufficient to enable the recovery of an opti- mal solution whenever exactness holds, and that when exactness fails, the rounded approximate solutions ˆR obtained by continuing up the staircase are not ultimately appreciably better than those obtained by terminating at r = 5. # nodes 3 3 5 3 7 3 9 3 11 3 13 3 15 3 Objective value 0 2000 4000 6000 8000 10000 GN-odom GN-chord SE-Sync # nodes 3 3 5 3 7 3 9 3 11 3 13 3 15 3 Computation time [s] 0 10 20 30 40 50 60 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 1. Varying s while holding pLC = .1, σR = .1 rad, σT = .5 m. pLC 0.2 0.4 0.6 0.8 1 Objective value 1000 2000 3000 4000 5000 6000 7000 8000 GN-odom GN-chord SE-Sync pLC 0.2 0.4 0.6 0.8 1 Computation time [s] 0 10 20 30 40 50 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 2. Varying pLC while holding s = 10, σR = .1 rad, σT = .5 m. σT 0.2 0.4 0.6 0.8 1 1.2 Objective value 800 1000 1200 1400 1600 1800 2000 GN-odom GN-chord SE-Sync σT 0.2 0.4 0.6 0.8 1 1.2 Computation time [s] 0 5 10 15 20 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 3. Varying σT while holding s = 10, pLC = .1, σR = .1 rad. σR 0 0.05 0.1 0.15 0.2 0.25 0.3 Objective value 800 1000 1200 1400 1600 1800 2000 2200 GN-odom GN-chord SE-Sync σR 0.05 0.1 0.15 0.2 0.25 0.3 Computation time [s] 0 5 10 15 20 25 GN-odom GN-chord GN-chord-v2 SE-Sync Fig. 4. Varying σR while holding s = 10, pLC = .1, σT = .5 m. Overall, these results indicate that SE-Sync is capable of converging to a certifiably globally optimal solution from a random starting point in a time that is comparable to (or in these cases, even faster than) a standard implementation of a purely local search technique initialized with a state-of-the-art method. This speed differential is particularly pronounced when comparing our (natively cer- tifiably correct) algorithm against the Gauss-Newton method with verification. Furthermore, this remains true across a wide variety of operationally-relevant conditions. The one exception to this general rule appears to be in the high- rotational-noise regime (Fig. 4), where the exactness of the relaxation breaks down (consistent with our earlier findings in [14]) and SE-Sync is unable to re- cover a good solution. Interestingly, the chordal initialization + Gauss-Newton method appears to perform remarkably well in this regime, although here it is no longer possible to certify the correctness of its results (as the certification procedure depends upon the same semidefinite relaxation as does SE-Sync). 5.2 Large-scale SLAM datasets Next, we apply SE-Sync to the large-scale SLAM datasets considered in our previous work [14]. We are interested in both the quality of the solutions that SE-Sync obtains, as well as its computational speed when applied to challenging large-scale instances of the SLAM problem. Results are summarized in Table 1. # Nodes # Meas. fGN odom. fGN init. fSE−sync SE-Sync time SE-Sync optimal? sphere 2500 4949 5.802 · 102 5.760 · 102 5.759 · 102 6.95 ✓ sphere-a 2200 8647 3.041 · 106 1.249 · 106 1.249 · 106 3.61 ✓ torus 5000 9048 2.767 · 104 1.211 · 104 1.211 · 104 24.50 ✓ cube 8000 22236 2.747 · 105 4.216 · 104 4.216 · 104 132.44 ✓ garage 1661 6275 6.300 · 10−1 6.300 · 10−1 6.299 · 10−1 203.30 ✓ cubicle 5750 16869 6.248 · 102 6.248 · 102 6.248 · 102 181.12 ✓ Table 1. Summary of results for large-scale real-world datasets. These results confirm that the Riemannian optimization scheme developed in Section 4.1 enables SE-Sync to scale effectively to large problem sizes, and that the semidefinite relaxation Problem 3 remains exact even in these challenging real-world examples. 6 Conclusion In this paper we developed SE-Sync, a certifiably correct algorithm for syn- chronization over the special Euclidean group. This method exploits the same semidefinite relaxation used in our procedure [14] to verify in-hand optimal solu- tions, but improves upon this prior work by enabling the efficient direct computa- tion of such solutions through the use of a specialized, structure-exploiting low- dimensional Riemannian optimization approach. Experimental evaluation shows that SE-Sync is capable of recovering certifiably optimal solutions of pose-graph SLAM problems in challenging large-scale examples, and does so at a computa- tional cost comparable with that of direct Newton-type local search techniques. Bibliography [1] P.-A. Absil, C.G. Baker, and K.A. Gallivan. Trust-region methods on Rie- mannian manifolds. Found. Comput. Math., 7(3):303–330, July 2007. [2] P.-A. Absil, R. Mahony, and R. Sepulchre. Optimization Algorithms on Matrix Manifolds. Princeton University Press, 2008. [3] R. Aragues, L. Carlone, G. Calafiore, and C. Sagues. Multi-agent localiza- tion from noisy relative pose measurements. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 364–369, Shanghai, China, May 2011. [4] A.S. Bandeira. A note on probably certifiably correct algorithms. Comptes Rendus Mathematique, 354(3):329–333, 2016. [5] A.S. Bandeira, N. Boumal, and A. Singer. Tightness of the maximum likeli- hood semidefinite relaxation for angular synchronization. Math. Program., 2016. [6] N. Boumal. A Riemannian low-rank method for optimization over semidefinite matrices with block-diagonal constraints. arXiv preprint: arXiv:1506.00575v2, 2015. [7] N. Boumal, B. Mishra, P.-A. Absil, and R. Sepulchre. Manopt, a MAT- LAB toolbox for optimization on manifolds. Journal of Machine Learning Research, 15(1):1455–1459, 2014. [8] N. Boumal, P.-A. Absil, and C. Cartis. Global rates of convergence for nonconvex optimization on manifolds. arXiv preprint: arXiv:1605.08101v1, 2016. [9] N. Boumal, V. Voroninski, and A.S. Bandeira. The non-convex Burer- Monteiro approach works on smooth semidefinite programs. arXiv preprint arXiv:1606.04970v1, June 2016. [10] S. Burer and R.D.C. Monteiro. A nonlinear programming algorithm for solving semidefinite programs via low-rank factorization. Math. Program., 95:329–357, 2003. [11] S. Burer and R.D.C. Monteiro. Local minima and convergence in low-rank semidefinite programming. Math. Program., 103:427–444, 2005. [12] L. Carlone and A. Censi. From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimiza- tion. IEEE Trans. on Robotics, 30(2):475–492, April 2014. [13] L. Carlone and F. Dellaert. Duality-based verification techniques for 2D SLAM. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 4589–4596, Seattle, WA, May 2015. [14] L. Carlone, D.M. Rosen, G. Calafiore, J.J. Leonard, and F. Dellaert. La- grangian duality in 3D SLAM: Verification techniques and optimal solu- tions. In IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS), Hamburg, Germany, September 2015. [15] L. Carlone, R. Tron, K. Daniilidis, and F. Dellaert. Initialization techniques for 3D SLAM: A survey on rotation estimation and its use in pose graph optimization. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 4597–4605, Seattle, WA, May 2015. [16] L. Carlone, G.C. Calafiore, C. Tommolillo, and F. Dellaert. Planar pose graph optimization: Duality, optimal solutions, and verification. IEEE Trans. on Robotics, 32(3):545–565, June 2016. [17] A. Chiuso, G. Picci, and S. Soatto. Wide-sense estimation on the special orthogonal group. Communications in Information and Systems, 8(3):185– 200, 2008. [18] F. Dellaert and M. Kaess. Square Root SAM: Simultaneous localization and mapping via square root information smoothing. Intl. J. of Robotics Research, 25(12):1181–1203, December 2006. [19] A. Edelman, T.A. Arias, and S.T. Smith. The geometry of algorithms with orthogonality constraints. SIAM J. Matrix Anal. Appl., 20(2):303– 353, October 1998. [20] T.S. Ferguson. A Course in Large Sample Theory. Chapman & Hall/CRC, Boca Raton, FL, 1996. [21] J. Gallier. The Schur complement and symmetric positive semidefinite (and definite) matrices. unpublished note, available online: http://www.cis. upenn.edu/~jean/schur-comp.pdf, December 2010. [22] G. Grisetti, C. Stachniss, and W. Burgard. Nonlinear constraint network optimization for efficient map learning. IEEE Trans. on Intelligent Trans- portation Systems, 10(3):428–439, September 2009. [23] R. Hartley, J. Trumpf, Y. Dai, and H. Li. Rotation averaging. Intl. J. of Computer Vision, 103(3):267–305, July 2013. [24] S. Huang, Y. Lai, U. Frese, and G. Dissanayake. How far is SLAM from a linear least squares problem? In IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS), pages 3011–3016, Taipei, Taiwan, October 2010. [25] S. Huang, H. Wang, U. Frese, and G. Dissanayake. On the number of local minima to the point feature based SLAM problem. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 2074–2079, St. Paul, MN, May 2012. [26] M. Kaess, H. Johannsson, R. Roberts, V. Ila, J.J. Leonard, and F. Dellaert. iSAM2: Incremental smoothing and mapping using the Bayes tree. Intl. J. of Robotics Research, 31(2):216–235, February 2012. [27] R. K¨ummerle, G. Grisetti, H. Strasdat, K. Konolige, and W. Burgard. g2o: A general framework for graph optimization. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 3607–3613, Shanghai, China, May 2011. [28] F. Lu and E. Milios. Globally consistent range scan alignment for environ- mental mapping. Autonomous Robots, 4:333–349, April 1997. [29] Z.-Q. Luo, W.-K. Ma, A. So, Y. Ye, and S. Zhang. Semidefinite relaxation of quadratic optimization problems. IEEE Signal Processing Magazine, 27 (3):20–34, May 2010. [30] D. Martinec and T. Pajdla. Robust rotation and translation estimation in multiview reconstruction. In IEEE Intl. Conf. on Computer Vision and Pattern Recognition (CVPR), pages 1–8, Minneapolis, MN, June 2007. [31] J. Nocedal and S.J. Wright. Numerical Optimization. Springer Sci- ence+Business Media, New York, 2nd edition, 2006. [32] E. Olson, J.J. Leonard, and S. Teller. Fast iterative alignment of pose graphs with poor initial estimates. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 2262–2269, Orlando, FL, May 2006. [33] J.R. Peters, D. Borra, B.E. Paden, and F. Bullo. Sensor network localization on the group of three-dimensional displacements. SIAM J. Control Optim., 53(6):3534–3561, 2015. [34] D.M. Rosen, M. Kaess, and J.J. Leonard. RISE: An incremental trust-region method for robust online sparse least-squares estimation. IEEE Trans. on Robotics, 30(5):1091–1108, October 2014. [35] D.M. Rosen, C. DuHadway, and J.J. Leonard. A convex relaxation for approximate global optimization in simultaneous localization and mapping. In IEEE Intl. Conf. on Robotics and Automation (ICRA), pages 5822–5829, Seattle, WA, May 2015. [36] D.M. Rosen, L. Carlone, A.S. Bandeira, and J.J. Leonard. SE-Sync: A certifiably correct algorithm for synchronization over the special Euclidean group. Technical Report MIT-CSAIL-TR-2017-002, Computer Science and Artificial Intelligence Laboratory, Massachusetts Institute of Technology, Cambridge, MA, February 2017. [37] A. Singer and Y. Shkolnisky. Three-dimensional structure determination from common lines in cryo-EM by eigenvectors and semidefinite program- ming. SIAM J. Imaging Sci., 4(2):543–572, 2011. [38] A. Singer and H.-T. Wu. Vector diffusion maps and the connection Lapla- cian. Comm. Pure Appl. Math., 65:1067–1144, 2012. [39] M.J. Todd. Semidefinite optimization. Acta Numerica, 10:515–560, 2001. [40] R. Tron and R. Vidal. Distributed 3-D localization of camera sensor net- works from 2-D image measurements. IEEE Trans. on Automatic Control, 59(12):3325–3340, December 2014. [41] S. Umeyama. Least-squares estimation of transformation parameters be- tween two point patterns. IEEE Trans. on Pattern Analysis and Machine Intelligence, 13(4):376–380, 1991. [42] V. Vandenberghe and S. Boyd. Semidefinite programming. SIAM Review, 38(1):49–95, March 1996. [43] B. Vlasic and N.E. Boudette. As U.S. investigates fatal Tesla crash, com- pany defends Autopilot system. The New York Times, July 12, 2016. Re- trieved from http://www.nytimes.com. [44] H. Wang, G. Hu, S. Huang, and G. Dissanayake. On the structure of non- linearities in pose graph SLAM. In Robotics: Science and Systems (RSS), Sydney, Australia, July 2012. [45] L. Wang and A. Singer. Exact and stable recovery of rotations for robust synchronization. Information and Inference, September 2013.