Drake
ConstraintVelProblemData< T > Struct Template Reference

Structure for holding constraint data for computing constraint forces at the velocity-level (i.e., impact problems). More...

#include <multibody/constraint/constraint_problem_data.h>

Collaboration diagram for ConstraintVelProblemData< T >:
[legend]

Public Member Functions

 ConstraintVelProblemData (int gv_dim)
 Constructs velocity problem data for a system with a gv_dim dimensional generalized velocity. More...
 

Public Attributes

std::vector< intr
 The number of spanning vectors in the contact tangents (used to linearize the friction cone) at the n contact points. More...
 
VectorX< Tmu
 Coefficients of friction for the n contacts. More...
 
VectorX< TMv
 The ℝᵐ generalized momentum immediately before any impulsive forces (from impact) are applied. More...
 
std::function< MatrixX< T >const MatrixX< T > &)> solve_inertia
 A function for solving the equation MX = B for matrix X, given input matrix B, where M is the generalized inertia matrix for the rigid body system. More...
 
Data for bilateral constraints at the velocity level

Problem data for bilateral constraints of functions of system velocity, where the constraint can be formulated as:

0 = G(q)⋅v + kᴳ(t,q)

which implies the constraint definition c(t,q,v) ≡ G(q)⋅v + kᴳ(t,q). G is defined as the ℝᵇˣᵐ Jacobian matrix that transforms generalized velocities (v ∈ ℝᵐ) into the time derivatives of b bilateral constraint functions. The class of constraint functions naturally includes holonomic constraints, which are constraints posable as g(t,q). Such holonomic constraints must be differentiated with respect to time to yield a velocity-level formulation (i.e., ġ(t, q, v), for the aforementioned definition of g(t,q)). That differentiation yields ġ = G⋅v, which is consistent with the constraint class under the definition kᴳ(t,q) ≡ 0. An example such holonomic constraint function is the transmission (gearing) constraint below:

0 = vᵢ - rvⱼ

which can be read as the velocity at joint i (vᵢ) must equal to r times the velocity at joint j (vⱼ); r is thus the gear ratio. In this example, the corresponding holonomic constraint function is g(q) ≡ qᵢ - rqⱼ, yielding ġ(q, v) = vᵢ - rvⱼ.

std::function< VectorX< T >const VectorX< T > &)> G_mult
 An operator that performs the multiplication G⋅v. More...
 
std::function< VectorX< T >const VectorX< T > &)> G_transpose_mult
 An operator that performs the multiplication Gᵀ⋅f where f ∈ ℝᵇ are the magnitudes of the constraint forces. More...
 
VectorX< TkG
 This ℝᵇ vector is the vector kᴳ(t,q) defined above. More...
 
Data for constraints on velocities along the contact normal

Problem data for constraining the velocity of two bodies projected along the contact surface normal, for n point contacts.

These data center around the Jacobian matrix N, the ℝⁿˣᵐ Jacobian matrix that transforms generalized velocities (v ∈ ℝᵐ) into velocities projected along the contact normals at the n point contacts. Constraint error (φ < 0, where φ is the signed distance between two bodies) can be incorporated into the constraint solution process (and thereby reduced) through setting the kN term to something other than its nonzero value (typically kN = αφ, where α ≥ 0). The resulting constraint on the motion will be:

0 ≤ N(q) v + kᴺ(t,q)  ⊥  fᶜ ≥ 0

which means that the constraint ċ(q,v) ≡ N(q)⋅v + kᴺ(t,q) is coupled to an impulsive force constraint (fᶜ ≥ 0) and a complementarity constraint fᶜ⋅(Nv + kᴺ(t,q)) = 0, meaning that the constraint can apply no force if it is inactive (i.e., if ċ(q,v) is strictly greater than zero).

std::function< VectorX< T >const VectorX< T > &)> N_mult
 An operator that performs the multiplication N⋅v. More...
 
std::function< VectorX< T >const VectorX< T > &)> N_transpose_mult
 An operator that performs the multiplication Nᵀ⋅f, where f ∈ ℝⁿ are the the magnitudes of the impulsive forces applied along the contact normals at the n point contacts. More...
 
VectorX< TkN
 This ℝⁿ vector is the vector kᴺ(t,q,v) defined above. More...
 
