JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 1 Rapidly computable viscous friction and no-slip rigid contact models Evan Drumwright Abstract—This article presents computationally efficient al- gorithms for modeling two special cases of rigid contact— contact with only viscous friction and contact without slip—that have particularly useful applications in robotic locomotion and grasping. Modeling rigid contact with Coulomb friction generally exhibits O(n3) expected time complexity in the number of contact points and 2O(n) worst-case complexity. The special cases we consider exhibit O(m3+m2n) time complexity (m is the number of independent coordinates in the multi rigid body system) in the expected case and polynomial complexity in the worst case; thus, asymptotic complexity is no longer driven by number of contact points (which is conceivably limitless) but instead is more dependent on the number of bodies in the system (which is often fixed). These special cases also require considerably fewer constrained nonlinear optimization variables thus yielding substantial improvements in running time. Finally, these special cases also afford one other advantage: the nonlinear optimization problems are numerically easier to solve. I. INTRODUCTION Dynamic robotic simulation; grasp planning; and, increas- ingly, locomotion planning and control employ rigid contact models with dry (typically Coulomb) and wet (viscous) fric- tion. These contact models yield an effective tradeoff between computation speed and physical accuracy. While rigid contact models are far faster than, e.g., elastodynamic finite element analysis, they still require heavy computation: the expected time complexity for such models is O(n3) in the number of contact points. Additionally, the number of contact points input to the model is conceivably limitless. This issue is not just theoretically interesting: Wang [25] reports that solving the contact problem absorbs up to 90% of computation time when simulating a scenario for the DARPA Robotics Challenge using ODE [19]. Roboticists are often content to use rigid contact models without Coulomb friction for computational expediency. For example, one may wish to model locomotion or effect sim- ulated grasping without observing slip; roboticists studying legged locomotion often predicate their models on no slip occurring, for example. If slip is desirable, purely viscous friction might yield a suitable model if, for example, a robot is walking on a wet surface. This article presents computationally efficient methods for both of these special cases. These special cases provide the following computational and modeling advantages: () time complexity goes from worst- case exponential (the worst-case complexity of solving rigid contact problems with Coulomb friction [23, 1] using Lemke’s E. Drumwright is with the Department of Computer Science, George Washington University, Washington, DC {drum@gwu.edu} Manuscript received April 19, 2005; revised December 27, 2012. Algorithm [15]) to worst-case polynomial in the number of contact points; () significant reduction in the number of nonlinear optimization problem variables; and () a positive- semi-definite-matrix linear complementarity problem (LCP), in place of a copositive-plus LCP, which is demonstrably easier to solve [8] (i.e., the solver is less likely to fail due to numerical errors) and permits the use of general algorithms for solving convex optimization problems. Finally, we provide an algorithm that yields O(m3 + m2n) expected asymptotic time complexity on these two contact models, where m is the number of independent coordinates in the multi rigid body system. This algorithm therefore provides a means to make complexity more dependent on the number of independent coordinates in the system (this number remains constant except in the unusual case in which bodies are inserted into the simulation) than on the number of contact points (which is conceivably unlimited). II. LCPS, NCPS, AND MLCPS A LCP, or linear complementarity problem, (r, Q) signifies the problem: w = Qz + r w ≥0 z ≥0 zTw = 0 for unknown vectors z, w ∈Rq. A nonlinear complementarity problem (NCP) is composed of a number of nonlinear complementarity constraints [6] that take the form: x ≥0 (1) f(x) ≥0 (2) xTf(x) = 0 (3) where x ∈Rq and f : Rq →Rq. A mixed linear complementarity problem (MLCP) is de- fined by the following constraints: Ax + Cy + g = 0 (4) Dx + By + h ≥0 (5) y ≥0 (6) yT(Cx + Dy + h) = 0 (7) Note that the x variables are unconstrained, while the y variables must be non-negative. If A is non-singular, the arXiv:1504.00719v1 [cs.RO] 3 Apr 2015 JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 2 unconstrained variables can be computed as: x = −A−1(Cy + g) (8) Substituting x into equations 4–7 yields the LCP (e, F): F ≡B −DA−1C (9) e ≡h −DA−1g (10) A solution (y, ν) to this LCP obeys the relationship Fy+e = ν; once one has y, x may be determined via Equation 8, and the MCLP is solved. III. BACKGROUND A. Coulomb friction Coulomb’s friction model provides relationships between the force applied along the contact normal and the frictional forces. Coulomb friction considers two cases, rolling/sticking and sliding. The former occurs when the velocity is zero in the tangent plane of the contact frame; conversely, sliding occurs when that velocity is non-zero. The magnitude of the friction force for a sliding contact modeled with Coulomb friction is given by the equation: ff = µcfn (11) where fn is the magnitude of the force applied along the contact normal. The frictional force is applied directly opposite the direction of sliding (i.e., against the relative velocity in the tangent plane of the contact frame). The magnitude of the friction force for a rolling or stick- ing contact modeled with Coulomb friction is given by the equation: ff ≤µcfn (12) In the case of rolling/sticking friction, the friction force acts to resist motion in the tangent (e.g., in the case of a box resting on a slope); thus, ff may be strictly less than µcfn. If external forces become sufficiently large to overcome rolling/sticking friction forces, the rolling/sticking contact will transition to sliding. Many applications in robotics use the Coulomb friction model because it is relatively straightforward to compute— one can determine the frictional forces without integrating ordinary differential equations—and it is reasonably predic- tive. Nevertheless, Coulomb friction is somewhat expensive (computationally) to model: the rigid contact models of Stew- art and Trinkle [23] and Anitescu and Potra [1] can be solved in expected polynomial time in the n contacts1, though exponential complexity may be exhibited in the worst case. B. Acceleration-level rigid body contact model with Coulomb and viscous friction We now describe the rigid contact model with Coulomb and viscous friction that uses only non-impulsive forces for consistency with the principle of constraints [10]. The multi 1These models yield an order n copositive-plus LCP solvable by Lemke’s Algorithm [12]. Each iteration of Lemke’s Algorithm requires an O(n2) matrix factorization update, and n iterations of the algorithm are expected [6]. rigid body dynamics equation with contact and joint constraint forces is given below: M(t) ˙v =f(t) + J(t)Tfj + N(t)Tfn + . . . (13) Sk(t)Tfs + Tk(t)Tft −Q(t)Tfq −. . . (14) S(t)TµvS(t)v −T(t)TµvT(t)v (15) where M ∈Rm×m is the system inertia matrix; v ∈Rm is the system velocity; J ∈Rj×m is the matrix of j bilateral constraint equations; N ∈Rn×m, S ∈Rn×m, and T ∈Rn×m are matrices of n wrenches applied along the contact normal, first contact tangent, and second contact tangent, respectively; Q ∈Rr×m is a matrix of r generalized wrenches applied against the direction of sliding for r ≤n sliding contacts; fj ∈ Rj is the vector bilateral constraint force magnitudes; fn ∈ Rn is a vector of contact normal force magnitudes; fs ∈Rk and ft ∈Rk are vectors of contact tangent force magnitudes applied at the k = n −r rolling/sticking contacts; fq ∈Rr is a vector of contact tangent force magnitudes applied at the r sliding contacts; f is a vector of forces on the rigid body system (gravity, Coriolis and centrifugal forces, etc.); and µv is a diagonal matrix of viscous friction coefficients. Equation 14 specifies the Coulomb friction forces and Equation 15 specifies the viscous friction forces. The viscous model, where friction forces oppose the direction of motion, is commonly used in robotics (see, e.g., [17]) and is a simplifica- tion of the viscous drag term in fluid dynamics. Out of the n points of contact in the system, some may be rolling/sticking and the remainder will be sliding. For Coulomb friction, the first two terms of Equation 14 (Sk(t)Tfs + Tk(t)Tft) are relevant to the rolling/sticking contacts only (k specifies the indices of S and T that correspond to rolling/sticking contacts) and the last term (−Q(t)Tfq) is relevant to only sliding contacts. 1) Bilateral constraint equation: Bilateral constraints can be specified in the form φ(q) = 0, where q are the generalized coordinates of the system (joint constraints that are an explicit function of time are not considered here, though their inclusion would not change the results in this article). Such constraints can be differentiated once with respect to time to yield: J ˙v = 0 (16) where J ≡∂φ ∂q . If we differentiate the constraints with respect to time once more, the bilateral joint constraints can be enforced using the equation: J ˙v + ˙Jv = 0 (17) where ˙J ≡ ∂ ∂qJv. 2) Contact normal constraints: We assume that there are n points of contact. The ith contact must satisfy the following linear complementarity condition that relates normal force and non-interpenetration: 0 ≤fni ⊥ni T ˙v + ˙ni Tv ≥0 (18) where ni and ˙ni are column vectors taken from the ith rows of N and ˙N, respectively. Here we adopt the notation a ⊥b to denote the relationship a · b = 0. fni ≥0 requires that the contact force can only push bodies apart, niT ˙v + ˙ niTv ≥0 JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 3 requires that the bodies cannot be accelerating toward one another at the ith contact point after the contact forces are applied, and the fni · (niT ˙v + ˙ni Tv) = 0 constraint ensures that frictionless contact does no work. 3) Sliding friction: If the velocity in the tangent plane at the ith contact point is non-zero, then the contact is sliding, and the Coulomb friction model specifies the magnitude of force to be applied. |fqi| = µ|fni| (19) 4) Rolling/sticking friction: If the velocity at time t in the tangent plane at the ith contact point is zero, then the contact is rolling/sticking at time t and may either continue rolling/sticking or begin sliding, depending on the normal force and Coulomb friction coefficient. The nonlinear com- plementarity conditions are then expressed by the following equations (adapted from [24]): 0 ≤u2f 2 ni −f 2 si −f 2 ti ⊥ q ˙v2si + ˙v2 ti ≥0 (20) 0 = µfni ˙vsi + fsi q ˙v2si + ˙v2 ti (21) 0 = µfni ˙vti + fti q ˙v2si + ˙v2 ti (22) Let us now examine the constraints above. Equation 20 constrains the frictional force to lie within the friction cone; if the tangential acceleration is non-zero, then the frictional force must lie on the edge of the friction cone. Equations 21 and 22 ensure that the frictional force opposes the tangent accelera- tion. 5) Solvability of the model: Others (e.g., [2]) have already shown that this rigid model may not possess a solution if there are any sliding contacts; such contact scenarios are known as inconsistent configurations. Nevertheless, we present this model because the contact model with Coulomb friction, which we present next and use to motivate the move to a velocity-level contact model, will build off of it. C. Solvable rigid body contact model with Coulomb and viscous friction The contact model of Stewart and Trinkle [23] and Anitescu and Potra [1] provides a guaranteed solution to the problem of inconsistent configurations in contact models with Coulomb friction. This model is presented to show a velocity-level formulation, which allows the model to overcome the issue of inconsistent configurations. The no-slip model introduced in Section VI will also employ a velocity-level formulation to simulate contact without sliding in arbitrary configurations; Lynch and Mason showed that sliding with infinite friction is possible for the acceleration-level model described in the previous section [13]. We now describe this contact model—we consider only the aspect of the model that treats all contacts as inelastic impacts and do not consider extensions to collisional impacts with restitution. For simplicity of presentation, we do not linearize the friction cone, which yields a NCP rather than the LCP in [23, 1]. The contact model uses a first-order approximation to the rigid body dynamics to resolve issues like Painlev´e’s Paradox (and other inconsistent contact configurations [2]), for which no non-impulsive force solutions exist. The rigid body dynam- ics are given by: M(t)∆v =∆tf(t) + J(t)Tfj + . . . (23) N(t)Tfn + S(t)Tfs + T(t)Tft where M, v, J, N, S, T, fj, fn, fs, ft, and f are as defined in Section III-B and ∆t is the change in time that realizes the first-order approximation. We now define v∗≡v + ∆v. 1) Bilateral constraint equation: Because the bilateral joint constraints are now defined at the velocity level, the constraints are enforced using the equation: Jv∗= 0 (24) 2) Contact normal constraints: The velocity-level con- straints on contact normal force and non-interpenetration are now defined as: 0 ≤fni ⊥nT i v∗≥0 (25) 3) Coulomb friction constraints: Coulomb friction is ef- fected more simply in this model than in the acceleration- level model: contacts can be treated identically whether they are initially sliding or sticking. The nonlinear complementarity conditions for the ith contact are: 0 ≤u2f 2 ni −f 2 si −f 2 ti ⊥ q v∗2 si + v ∗2 ti ≥0 (26) 0 = µfniv∗ si + fsi q v∗2 si + v∗2 ti (27) 0 = µfniv∗ ti + fti q v∗2 si + v∗2 ti (28) These equations are analogous to Equations 20–22. If the nonlinear complementarity conditions are converted to linear complementarity constraints by use of a linearized friction cone (i.e., a friction polygon), then a provably solvable copositive-plus LCP [6] results. However, Lemke’s Algo- rithm [12] is currently the only algorithm provably capable of solving copositive-plus LCPs. Lemke’s Algorithm can ex- hibit exponential complexity [15], though polynomial time is expected. IV. CONTACT MODEL WITH PURELY VISCOUS FRICTION We now describe the contact model with purely viscous friction. We start from the multi rigid body dynamics equation at the acceleration level (Equations 13 and 15), which are reproduced below: M(t) ˙v =f(t) + J(t)Tfj + N(t)Tfn + . . . S(t)TµvS(t)v −T(t)TµvT(t)v To this we add bilateral constraints (Equation III-B1) and the normal contact compressive force and non-interpenetration and complementarity constraints (Equation III-B2), again re- produced below: J ˙v + ˙Jv = 0 0 ≤ni T ˙v + ˙ni Tv ⊥fni ≥0 for i = 1, . . . , n JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 4 Combining these equations yields the following MLCP:   M −JT −NT J 0 0 N 0 0     ˙v fj fn  +   f ∗ ˙Jv ˙Nv  =   0 0 γ   (29) fn ≥0 (30) γ ≥0 (31) f T n γ = 0 (32) where f ∗≡−f +STµvSv+TTµvTv and γ ≡N ˙v+ ˙Nv. As long as J has full row rank (we will describe how to ensure this condition in the next section), the mixed LCP can be converted to a conventional LCP (as described in Section II) using the following definitions: A ≡  M −JT J 0  (33) C ≡  −NT 0  (34) D ≡−CT (35) B ≡0 (36) x ≡  ˙v fj  (37) y ≡fn (38) g ≡ −f ∗ 0  (39) h ≡0 (40) Equations 9 and 10 then yield the following standard LCP: F ≡NA−1NT (41) e ≡NA−1f ∗ (42) The system inertia matrix is block diagonal (each block is invertible), so A is invertible if J has full row rank (if it is not—indicating that one or more constraints is redundant— a subset of J which has full row rank can be used to ensure that A is invertible). From [3], a matrix of F’s form must be non-negative definite, i.e., either positive semi- definite (PSD) or positive definite (PD). Additionally, Baraff provided an algorithm that provably solved LCPs of the form (Gr, GHGT), where H ∈Rm×m is a symmetric matrix, r ∈Rm, and G ∈Rn×m [2]. Finally, we note that LCPs with PSD/PD matrices are equivalent to convex quadratic programs [6], which means that solving the LCP exhibits worst-case polynomial computational complexity. V. REDUCING EXPECTED TIME COMPLEXITY FROM O(n3) TO O(m3 + m2n) A system with m degrees-of-freedom requires no more than m positive force magnitudes applied along the contact normals to satisfy the constraints for the contact models with purely viscous friction and without slip (the latter model will be presented in Section VI). We now prove this statement. Assume we permute and partition the rows of N into r linearly independent and n −r linearly dependent rows, denoted by indices I and D, respectively, as follows: N = NI ND  (43) Then the LCP vectors q = Nv, z ∈Rn, and w ∈Rn and LCP matrix Q = NA−1NT can be partitioned as follows: QII QID QDI QDD  zI zD  + qI qD  = wI wD  (44) Given some matrix α ∈R(n−r)×r, it is the case that ND = αNI, and therefore that QDI = αNIA−1NI T, QID = NIA−1NI TαT (by symmetry), QDD = αNIA−1NI TαT, and qD = αNIv. Lemma 1. Since rank(XY) ≤min (rank(X), rank(Y)), the number of positive components of zI can not be greater than rank(A). Proof. Since the columns of XY have X multiplied by each column of Y, i.e., XY = Xy1 Xy2 . . . Xyn  . Columns in Y that are linearly dependent will thus produce columns in XY that are linearly dependent (with precisely the same coefficients). Thus, rank(XY) ≤rank(Y). Applying the same argument to the transposes produces rank(XY) ≤rank(X), thereby proving the claim. We now show that—in the case that the number of positive components of zI is equal to the rank of A—no more positive force magnitudes are necessary to solve the LCP. Theorem 1. If (zI = a, wI = 0) is a solution to the LCP (qI, QII), then (  zIT = aT zDT = 0TT , w = 0) is a solution to the LCP (q, Q). Proof. For (  zIT = aT zDT = 0TT , w = 0) to be a solu- tion to the LCP (q, Q), six conditions must be satisfied: 1) zI ≥0 2) wI ≥0 3) zITwI = 0 4) zD ≥0 5) wD ≥0 6) zDTwD = 0 Of these, (), (), and () are met trivially by the assumptions of the theorem. Since zD = 0, QIIzI + QIDzD + qI = 0, and thus wI = 0, thus satisfying () and (). Also due to zD = 0, it suffices to show for () that QDIzI + qD ≥0. From above, the left hand side of this equation is equivalent to α(NIA−1NI Ta + NIv), or αwI, which itself is equivalent to α0. Thus, wD = 0. 4) Algorithm: We use the theorem above to make a mi- nor modification to the Principal Pivot Method I [5, 15] (PPM), which solves LCPs with P-matrices (complex square matrices with fully non-negative principal minors [15] that includes positive semi-definite matrices as a proper subset). The resulting algorithm limits the size of matrix solves and multiplications. The PPM uses a set β with maximum cardinality n for a LCP of order n. Of a pair of LCP variables, (zi, wi), exactly one will be in β; we say that the other belongs to β. If a JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 5 variable belongs to β, we say that the variable is a basic variable; otherwise, it is a non-basic variable. Using this set, partition the LCP matrices and vectors as shown below: wβ wβ  = Aββ Aββ Aββ Aββ  zβ zβ  + qβ qβ  Segregating the basic and non-basic variables on different sides yields: wβ zβ  = " Aββ −AββAββ −1 AββAββ −1 −Aββ −1Aββ Aββ −1 # zβ wβ  + . . . " qβ −AββAββ −1qβ −Aββ −1qβ # If we set the values of the basic variables to zero, then solving for the values of the non-basic variables zB and wB entails only block inversion of A. The unmodified PPM I operates in the following manner: ()Find an index i of a basic variable xi (where xi is either wi or zi, depending which of the two is basic) such that xi < 0; () swap the variables between basic and non-basic sets for index i (e.g., if wi is basic and zi is non-basic, make wi non- basic and zi basic); () determine new values of z and w; () repeat ()–() until no basic variable has a negative value. PPM I requires few modifications, which are provided in Algorithm 1. First, the full matrix N · M−1 · NT is never constructed (such construction would require O(n3) time). Instead, Line 1 of the algorithm constructs a maximum m×m system; thus, that operation requires only O(m3) operations. Similarly, Lines 13–14 also leverage Theorem 1 in order to compute w† and a† efficiently (though these operations do not affect the asymptotic time complexity). Assuming that the number of iterations for a pivoting algorithm is O(n) in the size of the input,2 and that each iteration requires at most two pivot operations (each rank-1 update operation to a matrix factorization will exhibit time complexity O(m2)), the asymptotic complexity of the modified PPM I algorithm is O(m3+m2n). The termination conditions for the algorithm are not affected by our modifications. VI. NO-SLIP CONTACT MODEL A contact model without slip requires a velocity-level contact model in accordance with Lynch and Mason’s finding that sliding can occur with infinite friction at the acceleration level [13]. The no-slip friction contact model uses the first- order approximation and builds on Equations 23, 24, and 25 by dictating that the tangential velocity at each contact must be zero at v(t + ∆t): Sv(t + ∆t) = 0 (45) Tv(t + ∆t) = 0 (46) 2Regardless of the pathological problem devised by Klee and Minty[11], experience with the Simplex Algorithm on thousands of practical problems shows that it requires fewer than 3n iterations and the expected time complexity for the Simplex Algorithm is polynomial [18, 20]. We are unaware of research that shows these results are also applicable to pivoting methods for LCPs, though Cottle et al. claim O(n) expected iterations [6]. Forming these five equations into a MLCP and using the variable definitions in Section II yields: A ≡   M −JT −ST −TT J 0 0 0 S 0 0 0 T 0 0 0   (47) C ≡   −NT 0 0 0   (48) D ≡−CT (49) B ≡0 (50) (51) x ≡   v(t + ∆t) fj 0 0   (52) y ≡fn (53) g ≡   −Mv(t) 0 0 0   (54) h ≡0 (55) The matrix A may be singular, which would prevent us from converting the MLCP to a standard LCP. However, if J, S, and T have full row rank or we identify the largest row blocks of those matrices such that full row rank is attained, A is invertible without affecting the solution to the MLCP. Algorithm 2 performs exactly this task. The singularity check on Lines 7, 14, and 19 of Algorithm 2 is best performed using a Cholesky factorization; if the fac- torization is successful, the matrix is non-singular. Given that M is non-singular (it is symmetric and positive definite), the maximum size of X in Algorithm 2 is m × m; if X were larger, it would be singular (see Lemma 1). Given this information, the time complexity of Algorithm 2 is dominated by Lines 7, 14, and 19. As X changes by at most one row and one column per Cholesky factorization, singularity can be checked by O(m2) updates to an initial O(m3) Cholesky factorization. The overall time complexity is O(m3 + nm2). A. Resulting systems Using Equations 9 and 10), the LCP matrix F and vector e are equivalent to: F ≡NX−1NT (56) e ≡NX−1Mv(t) (57) As in Section IV, F must be symmetric and positive-semi- definite and—as noted in Section IV—Baraff’s algorithm [2] guarantees that a solution to this LCP exists. The Sv(t + ∆t) = Tv(t + ∆t) = 0 constraints (Equa- tions 45 and 46) and solvability of the LCP contrast with the JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 6 Algorithm 1 {z, w} = LCP(N, M, f ∗) Solves a frictionless contact model using a modification of the Principal Pivoting Method I Algorithm. 1: n ←rows(N) 2: q ←N · f ∗ 3: i ←arg mini qi ▷Check for trivial solution 4: if qi ≥0 then 5: return {0, q} 6: end if 7: B ←{i} ▷Establish initial nonbasic indices 8: B ←{1, . . . , i −1, i + 1, . . . , n} ▷Establish initial basic indices 9: while true do 10: A ←NB · M−1 · NB T 11: b ←NB · f ∗ 12: z† ←A−1 · −b . ▷Solve for non-basic components of z 13: a† ←M−1 · NB Tz† + f ∗ 14: w† ←N · a† 15: i ←arg mini w† i ▷Find the index for moving into the non-basic set (if any) 16: if w† i ≥0 then 17: j ←arg mini z† i ▷No index to move into the non-basic set; look whether there is an index to 18: . move into the basic set 19: if z† j < 0 then 20: k ←B(j) 21: B ←B ∪{k} ▷Move index k into the basic set 22: B ←B −{k} 23: continue 24: else 25: z ←0 26: zB ←z† 27: w ←0 28: wB ←w† 29: return {z, w} 30: end if 31: else 32: B ←B ∪{i} ▷Move index i into the non-basic set 33: B ←B −{i} 34: j ←arg mini z† i ▷Look whether there is an index to move into the basic set 35: if z† j < 0 then 36: k ←B(j) 37: B ←B ∪{k} ▷Move index k into the basic set 38: B ←B −{k} 39: end if 40: end if 41: end while finding of Lynch and Mason [13], who showed that sliding with infinite friction is possible. The admittance of impulsive forces has resolved this “paradox” analogously to the manner in which contact models like [23, 1] resolved Painlev´e’s Para- dox [16] and other inconsistent contact configurations [22]. VII. EXPERIMENTS We tested the contact models using two common con- tact scenarios in robotics, grasping and locomotion, in or- der to assess speed and numerical stability. These experi- ments can be reproduced using the experimental setup de- scribed at https://github.com/PositronicsLab/ no-slip-and-viscous-experiments. A. Grasping experiment We used RPIsim (https://code.google.com/p/ rpi-matlab-simulator) to simulate a force-closure grasping scenario (depicted in Figure 1) on a Macbook Air with 1.8 GHz Intel Core i5 CPU. Twelve contact points were generated between each pair of boxes3, yielding 36 contact points total. For the contact model with Coulomb friction (the Stewart-Trinkle model [21]), a friction “pyramid” (four 3The equal size boxes contacting in the manner in Figure 1 yields degenerate contact normals at the box corners; the RPI simulator treats this problem by duplicating each contact with all three possible directions for the contact normal. JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 7 Algorithm 2 FIND-INDICES(M, J, S, T), determines the row indices (J , S, and T ) of J, S, and T such that the equality matrix A (Equation 4) is non-singular. 1: J ←∅ 2: S ←∅ 3: T ←∅ 4: for i = 1, . . . r do ▷r is the number of bilateral constraint equations 5: J ∗←J ∪{i} 6: Set X ←JT J ∗ 7: if XTM−1X not singular then 8: J ←J ∗ 9: end if 10: end for 11: for i = 1, . . . , n do ▷n is the number of contacts 12: S∗←S ∪{i} 13: Set X ←  JT J ST S∗ TT T  14: if XTM−1X not singular then 15: S ←S∗ 16: end if 17: T ∗←T ∪{i} 18: Set X ←  JT J ST S TT T ∗  19: if XTM−1X not singular then 20: T ←T ∗ 21: end if 22: end for 23: return {J , S, T } sided approximation to the friction cone) was used, yielding six LCP variables per contact (i.e., 216 variables total). The RPI simulator allowed us to substitute the Stewart-Trinkle model with the no-slip friction model readily, which resulted in only 36 LCP variables. The simulation was run using a step size of 0.01 for ten iterations ( 1 10 of one second of simulated time); the grasped objects would tend to fall from the gripper after ten iterations only when using Stewart- Trinkle (due to numerical issues with Lemke’s Algorithm, to be discussed below). Lemke’s Algorithm was implemented using LEMKE [9]. The P0 matrix resulting from the no-slip friction model allowed us to employ the modified PPM solver and MATLAB’s quadprog solver (with the active-set algorithm) to solve the LCP. We used Lemke’s Algorithm [12], employing Tikhonov regularization [6] as necessary, to solve the Stewart-Trinkle model. No low-rank updates were used in our implementation of Algorithm 2. Contact model Running time (mean ± σ) Stewart-Trinkle (Lemke’s Algorithm) 10.9681s ± 2.1812s µc = 100.0, µv = 0.0 No-slip (active-set QP solver) 1.9892s ± 0.2640s No-slip (modified PPM) 1.6680s ± 0.3669s TABLE I MEAN RUNNING TIMES FOR THE GRASPING EXPERIMENT. TEN TRIALS WERE RUN FOR EACH METHOD. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). This experiment yielded several findings. As expected, Fig. 1. A depiction of the grasping experiment described in Section VII-A. The two red boxes act as grippers and push inward. Gravity pushes downward. Given sufficient friction (µ = ∞), the grippers should ideally keep the blue boxes grasped using force closure. reducing the LCP variables by a factor of five (216 variables to 36 variables) results in much faster solutions (451–558% faster mean, depending on the solver). Fewer variables also results in less rounding error; the no-slip approach was able to model the grasping scenario reliably for at least 100 iterations (again, compared to around ten iterations for Stewart-Trinkle). Of the twelve contacts per pair of boxes, it was only necessary to apply forces to two contacts, which the modified PPM method was able to exploit: it ran nearly 20% faster than the quadprog algorithm (mean and maximum numbers of pivot operations were observed to be 5.5 and 7, respectively). This performance differential is considerable given that our modified PPM algorithm was not implemented as a MEX file and that our implementation does not use low-rank updates to maximize performance). B. Locomotion experiments We used the Moby simulator (https://github.com/ PositronicsLab/Moby) to simulate a quadrupedal robot walking on a terrain map (see Figure 2) over ten seconds. An event-driven method (see [4] for a description of this paradigm) is used to simulate the system instead of the time- stepping approaches used in ODE, Bullet, and RPIsim; popular implementations of this approach are susceptible to energy gain when correcting interpenetration [21], which destabilizes our robot in the process. The integration method used for the no-slip model experi- ment is symplectic Euler (St¨ormer-Verlet) with a step size of 0.001, while fourth-order Runge-Kutta integration was used for the viscous model experiment with identical step size. Our approach using the former integrator allows only the no-slip model to be activated, while our approach using the latter integrator permits the acceleration-level viscous model to be used for sustained contacts. When impacts occur (e.g., on initial foot/ground contact) in the latter approach, the simulation uses an inelastic impact model [7] with purely viscous friction. Locomotion experiments were run on an Intel Xeon 2.27GHz desktop computer. All aspects of the simulation, including forward dynamics computations, collision detection, JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 8 and controls (which performs dynamics calculations) were accounted for in results; single LCP solves generally run too quickly to obtain timings for just that operation. We point out that the simulations run considerably slower than similar systems modeled using, e.g., ODE, but the goals of the two simulators. ODE uses approximate solves and permits interpenetration. Moby aims to provide a verifiable simulator, i.e., one that adheres closely to the rigid body dynamics models (which means that interpenetration is impermissible). Results for the no-slip experiment are provided in Ta- ble VII-B, which shows a speedup of nearly 28%. The minimum and maximum number of contact points generated in the experiment is 1 and 30, respectively; the mean number of contact points is 6, and the standard deviation is 8. Thus, simulations with greater numbers of contacts could expect greater performance differentials. Results for the viscous experiment are provided in Ta- ble VII-B, which shows a speedup of over 37%. We note that the viscous friction experiments required significantly longer to run than the no-slip experiments. We hypothesize that this disparity is due to the behavior of the simulation when applying the viscous model, which tends to produce rapid movements upon contact. Those rapid movements, which appear due to some sensitivity in the underlying ordinary dif- ferential equations, slow the simulator’s continuous collision detection system (see [14] for a description of that system). Fig. 2. A depiction of the quadrupedal robot walking on a terrain map in the locomotion experiment, as described in Section VII-B. The no-slip and viscous friction models were both assessed. Contact model Running time Drumwright-Shell 416.284s µc = 100.0, µv = 0.0 No-slip (modified PPM) 301.796s TABLE II TIMES REQUIRED TO SIMULATE THE QUADRUPED LOCOMOTION SCENARIO DESCRIBED IN SECTION VII-B UNDER A NO-SLIP CONTACT MODEL. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). VIII. CONCLUSION We presented an algorithm for rapidly computing two rigid contact models without Coulomb friction that have proven useful in certain modeling and simulation applications for Contact model Running time Viscous (Lemke’s Algorithm) 2936.36s µc = 0.0, µv = 0.1 Viscous (modified PPM) 2139.73s TABLE III TIMES REQUIRED TO SIMULATE THE QUADRUPED LOCOMOTION SCENARIO DESCRIBED IN SECTION VII-B UNDER A PURELY VISCOUS FRICTION MODEL. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). robotics. We showed how these models exhibit both asymp- totic computational complexity and significant running time advantages over rigid models with Coulomb friction. While we do not expect these special-case models to replace rigid models with Coulomb friction, the former serve as computationally efficient alternatives as applications allow. IX. ACKNOWLEDGEMENTS We thank Sam Zapolsky for providing the quadruped model and the locomotion controller. This work was funded by NSF CMMI-110532. REFERENCES [1] M. Anitescu and F. A. Potra. Formulating dynamic multi- rigid-body contact problems with friction as solvable linear complementarity problems. Nonlinear Dynamics, 14:231–247, 1997. [2] D. Baraff. Fast contact force computation for nonpen- etrating rigid bodies. In Proc. of SIGGRAPH, Orlando, FL, July 1994. [3] R. Bhatia. Positive definite matrices. Princeton University Press, 2007. [4] B. Brogliato, A. A. ten Dam, L. Paoli, F. G´enot, and S. Abadie. Numerical simulation of finite dimensional multibody nonsmooth mechanical systems. ASME Appl. Mech. Reviews, 55(2):107–150, March 2002. [5] R. W. Cottle. The principal pivoting method of quadratic programming. In G. Dantzig and J. A. F. Veinott, editors, Mathematics of Decision Sciences, pages 144–162. AMS, Rhode Island, 1968. [6] R. W. Cottle, J.-S. Pang, and R. Stone. The Linear Complementarity Problem. Academic Press, Boston, 1992. [7] E. Drumwright. Avoiding Zeno’s paradox in impulse- based rigid body simulation. In Proc. of IEEE Intl. Conf. on Robotics and Automation (ICRA), Anchorage, AK, 2010. [8] E. Drumwright and D. Shell. Extensive analysis of linear complementarity problem (LCP) solver performance on randomly generated rigid body contact problems. In Proc. IEEE/RSJ Intl. Conf. Intelligent Robots and Sys- tems (IROS), Vilamoura, Algarve, Oct 2012. [9] P. L. Fackler and M. J. Miranda. LEMKE. http://people.sc.fsu.edu/ burkardt/m src/lemke/lemke.m. [10] C. W. Kilmister and J. E. Reeve. Rational Mechanics. Longmans, London, 1966. [11] V. Klee and G. J. Minty. How good is the simplex algorithm? In Proc. of the Third Symp. on Inequalities, pages 159–175, UCLA, 1972. JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 9 [12] C. E. Lemke. Bimatrix equilibrium points and mathemat- ical programming. Management Science, 11:681–689, 1965. [13] K. Lynch and M. J. Mason. Pushing by slipping, slip with infinite friction, and perfectly rough surfaces. Intl. J. Robot. Res., 14(2):174–183, Apr 1995. [14] B. Mirtich. Impulse-based Dynamic Simulation of Rigid Body Systems. PhD thesis, University of California, Berkeley, 1996. [15] K. G. Murty. Linear Complementarity, Linear and Nonlinear Programming. Heldermann Verlag, Berlin, 1988. [16] P. Painlev´e. Sur le lois du frottement de glissemment. C. R. Acad´emie des Sciences Paris, 121:112–115, 1895. [17] L. Sciavicco and B. Siciliano. Modeling and Control of Robot Manipulators, 2nd Ed. Springer-Verlag, London, 2000. [18] R. Shamir. The efficiency of the simplex method: A survey. Management Science, 33(3):301–334, 1987. [19] R. Smith. ODE: Open Dynamics Engine. [20] D. A. Spielman and S.-H. Teng. Smoothed analysis: why the simplex algorithm usually takes polynomial time. J. of the ACM, 51(3):385–463, 2004. [21] D. Stewart and J. C. Trinkle. An implicit time-stepping scheme for rigid body dynamics with Coulomb friction. In Proc. of the IEEE Intl. Conf. on Robotics and Automa- tion (ICRA), San Francisco, CA, April 2000. [22] D. E. Stewart. Rigid-body dynamics with friction and impact. SIAM Review, 42(1):3–39, Mar 2000. [23] D. E. Stewart and J. C. Trinkle. An implicit time-stepping scheme for rigid body dynamics with inelastic collisions and Coulomb friction. Intl. J. Numerical Methods in Engineering, 39(15):2673–2691, 1996. [24] J. Trinkle, J.-S. Pang, S. Sudarsky, and G. Lo. On dy- namic multi-rigid-body contact problems with Coulomb friction. Zeithscrift fur Angewandte Mathematik und Mechanik, 77(4):267–279, 1997. [25] J. Wang. Dynamic grasp analysis and profiling of gazebo. Master’s thesis, Rennselaer Polytechnic Inst., 2013. JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 1 Rapidly computable viscous friction and no-slip rigid contact models Evan Drumwright Abstract—This article presents computationally efficient al- gorithms for modeling two special cases of rigid contact— contact with only viscous friction and contact without slip—that have particularly useful applications in robotic locomotion and grasping. Modeling rigid contact with Coulomb friction generally exhibits O(n3) expected time complexity in the number of contact points and 2O(n) worst-case complexity. The special cases we consider exhibit O(m3+m2n) time complexity (m is the number of independent coordinates in the multi rigid body system) in the expected case and polynomial complexity in the worst case; thus, asymptotic complexity is no longer driven by number of contact points (which is conceivably limitless) but instead is more dependent on the number of bodies in the system (which is often fixed). These special cases also require considerably fewer constrained nonlinear optimization variables thus yielding substantial improvements in running time. Finally, these special cases also afford one other advantage: the nonlinear optimization problems are numerically easier to solve. I. INTRODUCTION Dynamic robotic simulation; grasp planning; and, increas- ingly, locomotion planning and control employ rigid contact models with dry (typically Coulomb) and wet (viscous) fric- tion. These contact models yield an effective tradeoff between computation speed and physical accuracy. While rigid contact models are far faster than, e.g., elastodynamic finite element analysis, they still require heavy computation: the expected time complexity for such models is O(n3) in the number of contact points. Additionally, the number of contact points input to the model is conceivably limitless. This issue is not just theoretically interesting: Wang [25] reports that solving the contact problem absorbs up to 90% of computation time when simulating a scenario for the DARPA Robotics Challenge using ODE [19]. Roboticists are often content to use rigid contact models without Coulomb friction for computational expediency. For example, one may wish to model locomotion or effect sim- ulated grasping without observing slip; roboticists studying legged locomotion often predicate their models on no slip occurring, for example. If slip is desirable, purely viscous friction might yield a suitable model if, for example, a robot is walking on a wet surface. This article presents computationally efficient methods for both of these special cases. These special cases provide the following computational and modeling advantages: () time complexity goes from worst- case exponential (the worst-case complexity of solving rigid contact problems with Coulomb friction [23, 1] using Lemke’s E. Drumwright is with the Department of Computer Science, George Washington University, Washington, DC {drum@gwu.edu} Manuscript received April 19, 2005; revised December 27, 2012. Algorithm [15]) to worst-case polynomial in the number of contact points; () significant reduction in the number of nonlinear optimization problem variables; and () a positive- semi-definite-matrix linear complementarity problem (LCP), in place of a copositive-plus LCP, which is demonstrably easier to solve [8] (i.e., the solver is less likely to fail due to numerical errors) and permits the use of general algorithms for solving convex optimization problems. Finally, we provide an algorithm that yields O(m3 + m2n) expected asymptotic time complexity on these two contact models, where m is the number of independent coordinates in the multi rigid body system. This algorithm therefore provides a means to make complexity more dependent on the number of independent coordinates in the system (this number remains constant except in the unusual case in which bodies are inserted into the simulation) than on the number of contact points (which is conceivably unlimited). II. LCPS, NCPS, AND MLCPS A LCP, or linear complementarity problem, (r, Q) signifies the problem: w = Qz + r w ≥0 z ≥0 zTw = 0 for unknown vectors z, w ∈Rq. A nonlinear complementarity problem (NCP) is composed of a number of nonlinear complementarity constraints [6] that take the form: x ≥0 (1) f(x) ≥0 (2) xTf(x) = 0 (3) where x ∈Rq and f : Rq →Rq. A mixed linear complementarity problem (MLCP) is de- fined by the following constraints: Ax + Cy + g = 0 (4) Dx + By + h ≥0 (5) y ≥0 (6) yT(Cx + Dy + h) = 0 (7) Note that the x variables are unconstrained, while the y variables must be non-negative. If A is non-singular, the arXiv:1504.00719v1 [cs.RO] 3 Apr 2015 JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 2 unconstrained variables can be computed as: x = −A−1(Cy + g) (8) Substituting x into equations 4–7 yields the LCP (e, F): F ≡B −DA−1C (9) e ≡h −DA−1g (10) A solution (y, ν) to this LCP obeys the relationship Fy+e = ν; once one has y, x may be determined via Equation 8, and the MCLP is solved. III. BACKGROUND A. Coulomb friction Coulomb’s friction model provides relationships between the force applied along the contact normal and the frictional forces. Coulomb friction considers two cases, rolling/sticking and sliding. The former occurs when the velocity is zero in the tangent plane of the contact frame; conversely, sliding occurs when that velocity is non-zero. The magnitude of the friction force for a sliding contact modeled with Coulomb friction is given by the equation: ff = µcfn (11) where fn is the magnitude of the force applied along the contact normal. The frictional force is applied directly opposite the direction of sliding (i.e., against the relative velocity in the tangent plane of the contact frame). The magnitude of the friction force for a rolling or stick- ing contact modeled with Coulomb friction is given by the equation: ff ≤µcfn (12) In the case of rolling/sticking friction, the friction force acts to resist motion in the tangent (e.g., in the case of a box resting on a slope); thus, ff may be strictly less than µcfn. If external forces become sufficiently large to overcome rolling/sticking friction forces, the rolling/sticking contact will transition to sliding. Many applications in robotics use the Coulomb friction model because it is relatively straightforward to compute— one can determine the frictional forces without integrating ordinary differential equations—and it is reasonably predic- tive. Nevertheless, Coulomb friction is somewhat expensive (computationally) to model: the rigid contact models of Stew- art and Trinkle [23] and Anitescu and Potra [1] can be solved in expected polynomial time in the n contacts1, though exponential complexity may be exhibited in the worst case. B. Acceleration-level rigid body contact model with Coulomb and viscous friction We now describe the rigid contact model with Coulomb and viscous friction that uses only non-impulsive forces for consistency with the principle of constraints [10]. The multi 1These models yield an order n copositive-plus LCP solvable by Lemke’s Algorithm [12]. Each iteration of Lemke’s Algorithm requires an O(n2) matrix factorization update, and n iterations of the algorithm are expected [6]. rigid body dynamics equation with contact and joint constraint forces is given below: M(t) ˙v =f(t) + J(t)Tfj + N(t)Tfn + . . . (13) Sk(t)Tfs + Tk(t)Tft −Q(t)Tfq −. . . (14) S(t)TµvS(t)v −T(t)TµvT(t)v (15) where M ∈Rm×m is the system inertia matrix; v ∈Rm is the system velocity; J ∈Rj×m is the matrix of j bilateral constraint equations; N ∈Rn×m, S ∈Rn×m, and T ∈Rn×m are matrices of n wrenches applied along the contact normal, first contact tangent, and second contact tangent, respectively; Q ∈Rr×m is a matrix of r generalized wrenches applied against the direction of sliding for r ≤n sliding contacts; fj ∈ Rj is the vector bilateral constraint force magnitudes; fn ∈ Rn is a vector of contact normal force magnitudes; fs ∈Rk and ft ∈Rk are vectors of contact tangent force magnitudes applied at the k = n −r rolling/sticking contacts; fq ∈Rr is a vector of contact tangent force magnitudes applied at the r sliding contacts; f is a vector of forces on the rigid body system (gravity, Coriolis and centrifugal forces, etc.); and µv is a diagonal matrix of viscous friction coefficients. Equation 14 specifies the Coulomb friction forces and Equation 15 specifies the viscous friction forces. The viscous model, where friction forces oppose the direction of motion, is commonly used in robotics (see, e.g., [17]) and is a simplifica- tion of the viscous drag term in fluid dynamics. Out of the n points of contact in the system, some may be rolling/sticking and the remainder will be sliding. For Coulomb friction, the first two terms of Equation 14 (Sk(t)Tfs + Tk(t)Tft) are relevant to the rolling/sticking contacts only (k specifies the indices of S and T that correspond to rolling/sticking contacts) and the last term (−Q(t)Tfq) is relevant to only sliding contacts. 1) Bilateral constraint equation: Bilateral constraints can be specified in the form φ(q) = 0, where q are the generalized coordinates of the system (joint constraints that are an explicit function of time are not considered here, though their inclusion would not change the results in this article). Such constraints can be differentiated once with respect to time to yield: J ˙v = 0 (16) where J ≡∂φ ∂q . If we differentiate the constraints with respect to time once more, the bilateral joint constraints can be enforced using the equation: J ˙v + ˙Jv = 0 (17) where ˙J ≡ ∂ ∂qJv. 2) Contact normal constraints: We assume that there are n points of contact. The ith contact must satisfy the following linear complementarity condition that relates normal force and non-interpenetration: 0 ≤fni ⊥ni T ˙v + ˙ni Tv ≥0 (18) where ni and ˙ni are column vectors taken from the ith rows of N and ˙N, respectively. Here we adopt the notation a ⊥b to denote the relationship a · b = 0. fni ≥0 requires that the contact force can only push bodies apart, niT ˙v + ˙ niTv ≥0 JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 3 requires that the bodies cannot be accelerating toward one another at the ith contact point after the contact forces are applied, and the fni · (niT ˙v + ˙ni Tv) = 0 constraint ensures that frictionless contact does no work. 3) Sliding friction: If the velocity in the tangent plane at the ith contact point is non-zero, then the contact is sliding, and the Coulomb friction model specifies the magnitude of force to be applied. |fqi| = µ|fni| (19) 4) Rolling/sticking friction: If the velocity at time t in the tangent plane at the ith contact point is zero, then the contact is rolling/sticking at time t and may either continue rolling/sticking or begin sliding, depending on the normal force and Coulomb friction coefficient. The nonlinear com- plementarity conditions are then expressed by the following equations (adapted from [24]): 0 ≤u2f 2 ni −f 2 si −f 2 ti ⊥ q ˙v2si + ˙v2 ti ≥0 (20) 0 = µfni ˙vsi + fsi q ˙v2si + ˙v2 ti (21) 0 = µfni ˙vti + fti q ˙v2si + ˙v2 ti (22) Let us now examine the constraints above. Equation 20 constrains the frictional force to lie within the friction cone; if the tangential acceleration is non-zero, then the frictional force must lie on the edge of the friction cone. Equations 21 and 22 ensure that the frictional force opposes the tangent accelera- tion. 5) Solvability of the model: Others (e.g., [2]) have already shown that this rigid model may not possess a solution if there are any sliding contacts; such contact scenarios are known as inconsistent configurations. Nevertheless, we present this model because the contact model with Coulomb friction, which we present next and use to motivate the move to a velocity-level contact model, will build off of it. C. Solvable rigid body contact model with Coulomb and viscous friction The contact model of Stewart and Trinkle [23] and Anitescu and Potra [1] provides a guaranteed solution to the problem of inconsistent configurations in contact models with Coulomb friction. This model is presented to show a velocity-level formulation, which allows the model to overcome the issue of inconsistent configurations. The no-slip model introduced in Section VI will also employ a velocity-level formulation to simulate contact without sliding in arbitrary configurations; Lynch and Mason showed that sliding with infinite friction is possible for the acceleration-level model described in the previous section [13]. We now describe this contact model—we consider only the aspect of the model that treats all contacts as inelastic impacts and do not consider extensions to collisional impacts with restitution. For simplicity of presentation, we do not linearize the friction cone, which yields a NCP rather than the LCP in [23, 1]. The contact model uses a first-order approximation to the rigid body dynamics to resolve issues like Painlev´e’s Paradox (and other inconsistent contact configurations [2]), for which no non-impulsive force solutions exist. The rigid body dynam- ics are given by: M(t)∆v =∆tf(t) + J(t)Tfj + . . . (23) N(t)Tfn + S(t)Tfs + T(t)Tft where M, v, J, N, S, T, fj, fn, fs, ft, and f are as defined in Section III-B and ∆t is the change in time that realizes the first-order approximation. We now define v∗≡v + ∆v. 1) Bilateral constraint equation: Because the bilateral joint constraints are now defined at the velocity level, the constraints are enforced using the equation: Jv∗= 0 (24) 2) Contact normal constraints: The velocity-level con- straints on contact normal force and non-interpenetration are now defined as: 0 ≤fni ⊥nT i v∗≥0 (25) 3) Coulomb friction constraints: Coulomb friction is ef- fected more simply in this model than in the acceleration- level model: contacts can be treated identically whether they are initially sliding or sticking. The nonlinear complementarity conditions for the ith contact are: 0 ≤u2f 2 ni −f 2 si −f 2 ti ⊥ q v∗2 si + v ∗2 ti ≥0 (26) 0 = µfniv∗ si + fsi q v∗2 si + v∗2 ti (27) 0 = µfniv∗ ti + fti q v∗2 si + v∗2 ti (28) These equations are analogous to Equations 20–22. If the nonlinear complementarity conditions are converted to linear complementarity constraints by use of a linearized friction cone (i.e., a friction polygon), then a provably solvable copositive-plus LCP [6] results. However, Lemke’s Algo- rithm [12] is currently the only algorithm provably capable of solving copositive-plus LCPs. Lemke’s Algorithm can ex- hibit exponential complexity [15], though polynomial time is expected. IV. CONTACT MODEL WITH PURELY VISCOUS FRICTION We now describe the contact model with purely viscous friction. We start from the multi rigid body dynamics equation at the acceleration level (Equations 13 and 15), which are reproduced below: M(t) ˙v =f(t) + J(t)Tfj + N(t)Tfn + . . . S(t)TµvS(t)v −T(t)TµvT(t)v To this we add bilateral constraints (Equation III-B1) and the normal contact compressive force and non-interpenetration and complementarity constraints (Equation III-B2), again re- produced below: J ˙v + ˙Jv = 0 0 ≤ni T ˙v + ˙ni Tv ⊥fni ≥0 for i = 1, . . . , n JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 4 Combining these equations yields the following MLCP:   M −JT −NT J 0 0 N 0 0     ˙v fj fn  +   f ∗ ˙Jv ˙Nv  =   0 0 γ   (29) fn ≥0 (30) γ ≥0 (31) f T n γ = 0 (32) where f ∗≡−f +STµvSv+TTµvTv and γ ≡N ˙v+ ˙Nv. As long as J has full row rank (we will describe how to ensure this condition in the next section), the mixed LCP can be converted to a conventional LCP (as described in Section II) using the following definitions: A ≡  M −JT J 0  (33) C ≡  −NT 0  (34) D ≡−CT (35) B ≡0 (36) x ≡  ˙v fj  (37) y ≡fn (38) g ≡ −f ∗ 0  (39) h ≡0 (40) Equations 9 and 10 then yield the following standard LCP: F ≡NA−1NT (41) e ≡NA−1f ∗ (42) The system inertia matrix is block diagonal (each block is invertible), so A is invertible if J has full row rank (if it is not—indicating that one or more constraints is redundant— a subset of J which has full row rank can be used to ensure that A is invertible). From [3], a matrix of F’s form must be non-negative definite, i.e., either positive semi- definite (PSD) or positive definite (PD). Additionally, Baraff provided an algorithm that provably solved LCPs of the form (Gr, GHGT), where H ∈Rm×m is a symmetric matrix, r ∈Rm, and G ∈Rn×m [2]. Finally, we note that LCPs with PSD/PD matrices are equivalent to convex quadratic programs [6], which means that solving the LCP exhibits worst-case polynomial computational complexity. V. REDUCING EXPECTED TIME COMPLEXITY FROM O(n3) TO O(m3 + m2n) A system with m degrees-of-freedom requires no more than m positive force magnitudes applied along the contact normals to satisfy the constraints for the contact models with purely viscous friction and without slip (the latter model will be presented in Section VI). We now prove this statement. Assume we permute and partition the rows of N into r linearly independent and n −r linearly dependent rows, denoted by indices I and D, respectively, as follows: N = NI ND  (43) Then the LCP vectors q = Nv, z ∈Rn, and w ∈Rn and LCP matrix Q = NA−1NT can be partitioned as follows: QII QID QDI QDD  zI zD  + qI qD  = wI wD  (44) Given some matrix α ∈R(n−r)×r, it is the case that ND = αNI, and therefore that QDI = αNIA−1NI T, QID = NIA−1NI TαT (by symmetry), QDD = αNIA−1NI TαT, and qD = αNIv. Lemma 1. Since rank(XY) ≤min (rank(X), rank(Y)), the number of positive components of zI can not be greater than rank(A). Proof. Since the columns of XY have X multiplied by each column of Y, i.e., XY = Xy1 Xy2 . . . Xyn  . Columns in Y that are linearly dependent will thus produce columns in XY that are linearly dependent (with precisely the same coefficients). Thus, rank(XY) ≤rank(Y). Applying the same argument to the transposes produces rank(XY) ≤rank(X), thereby proving the claim. We now show that—in the case that the number of positive components of zI is equal to the rank of A—no more positive force magnitudes are necessary to solve the LCP. Theorem 1. If (zI = a, wI = 0) is a solution to the LCP (qI, QII), then (  zIT = aT zDT = 0TT , w = 0) is a solution to the LCP (q, Q). Proof. For (  zIT = aT zDT = 0TT , w = 0) to be a solu- tion to the LCP (q, Q), six conditions must be satisfied: 1) zI ≥0 2) wI ≥0 3) zITwI = 0 4) zD ≥0 5) wD ≥0 6) zDTwD = 0 Of these, (), (), and () are met trivially by the assumptions of the theorem. Since zD = 0, QIIzI + QIDzD + qI = 0, and thus wI = 0, thus satisfying () and (). Also due to zD = 0, it suffices to show for () that QDIzI + qD ≥0. From above, the left hand side of this equation is equivalent to α(NIA−1NI Ta + NIv), or αwI, which itself is equivalent to α0. Thus, wD = 0. 4) Algorithm: We use the theorem above to make a mi- nor modification to the Principal Pivot Method I [5, 15] (PPM), which solves LCPs with P-matrices (complex square matrices with fully non-negative principal minors [15] that includes positive semi-definite matrices as a proper subset). The resulting algorithm limits the size of matrix solves and multiplications. The PPM uses a set β with maximum cardinality n for a LCP of order n. Of a pair of LCP variables, (zi, wi), exactly one will be in β; we say that the other belongs to β. If a JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 5 variable belongs to β, we say that the variable is a basic variable; otherwise, it is a non-basic variable. Using this set, partition the LCP matrices and vectors as shown below: wβ wβ  = Aββ Aββ Aββ Aββ  zβ zβ  + qβ qβ  Segregating the basic and non-basic variables on different sides yields: wβ zβ  = " Aββ −AββAββ −1 AββAββ −1 −Aββ −1Aββ Aββ −1 # zβ wβ  + . . . " qβ −AββAββ −1qβ −Aββ −1qβ # If we set the values of the basic variables to zero, then solving for the values of the non-basic variables zB and wB entails only block inversion of A. The unmodified PPM I operates in the following manner: ()Find an index i of a basic variable xi (where xi is either wi or zi, depending which of the two is basic) such that xi < 0; () swap the variables between basic and non-basic sets for index i (e.g., if wi is basic and zi is non-basic, make wi non- basic and zi basic); () determine new values of z and w; () repeat ()–() until no basic variable has a negative value. PPM I requires few modifications, which are provided in Algorithm 1. First, the full matrix N · M−1 · NT is never constructed (such construction would require O(n3) time). Instead, Line 1 of the algorithm constructs a maximum m×m system; thus, that operation requires only O(m3) operations. Similarly, Lines 13–14 also leverage Theorem 1 in order to compute w† and a† efficiently (though these operations do not affect the asymptotic time complexity). Assuming that the number of iterations for a pivoting algorithm is O(n) in the size of the input,2 and that each iteration requires at most two pivot operations (each rank-1 update operation to a matrix factorization will exhibit time complexity O(m2)), the asymptotic complexity of the modified PPM I algorithm is O(m3+m2n). The termination conditions for the algorithm are not affected by our modifications. VI. NO-SLIP CONTACT MODEL A contact model without slip requires a velocity-level contact model in accordance with Lynch and Mason’s finding that sliding can occur with infinite friction at the acceleration level [13]. The no-slip friction contact model uses the first- order approximation and builds on Equations 23, 24, and 25 by dictating that the tangential velocity at each contact must be zero at v(t + ∆t): Sv(t + ∆t) = 0 (45) Tv(t + ∆t) = 0 (46) 2Regardless of the pathological problem devised by Klee and Minty[11], experience with the Simplex Algorithm on thousands of practical problems shows that it requires fewer than 3n iterations and the expected time complexity for the Simplex Algorithm is polynomial [18, 20]. We are unaware of research that shows these results are also applicable to pivoting methods for LCPs, though Cottle et al. claim O(n) expected iterations [6]. Forming these five equations into a MLCP and using the variable definitions in Section II yields: A ≡   M −JT −ST −TT J 0 0 0 S 0 0 0 T 0 0 0   (47) C ≡   −NT 0 0 0   (48) D ≡−CT (49) B ≡0 (50) (51) x ≡   v(t + ∆t) fj 0 0   (52) y ≡fn (53) g ≡   −Mv(t) 0 0 0   (54) h ≡0 (55) The matrix A may be singular, which would prevent us from converting the MLCP to a standard LCP. However, if J, S, and T have full row rank or we identify the largest row blocks of those matrices such that full row rank is attained, A is invertible without affecting the solution to the MLCP. Algorithm 2 performs exactly this task. The singularity check on Lines 7, 14, and 19 of Algorithm 2 is best performed using a Cholesky factorization; if the fac- torization is successful, the matrix is non-singular. Given that M is non-singular (it is symmetric and positive definite), the maximum size of X in Algorithm 2 is m × m; if X were larger, it would be singular (see Lemma 1). Given this information, the time complexity of Algorithm 2 is dominated by Lines 7, 14, and 19. As X changes by at most one row and one column per Cholesky factorization, singularity can be checked by O(m2) updates to an initial O(m3) Cholesky factorization. The overall time complexity is O(m3 + nm2). A. Resulting systems Using Equations 9 and 10), the LCP matrix F and vector e are equivalent to: F ≡NX−1NT (56) e ≡NX−1Mv(t) (57) As in Section IV, F must be symmetric and positive-semi- definite and—as noted in Section IV—Baraff’s algorithm [2] guarantees that a solution to this LCP exists. The Sv(t + ∆t) = Tv(t + ∆t) = 0 constraints (Equa- tions 45 and 46) and solvability of the LCP contrast with the JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 6 Algorithm 1 {z, w} = LCP(N, M, f ∗) Solves a frictionless contact model using a modification of the Principal Pivoting Method I Algorithm. 1: n ←rows(N) 2: q ←N · f ∗ 3: i ←arg mini qi ▷Check for trivial solution 4: if qi ≥0 then 5: return {0, q} 6: end if 7: B ←{i} ▷Establish initial nonbasic indices 8: B ←{1, . . . , i −1, i + 1, . . . , n} ▷Establish initial basic indices 9: while true do 10: A ←NB · M−1 · NB T 11: b ←NB · f ∗ 12: z† ←A−1 · −b . ▷Solve for non-basic components of z 13: a† ←M−1 · NB Tz† + f ∗ 14: w† ←N · a† 15: i ←arg mini w† i ▷Find the index for moving into the non-basic set (if any) 16: if w† i ≥0 then 17: j ←arg mini z† i ▷No index to move into the non-basic set; look whether there is an index to 18: . move into the basic set 19: if z† j < 0 then 20: k ←B(j) 21: B ←B ∪{k} ▷Move index k into the basic set 22: B ←B −{k} 23: continue 24: else 25: z ←0 26: zB ←z† 27: w ←0 28: wB ←w† 29: return {z, w} 30: end if 31: else 32: B ←B ∪{i} ▷Move index i into the non-basic set 33: B ←B −{i} 34: j ←arg mini z† i ▷Look whether there is an index to move into the basic set 35: if z† j < 0 then 36: k ←B(j) 37: B ←B ∪{k} ▷Move index k into the basic set 38: B ←B −{k} 39: end if 40: end if 41: end while finding of Lynch and Mason [13], who showed that sliding with infinite friction is possible. The admittance of impulsive forces has resolved this “paradox” analogously to the manner in which contact models like [23, 1] resolved Painlev´e’s Para- dox [16] and other inconsistent contact configurations [22]. VII. EXPERIMENTS We tested the contact models using two common con- tact scenarios in robotics, grasping and locomotion, in or- der to assess speed and numerical stability. These experi- ments can be reproduced using the experimental setup de- scribed at https://github.com/PositronicsLab/ no-slip-and-viscous-experiments. A. Grasping experiment We used RPIsim (https://code.google.com/p/ rpi-matlab-simulator) to simulate a force-closure grasping scenario (depicted in Figure 1) on a Macbook Air with 1.8 GHz Intel Core i5 CPU. Twelve contact points were generated between each pair of boxes3, yielding 36 contact points total. For the contact model with Coulomb friction (the Stewart-Trinkle model [21]), a friction “pyramid” (four 3The equal size boxes contacting in the manner in Figure 1 yields degenerate contact normals at the box corners; the RPI simulator treats this problem by duplicating each contact with all three possible directions for the contact normal. JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 7 Algorithm 2 FIND-INDICES(M, J, S, T), determines the row indices (J , S, and T ) of J, S, and T such that the equality matrix A (Equation 4) is non-singular. 1: J ←∅ 2: S ←∅ 3: T ←∅ 4: for i = 1, . . . r do ▷r is the number of bilateral constraint equations 5: J ∗←J ∪{i} 6: Set X ←JT J ∗ 7: if XTM−1X not singular then 8: J ←J ∗ 9: end if 10: end for 11: for i = 1, . . . , n do ▷n is the number of contacts 12: S∗←S ∪{i} 13: Set X ←  JT J ST S∗ TT T  14: if XTM−1X not singular then 15: S ←S∗ 16: end if 17: T ∗←T ∪{i} 18: Set X ←  JT J ST S TT T ∗  19: if XTM−1X not singular then 20: T ←T ∗ 21: end if 22: end for 23: return {J , S, T } sided approximation to the friction cone) was used, yielding six LCP variables per contact (i.e., 216 variables total). The RPI simulator allowed us to substitute the Stewart-Trinkle model with the no-slip friction model readily, which resulted in only 36 LCP variables. The simulation was run using a step size of 0.01 for ten iterations ( 1 10 of one second of simulated time); the grasped objects would tend to fall from the gripper after ten iterations only when using Stewart- Trinkle (due to numerical issues with Lemke’s Algorithm, to be discussed below). Lemke’s Algorithm was implemented using LEMKE [9]. The P0 matrix resulting from the no-slip friction model allowed us to employ the modified PPM solver and MATLAB’s quadprog solver (with the active-set algorithm) to solve the LCP. We used Lemke’s Algorithm [12], employing Tikhonov regularization [6] as necessary, to solve the Stewart-Trinkle model. No low-rank updates were used in our implementation of Algorithm 2. Contact model Running time (mean ± σ) Stewart-Trinkle (Lemke’s Algorithm) 10.9681s ± 2.1812s µc = 100.0, µv = 0.0 No-slip (active-set QP solver) 1.9892s ± 0.2640s No-slip (modified PPM) 1.6680s ± 0.3669s TABLE I MEAN RUNNING TIMES FOR THE GRASPING EXPERIMENT. TEN TRIALS WERE RUN FOR EACH METHOD. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). This experiment yielded several findings. As expected, Fig. 1. A depiction of the grasping experiment described in Section VII-A. The two red boxes act as grippers and push inward. Gravity pushes downward. Given sufficient friction (µ = ∞), the grippers should ideally keep the blue boxes grasped using force closure. reducing the LCP variables by a factor of five (216 variables to 36 variables) results in much faster solutions (451–558% faster mean, depending on the solver). Fewer variables also results in less rounding error; the no-slip approach was able to model the grasping scenario reliably for at least 100 iterations (again, compared to around ten iterations for Stewart-Trinkle). Of the twelve contacts per pair of boxes, it was only necessary to apply forces to two contacts, which the modified PPM method was able to exploit: it ran nearly 20% faster than the quadprog algorithm (mean and maximum numbers of pivot operations were observed to be 5.5 and 7, respectively). This performance differential is considerable given that our modified PPM algorithm was not implemented as a MEX file and that our implementation does not use low-rank updates to maximize performance). B. Locomotion experiments We used the Moby simulator (https://github.com/ PositronicsLab/Moby) to simulate a quadrupedal robot walking on a terrain map (see Figure 2) over ten seconds. An event-driven method (see [4] for a description of this paradigm) is used to simulate the system instead of the time- stepping approaches used in ODE, Bullet, and RPIsim; popular implementations of this approach are susceptible to energy gain when correcting interpenetration [21], which destabilizes our robot in the process. The integration method used for the no-slip model experi- ment is symplectic Euler (St¨ormer-Verlet) with a step size of 0.001, while fourth-order Runge-Kutta integration was used for the viscous model experiment with identical step size. Our approach using the former integrator allows only the no-slip model to be activated, while our approach using the latter integrator permits the acceleration-level viscous model to be used for sustained contacts. When impacts occur (e.g., on initial foot/ground contact) in the latter approach, the simulation uses an inelastic impact model [7] with purely viscous friction. Locomotion experiments were run on an Intel Xeon 2.27GHz desktop computer. All aspects of the simulation, including forward dynamics computations, collision detection, JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 8 and controls (which performs dynamics calculations) were accounted for in results; single LCP solves generally run too quickly to obtain timings for just that operation. We point out that the simulations run considerably slower than similar systems modeled using, e.g., ODE, but the goals of the two simulators. ODE uses approximate solves and permits interpenetration. Moby aims to provide a verifiable simulator, i.e., one that adheres closely to the rigid body dynamics models (which means that interpenetration is impermissible). Results for the no-slip experiment are provided in Ta- ble VII-B, which shows a speedup of nearly 28%. The minimum and maximum number of contact points generated in the experiment is 1 and 30, respectively; the mean number of contact points is 6, and the standard deviation is 8. Thus, simulations with greater numbers of contacts could expect greater performance differentials. Results for the viscous experiment are provided in Ta- ble VII-B, which shows a speedup of over 37%. We note that the viscous friction experiments required significantly longer to run than the no-slip experiments. We hypothesize that this disparity is due to the behavior of the simulation when applying the viscous model, which tends to produce rapid movements upon contact. Those rapid movements, which appear due to some sensitivity in the underlying ordinary dif- ferential equations, slow the simulator’s continuous collision detection system (see [14] for a description of that system). Fig. 2. A depiction of the quadrupedal robot walking on a terrain map in the locomotion experiment, as described in Section VII-B. The no-slip and viscous friction models were both assessed. Contact model Running time Drumwright-Shell 416.284s µc = 100.0, µv = 0.0 No-slip (modified PPM) 301.796s TABLE II TIMES REQUIRED TO SIMULATE THE QUADRUPED LOCOMOTION SCENARIO DESCRIBED IN SECTION VII-B UNDER A NO-SLIP CONTACT MODEL. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). VIII. CONCLUSION We presented an algorithm for rapidly computing two rigid contact models without Coulomb friction that have proven useful in certain modeling and simulation applications for Contact model Running time Viscous (Lemke’s Algorithm) 2936.36s µc = 0.0, µv = 0.1 Viscous (modified PPM) 2139.73s TABLE III TIMES REQUIRED TO SIMULATE THE QUADRUPED LOCOMOTION SCENARIO DESCRIBED IN SECTION VII-B UNDER A PURELY VISCOUS FRICTION MODEL. TIMINGS INCLUDE ALL ASPECTS OF THE SIMULATION (INCLUDING COLLISION DETECTION). robotics. We showed how these models exhibit both asymp- totic computational complexity and significant running time advantages over rigid models with Coulomb friction. While we do not expect these special-case models to replace rigid models with Coulomb friction, the former serve as computationally efficient alternatives as applications allow. IX. ACKNOWLEDGEMENTS We thank Sam Zapolsky for providing the quadruped model and the locomotion controller. This work was funded by NSF CMMI-110532. REFERENCES [1] M. Anitescu and F. A. Potra. Formulating dynamic multi- rigid-body contact problems with friction as solvable linear complementarity problems. Nonlinear Dynamics, 14:231–247, 1997. [2] D. Baraff. Fast contact force computation for nonpen- etrating rigid bodies. In Proc. of SIGGRAPH, Orlando, FL, July 1994. [3] R. Bhatia. Positive definite matrices. Princeton University Press, 2007. [4] B. Brogliato, A. A. ten Dam, L. Paoli, F. G´enot, and S. Abadie. Numerical simulation of finite dimensional multibody nonsmooth mechanical systems. ASME Appl. Mech. Reviews, 55(2):107–150, March 2002. [5] R. W. Cottle. The principal pivoting method of quadratic programming. In G. Dantzig and J. A. F. Veinott, editors, Mathematics of Decision Sciences, pages 144–162. AMS, Rhode Island, 1968. [6] R. W. Cottle, J.-S. Pang, and R. Stone. The Linear Complementarity Problem. Academic Press, Boston, 1992. [7] E. Drumwright. Avoiding Zeno’s paradox in impulse- based rigid body simulation. In Proc. of IEEE Intl. Conf. on Robotics and Automation (ICRA), Anchorage, AK, 2010. [8] E. Drumwright and D. Shell. Extensive analysis of linear complementarity problem (LCP) solver performance on randomly generated rigid body contact problems. In Proc. IEEE/RSJ Intl. Conf. Intelligent Robots and Sys- tems (IROS), Vilamoura, Algarve, Oct 2012. [9] P. L. Fackler and M. J. Miranda. LEMKE. http://people.sc.fsu.edu/ burkardt/m src/lemke/lemke.m. [10] C. W. Kilmister and J. E. Reeve. Rational Mechanics. Longmans, London, 1966. [11] V. Klee and G. J. Minty. How good is the simplex algorithm? In Proc. of the Third Symp. on Inequalities, pages 159–175, UCLA, 1972. JOURNAL OF LATEX CLASS FILES, VOL. 11, NO. 4, DECEMBER 2012 9 [12] C. E. Lemke. Bimatrix equilibrium points and mathemat- ical programming. Management Science, 11:681–689, 1965. [13] K. Lynch and M. J. Mason. Pushing by slipping, slip with infinite friction, and perfectly rough surfaces. Intl. J. Robot. Res., 14(2):174–183, Apr 1995. [14] B. Mirtich. Impulse-based Dynamic Simulation of Rigid Body Systems. PhD thesis, University of California, Berkeley, 1996. [15] K. G. Murty. Linear Complementarity, Linear and Nonlinear Programming. Heldermann Verlag, Berlin, 1988. [16] P. Painlev´e. Sur le lois du frottement de glissemment. C. R. Acad´emie des Sciences Paris, 121:112–115, 1895. [17] L. Sciavicco and B. Siciliano. Modeling and Control of Robot Manipulators, 2nd Ed. Springer-Verlag, London, 2000. [18] R. Shamir. The efficiency of the simplex method: A survey. Management Science, 33(3):301–334, 1987. [19] R. Smith. ODE: Open Dynamics Engine. [20] D. A. Spielman and S.-H. Teng. Smoothed analysis: why the simplex algorithm usually takes polynomial time. J. of the ACM, 51(3):385–463, 2004. [21] D. Stewart and J. C. Trinkle. An implicit time-stepping scheme for rigid body dynamics with Coulomb friction. In Proc. of the IEEE Intl. Conf. on Robotics and Automa- tion (ICRA), San Francisco, CA, April 2000. [22] D. E. Stewart. Rigid-body dynamics with friction and impact. SIAM Review, 42(1):3–39, Mar 2000. [23] D. E. Stewart and J. C. Trinkle. An implicit time-stepping scheme for rigid body dynamics with inelastic collisions and Coulomb friction. Intl. J. Numerical Methods in Engineering, 39(15):2673–2691, 1996. [24] J. Trinkle, J.-S. Pang, S. Sudarsky, and G. Lo. On dy- namic multi-rigid-body contact problems with Coulomb friction. Zeithscrift fur Angewandte Mathematik und Mechanik, 77(4):267–279, 1997. [25] J. Wang. Dynamic grasp analysis and profiling of gazebo. Master’s thesis, Rennselaer Polytechnic Inst., 2013.