Finds the static equilibrium pose of a multibody system through optimization.
The constraints are
#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::MathematicalProgram * | get_mutable_prog () const |
const solvers::MathematicalProgram & | prog () 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< ContactWrench > | GetContactWrenchSolution (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 | |
StaticEquilibriumProblem & | operator= (const StaticEquilibriumProblem &)=delete |
StaticEquilibriumProblem (StaticEquilibriumProblem &&)=delete | |
StaticEquilibriumProblem & | operator= (StaticEquilibriumProblem &&)=delete |
|
delete |
|
delete |
StaticEquilibriumProblem | ( | const MultibodyPlant< AutoDiffXd > * | plant, |
systems::Context< AutoDiffXd > * | context, | ||
const std::set< std::pair< geometry::GeometryId, geometry::GeometryId >> & | ignored_collision_pairs | ||
) |
plant | The plant for which the static equilibrium posture is computed. plant should remain alive as long as this StaticEquilibriumProblem exists. |
context | The context for plant . context should remain alive as long as this StaticEquilibriumProblem exists. |
ignored_collision_pairs | The 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. |
solvers::MathematicalProgram* get_mutable_prog | ( | ) | const |
std::vector<ContactWrench> GetContactWrenchSolution | ( | const solvers::MathematicalProgramResult & | result | ) |
Retrieve the solution to all contact wrenches.
result | The result of solving prog(). |
|
delete |
|
delete |
const solvers::MathematicalProgram& prog | ( | ) | const |
Getter for the immutable optimization program.
const VectorX<symbolic::Variable>& q_vars | ( | ) | const |
Getter for q, the decision variable for the generalized position.
const VectorX<symbolic::Variable>& u_vars | ( | ) | const |
Getter for u, the decision variable for the input.
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.