VectorX< TgammaN
 This ℝⁿ vector represents the diagonal matrix γᴺ. More...
 
Data for constraints on contact friction

Problem data for constraining the tangential velocity of two bodies projected along the contact surface tangents, for n point contacts.

These data center around the Jacobian matrix, F ∈ ℝⁿʳˣᵐ, that transforms generalized velocities (v ∈ ℝᵐ) into velocities projected along the r vectors that span the contact tangents at the n point contacts. For contact problems in two dimensions, r would be one. For a friction pyramid in three dimensions, r would be two. While the definition of the dimension of the Jacobian matrix above indicates that every one of the n contacts uses the same "r", the code imposes no such requirement. Constraint error (F⋅v < 0) can be reduced through the constraint solution process by setting the kF term to something other than its default zero value. The resulting constraint on the motion will be:

0 ≤ F(q)⋅v + kᴺ(t,q) + eλ  ⊥  fᶜ ≥ 0

which means that the constraint ċ(q,v) ≡ F(q)⋅v + kᶠ(t,q) + eλ is coupled to an impulsive force constraint (fᶜ ≥ 0) and a complementarity constraint fᶜ⋅(Fv + kᶠ(t,q) + eλ) = 0, meaning that the constraint can apply no force if it is inactive (i.e., if ċ(q,v) is strictly greater than zero). The presence of the λe term is taken directly from [Anitescu 1997], where e is a vector of ones and zeros and λ corresponds roughly to the tangential acceleration at the contacts. The interested reader should refer to [Anitescu 1997] for a more thorough explanation of this constraint; the full constraint equation is presented only to elucidate the purpose of the kᶠ term.

std::function< VectorX< T >const VectorX< T > &)> F_mult
 An operator that performs the multiplication F⋅v. More...
 
std::function< VectorX< T >const VectorX< T > &)> F_transpose_mult
 An operator that performs the multiplication Fᵀ⋅f, where f ∈ ℝⁿʳ corresponds to frictional impulsive force magnitudes. More...
 
VectorX< TkF
 This ℝʸʳ vector is the vector kᶠ(t,q,v) defined above. More...
 
VectorX< TgammaF
 This ℝʸʳ vector represents the diagonal matrix γᶠ. More...
 
VectorX< TgammaE
 This ℝʸ vector represents the diagonal matrix γᴱ. More...
 
Data for unilateral constraints at the velocity level

Problem data for unilateral constraints of functions of system velocity, where the constraint can be formulated as:

0 ≤ L(q)⋅v + kᴸ(t,q)  ⊥  fᶜ ≥ 0

which means that the constraint ċ(q,v) ≡ L(q)⋅v + kᴸ(t,q) is coupled to an impulsive force constraint (fᶜ ≥ 0) and a complementarity constraint fᶜ⋅(L⋅v + kᴸ(t,q)) = 0, meaning that the constraint can apply no force if it is inactive (i.e., if ċ(q,v) is strictly greater than zero). L is defined as the ℝˢˣᵐ Jacobian matrix that transforms generalized velocities (v ∈ ℝᵐ) into the time derivatives of s unilateral constraint functions. The class of constraint functions naturally includes holonomic constraints, which are constraints posable as g(q, t). Such holonomic constraints must be differentiated with respect to time to yield a velocity-level formulation (i.e., ġ(q, v, t), for the aforementioned definition of g(q, t)). That differentiation yields ġ = L⋅v, which is consistent with the constraint class under the definition kᴸ(t,q) ≡ 0. An example such holonomic constraint function is a joint velocity limit:

0 ≤ -vⱼ + r  ⊥  fᶜⱼ ≥ 0

which can be read as the velocity at joint j (vⱼ) must be no larger than r, the impulsive force must be applied to limit the acceleration at the joint, and the limiting force cannot be applied if the velocity at the joint is not at the limit (i.e., vⱼ < r). In this example, the constraint function is g(t,q) ≡ qⱼ + rt, yielding ġ(q, v) = -vⱼ + r.

std::function< VectorX< T >const VectorX< T > &)> L_mult
 An operator that performs the multiplication L⋅v. More...
 
std::function< VectorX< T >const VectorX< T > &)> L_transpose_mult
 An operator that performs the multiplication Lᵀ⋅f where f ∈ ℝᵗ are the magnitudes of the impulsive constraint forces. More...
 
