Drake
Drake C++ Documentation
StaticEquilibriumProblem Class Reference

Detailed Description

Finds the static equilibrium pose of a multibody system through optimization.

The constraints are

  1. 0 = g(q) + Bu + ∑ᵢ JᵢᵀFᵢ_AB_W(λᵢ) (generalized force equals to 0).
  2. Fᵢ_AB_W(λᵢ) is within the admissible contact wrench (for example, contact force is in the friction cone).
  3. sdf(q) >= 0 (signed distance function is no smaller than 0, hence no penetration).
  4. complementarity condition between the contact force and the signed distance.
  5. q within the joint limit.

#include <drake/multibody/optimization/static_equilibrium_problem.h>

Public Member Functions

 StaticEquilibriumProblem (const MultibodyPlant< AutoDiffXd > *plant, systems::Context< AutoDiffXd > *context, const std::set< std::pair< geometry::GeometryId, geometry::GeometryId >> &ignored_collision_pairs)
 
 ~StaticEquilibriumProblem ()
 
solvers::MathematicalProgramget_mutable_prog () const
 
const solvers::MathematicalProgramprog () const
 Getter for the immutable optimization program. More...
 
const VectorX< symbolic::Variable > & q_vars () const
 Getter for q, the decision variable for the generalized position. More...
 
const VectorX< symbolic::Variable > & u_vars () const
 Getter for u, the decision variable for the input. More...
 
std::vector< ContactWrenchGetContactWrenchSolution (const solvers::MathematicalProgramResult &result)
 Retrieve the solution to all contact wrenches. More...
 
void UpdateComplementarityTolerance (double tol)
 Updates the tolerance on all the complementarity constraints α * β = 0. More...
 
Does not allow copy, move, or assignment
 StaticEquilibriumProblem (const StaticEquilibriumProblem &)=delete
 
StaticEquilibriumProblemoperator= (const StaticEquilibriumProblem &)=delete
 
 StaticEquilibriumProblem (StaticEquilibriumProblem &&)=delete
 
StaticEquilibriumProblemoperator= (StaticEquilibriumProblem &&)=delete
 

Constructor & Destructor Documentation

◆ StaticEquilibriumProblem() [1/3]

◆ StaticEquilibriumProblem() [2/3]

◆ StaticEquilibriumProblem() [3/3]

StaticEquilibriumProblem ( const MultibodyPlant< AutoDiffXd > *  plant,
systems::Context< AutoDiffXd > *  context,
const std::set< std::pair< geometry::GeometryId, geometry::GeometryId >> &  ignored_collision_pairs 
)
Parameters
plantThe plant for which the static equilibrium posture is computed. plant should remain alive as long as this StaticEquilibriumProblem exists.
contextThe context for plant. context should remain alive as long as this StaticEquilibriumProblem exists.
ignored_collision_pairsThe contact between the pair of geometry in ignored_collision_pairs will be ignored. We will not impose non-penetration constraint between these pairs, and no contact wrench will be applied between these pairs.

◆ ~StaticEquilibriumProblem()

Member Function Documentation

◆ get_mutable_prog()

solvers::MathematicalProgram* get_mutable_prog ( ) const

◆ GetContactWrenchSolution()

std::vector<ContactWrench> GetContactWrenchSolution ( const solvers::MathematicalProgramResult result)

Retrieve the solution to all contact wrenches.

Parameters
resultThe result of solving prog().

◆ operator=() [1/2]

◆ operator=() [2/2]

StaticEquilibriumProblem& operator= ( const StaticEquilibriumProblem )
delete

◆ prog()

const solvers::MathematicalProgram& prog ( ) const

Getter for the immutable optimization program.

◆ q_vars()

const VectorX<symbolic::Variable>& q_vars ( ) const

Getter for q, the decision variable for the generalized position.

◆ u_vars()

const VectorX<symbolic::Variable>& u_vars ( ) const

Getter for u, the decision variable for the input.

◆ UpdateComplementarityTolerance()

void UpdateComplementarityTolerance ( double  tol)

Updates the tolerance on all the complementarity constraints α * β = 0.

The complementarity constraint is relaxed as 0 ≤ α * β ≤ tol. See AddStaticFrictionConeComplementarityConstraint() for more details.


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