Wrench friction cones

Wrench friction cones are 6D convex cones that characterize feasible contact wrenches, that is to say, wrenches a robot can apply while performing contact-stable motions. They generalize Coulomb friction cones to rigid bodies, and can also be used to encode other limitations such as joint torque limits.

Net Contact Wrench Cone

The net contact wrench cone (CWC) is the friction cone of the net contact wrench acting on a robot making multiple contacts, i.e. the sum of all contact wrenches. It can be represented as a set of feasible wrenches:

\begin{equation*} \calK_O = \left\{ \sum_{\mathrm{contact}\ i} (\bff_i, \bfp_{C_i} \times \bff_i), \bff_i \in \calC_i \right\} \end{equation*}

Since wrenches are screws, their coordinates are taken at a point with respect to a given frame. The same holds for the cone \(\calK_O\), here taken at the origin \(O\) of and with respect to the inertial frame. Forces \(\bff_i\) at each contact point \(i\) are constrained to lie in the point's Coulomb friction cone \(\calC_i\).

Illustration of the Contact Wrench Cone in multi-contact

To the right is an artist view of the wrench cone for a humanoid making three point contacts. The 6D cone is represented by a red 3D force cone and a green 3D moment cone, yet keep in mind that it is only a drawing convenience. Force and moment are not independent, i.e. the 6D cone is not the direct product of these two 3D cones. If we fix the resultant force in the red cone, it will affect the shape of the green one, and conversely, if we fix the resultant moment (e.g. to zero, the linear inverted pendulum model discussed below), the red cone will change accordingly.

Wrench friction cone for surface contacts

In practice, the contacts that this humanoid is making are stronger (the net wrench cone they yield is bigger) than point contacts: they are surface contacts. The wrench cone of a surface contact can be represented by summing up Coulomb friction cones over all contact points on its contour (a proof of this property is e.g. recalled in Section III of this writeup). But in the case of a rectangular contact area, such as the foot or palm pad of 2010's humanoid robots, the formula for these wrench cones is \(\calK_i = \{ \bfw_i \ |\ \bfU \bfw_i \leq \bfzero \}\) where:

\begin{equation*} \bfU = \begin{bmatrix} -1 & 0 & -\mu & 0 & 0 & 0 \\ +1 & 0 & -\mu & 0 & 0 & 0 \\ 0 & -1 & -\mu & 0 & 0 & 0 \\ 0 & +1 & -\mu & 0 & 0 & 0 \\ 0 & 0 & -Y & -1 & 0 & 0 \\ 0 & 0 & -Y & +1 & 0 & 0 \\ 0 & 0 & -X & 0 & -1 & 0 \\ 0 & 0 & -X & 0 & +1 & 0 \\ -Y & -X & -(X + Y) \mu & +\mu & +\mu & -1 \\ -Y & +X & -(X + Y) \mu & +\mu & -\mu & -1 \\ +Y & -X & -(X + Y) \mu & -\mu & +\mu & -1 \\ +Y & +X & -(X + Y) \mu & -\mu & -\mu & -1 \\ +Y & +X & -(X + Y) \mu & +\mu & +\mu & +1 \\ +Y & -X & -(X + Y) \mu & +\mu & -\mu & +1 \\ -Y & +X & -(X + Y) \mu & -\mu & +\mu & +1 \\ -Y & -X & -(X + Y) \mu & -\mu & -\mu & +1 \end{bmatrix} \end{equation*}

Here \(\bfw_i = (\bff_i, \bftau_i)\) is the contact wrench, expressed at the central frame of the rectangular contact area \(i\). Note how the matrix \(\bfU\) does not depend on the contact index \(i\), but only on the rectangle dimensions \((X \times Y)\) and friction coefficient \(\mu\).

Computing the net contact wrench cone

Summing up over surface contacts, we can express the net contact wrench cone similarly as with point contacts:

\begin{equation*} \calK_O = \left\{ \sum_{\mathrm{contact }i} (\bff_i, \bftau_i + \bfp_{C_i} \times \bff_i), \bff_i \in \calK_i \right\} \end{equation*}

Unlike with rectangular contact areas \(\calK_i\), we seldom have an analytical formula for \(\calK\) because contact positions and orientations can be arbitrary over uneven terrains. A common solution is then to linearize friction cones and apply a numerical polyhedral projection algorithms. The outcome of this calculation is a linear inequality matrix \(\bfF\) such that:

\begin{equation*} \calK_O = \{ \bfw \in \mathbb{R}^6 \ | \ \bfF \bfw \leq \bfzero \} \end{equation*}

This matrix \(\bfF\) depends on contact positions and orientations, so it needs to be recomputed if the terrain moves. It doesn't depend on the configuration of the robot though, so it can be used as long as the robot maintains the same set of contacts. If we only want to check if, at a given time, the robot can apply a given motion (centroidal momentum, i.e. center of mass acceleration and angular momentum), it is computationally more efficient to solve a quadratic program of surface contact wrenches directly. But if we are optimizing a whole trajectory rather than a single time, computing the net wrench cone matrix \(\bfF\) and using it over the whole optimization can become more efficient.

Contact-stability areas and volumes

When additional constraints are imposed on the centroidal motion, the 6D net contact wrench cone reduces to lower-dimensional areas and volumes that can be used for planning or control:

  • When the robot is not moving, contact stability is characterized by the static equilibrium polygon: the configuration of the robot is feasible (sustainable) if and only if the center of mass lies in a specific polygon, which can be computed efficiently.
  • When the robot moves in the linear inverted pendulum mode (with conserved angular momentum and keeping the center of mass in a plane), the CWC reduces to a ZMP support area.
  • When the robot moves with a conserved angular momentum \((\Ld_G = 0)\), the CWC reduces to a 3D cone over center-of-mass accelerations that can be used e.g. for multi-contact locomotion.

To go further

Stability conditions are used extensively in motion generation, for instance in multi-contact walking pattern generation. Details on the computation of the CWC by polyhedral projection can be found in this paper. Sample implementations of the algorithms can be found e.g. in the Contact and ContactSet types of pymanoid (Python) or in wrench-cone-lib (C++).

Wrench friction cones can represent all sorts of power limitations, including but not restricted to friction. One example is given by the torque-limited wrench cones used in this predictive controller for impact absorption, which can be projected into actuation-aware center-of-mass support areas.

© Stéphane Caron — Pages of this website are under the Creative Commons CC BY 4.0 license.