VectorX< TkL
 This ℝˢ vector is the vector kᴸ(t,q) defined above. More...
 
VectorX< TgammaL
 This ℝˢ vector represents the diagonal matrix γᴸ. More...
 

Detailed Description

template<class T>
struct drake::multibody::constraint::ConstraintVelProblemData< T >

Structure for holding constraint data for computing constraint forces at the velocity-level (i.e., impact problems).

Constructor & Destructor Documentation

ConstraintVelProblemData ( int  gv_dim)
inlineexplicit

Constructs velocity problem data for a system with a gv_dim dimensional generalized velocity.

Member Data Documentation

std::function<VectorX<T>const VectorX<T>&)> F_mult

An operator that performs the multiplication F⋅v.

The default operator returns an empty vector.

std::function<VectorX<T>const VectorX<T>&)> F_transpose_mult

An operator that performs the multiplication Fᵀ⋅f, where f ∈ ℝⁿʳ corresponds to frictional impulsive force magnitudes.

The default operator returns a zero vector of dimension equal to that of the generalized forces.

std::function<VectorX<T>const VectorX<T>&)> G_mult

An operator that performs the multiplication G⋅v.

The default operator returns an empty vector.

std::function<VectorX<T>const VectorX<T>&)> G_transpose_mult

An operator that performs the multiplication Gᵀ⋅f where f ∈ ℝᵇ are the magnitudes of the constraint forces.

The default operator returns a zero vector of dimension equal to that of the generalized forces.

VectorX<T> gammaE

This ℝʸ vector represents the diagonal matrix γᴱ.

VectorX<T> gammaF

This ℝʸʳ vector represents the diagonal matrix γᶠ.

VectorX<T> gammaL

This ℝˢ vector represents the diagonal matrix γᴸ.

VectorX<T> gammaN

This ℝⁿ vector represents the diagonal matrix γᴺ.

VectorX<T> kF

This ℝʸʳ vector is the vector kᶠ(t,q,v) defined above.

VectorX<T> kG

This ℝᵇ vector is the vector kᴳ(t,q) defined above.

VectorX<T> kL

This ℝˢ vector is the vector kᴸ(t,q) defined above.

VectorX<T> kN

This ℝⁿ vector is the vector kᴺ(t,q,v) defined above.

std::function<VectorX<T>const VectorX<T>&)> L_mult

An operator that performs the multiplication L⋅v.

The default operator returns an empty vector.

std::function<VectorX<T>const VectorX<T>&)> L_transpose_mult

An operator that performs the multiplication Lᵀ⋅f where f ∈ ℝᵗ are the magnitudes of the impulsive constraint forces.

The default operator returns a zero vector of dimension equal to that of the generalized forces.

VectorX<T> mu

Coefficients of friction for the n contacts.

This problem specification does not distinguish between static and dynamic friction coefficients.

VectorX<T> Mv

The ℝᵐ generalized momentum immediately before any impulsive forces (from impact) are applied.

std::function<VectorX<T>const VectorX<T>&)> N_mult

An operator that performs the multiplication N⋅v.

The default operator returns an empty vector.

std::function<VectorX<T>const VectorX<T>&)> N_transpose_mult

An operator that performs the multiplication Nᵀ⋅f, where f ∈ ℝⁿ are the the magnitudes of the impulsive forces applied along the contact normals at the n point contacts.

The default operator returns a zero vector of dimension equal to that of the generalized velocities (which should be identical to the dimension of the generalized forces).

The number of spanning vectors in the contact tangents (used to linearize the friction cone) at the n contact points.

For contact problems in two dimensions, each element of r will be one. For contact problems in three dimensions, a friction pyramid (for example), for a contact point i will have rᵢ = 2. [Anitescu 1997] define k such vectors and require that, for each vector w in the spanning set, -w also exists in the spanning set. The RigidContactVelProblemData structure expects that the contact solving mechanism negates the spanning vectors so r = k/2 spanning vectors will correspond to a k-edge polygon friction cone approximation.

std::function<MatrixX<T>const MatrixX<T>&)> solve_inertia

A function for solving the equation MX = B for matrix X, given input matrix B, where M is the generalized inertia matrix for the rigid body system.


The documentation for this struct was generated from the following file: