Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
CentroidalMomentumConstraint Class Referencefinal

Detailed Description

Impose the constraint CentroidalMomentum(q, v) - h_WC = 0 with decision variables [q;v;h_WC] or CentroidalAngularMomentum(q, v) - k_WC = 0 with decision variables [q; v; k_WC] h_WC is the 6D spatial momentum (linear and angular momentum about the center of mass C) expressed in the world frame (W).

k_WC is the 3D vector representing the angular momentum about the center of mass C expressed in the world frame W.

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

Public Member Functions

 CentroidalMomentumConstraint (const MultibodyPlant< AutoDiffXd > *plant, std::optional< std::vector< ModelInstanceIndex > > model_instances, systems::Context< AutoDiffXd > *plant_context, bool angular_only)
 Construct centroidal momentum constraint If angular_only = false, we impose the constraint CentroidalMomentum(q, v) - h_WC = 0 where CentroidalMomentum computes the spatial momentum of the robot about its center-of-mass, expressed in the world frame.
 ~CentroidalMomentumConstraint () override
template<typename T>
void ComposeVariable (const Eigen::Ref< const VectorX< T > > &q, const Eigen::Ref< const VectorX< T > > &v, const Eigen::Ref< const VectorX< T > > &momentum, VectorX< T > *vars) const
Does not allow copy, move, or assignment
 CentroidalMomentumConstraint (const CentroidalMomentumConstraint &)=delete
CentroidalMomentumConstraintoperator= (const CentroidalMomentumConstraint &)=delete
 CentroidalMomentumConstraint (CentroidalMomentumConstraint &&)=delete
CentroidalMomentumConstraintoperator= (CentroidalMomentumConstraint &&)=delete
Public Member Functions inherited from Constraint
template<typename DerivedLB, typename DerivedUB>
 Constraint (int num_constraints, int num_vars, const Eigen::MatrixBase< DerivedLB > &lb, const Eigen::MatrixBase< DerivedUB > &ub, const std::string &description="")
 Constructs a constraint which has num_constraints rows, with an input num_vars x 1 vector.
 Constraint (int num_constraints, int num_vars)
 Constructs a constraint which has num_constraints rows, with an input num_vars x 1 vector, with no bounds.
bool CheckSatisfied (const Eigen::Ref< const Eigen::VectorXd > &x, double tol=1E-6) const
 Return whether this constraint is satisfied by the given value, x.
bool CheckSatisfied (const Eigen::Ref< const AutoDiffVecXd > &x, double tol=1E-6) const
symbolic::Formula CheckSatisfied (const Eigen::Ref< const VectorX< symbolic::Variable > > &x) const
const Eigen::VectorXd & lower_bound () const
const Eigen::VectorXd & upper_bound () const
int num_constraints () const
 Number of rows in the output constraint.
 Constraint (const Constraint &)=delete
Constraintoperator= (const Constraint &)=delete
 Constraint (Constraint &&)=delete
Constraintoperator= (Constraint &&)=delete
Public Member Functions inherited from EvaluatorBase
virtual ~EvaluatorBase ()
void Eval (const Eigen::Ref< const Eigen::VectorXd > &x, Eigen::VectorXd *y) const
 Evaluates the expression.
void Eval (const Eigen::Ref< const AutoDiffVecXd > &x, AutoDiffVecXd *y) const
 Evaluates the expression.
void Eval (const Eigen::Ref< const VectorX< symbolic::Variable > > &x, VectorX< symbolic::Expression > *y) const
 Evaluates the expression.
void set_description (const std::string &description)
 Set a human-friendly description for the evaluator.
const std::string & get_description () const
 Getter for a human-friendly description for the evaluator.
std::ostream & Display (std::ostream &os, const VectorX< symbolic::Variable > &vars) const
 Formats this evaluator into the given stream using vars for the bound decision variable names.
std::ostream & Display (std::ostream &os) const
 Formats this evaluator into the given stream, without displaying the decision variables it is bound to.
std::string ToLatex (const VectorX< symbolic::Variable > &vars, int precision=3) const
 Returns a LaTeX string describing this evaluator.
int num_vars () const
 Getter for the number of variables, namely the number of rows in x, as used in Eval(x, y).
int num_outputs () const
 Getter for the number of outputs, namely the number of rows in y, as used in Eval(x, y).
void SetGradientSparsityPattern (const std::vector< std::pair< int, int > > &gradient_sparsity_pattern)
 Set the sparsity pattern of the gradient matrix ∂y/∂x (the gradient of y value in Eval, w.r.t x in Eval) .
const std::optional< std::vector< std::pair< int, int > > > & gradient_sparsity_pattern () const
 Returns the vector of (row_index, col_index) that contains all the entries in the gradient of Eval function (∂y/∂x) whose value could be non-zero, namely if ∂yᵢ/∂xⱼ could be non-zero, then the pair (i, j) is in gradient_sparsity_pattern.
bool is_thread_safe () const
 Returns whether it is safe to call Eval in parallel.
 EvaluatorBase (const EvaluatorBase &)=delete
EvaluatorBaseoperator= (const EvaluatorBase &)=delete
 EvaluatorBase (EvaluatorBase &&)=delete
EvaluatorBaseoperator= (EvaluatorBase &&)=delete

Additional Inherited Members

Protected Member Functions inherited from Constraint
void UpdateLowerBound (const Eigen::Ref< const Eigen::VectorXd > &new_lb)
 Updates the lower bound.
void UpdateUpperBound (const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the upper bound.
void set_bounds (const Eigen::Ref< const Eigen::VectorXd > &new_lb, const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Set the upper and lower bounds of the constraint.
virtual bool DoCheckSatisfied (const Eigen::Ref< const Eigen::VectorXd > &x, const double tol) const
virtual bool DoCheckSatisfied (const Eigen::Ref< const AutoDiffVecXd > &x, const double tol) const
virtual symbolic::Formula DoCheckSatisfied (const Eigen::Ref< const VectorX< symbolic::Variable > > &x) const
Protected Member Functions inherited from EvaluatorBase
 EvaluatorBase (int num_outputs, int num_vars, const std::string &description="")
 Constructs a evaluator.
virtual std::ostream & DoDisplay (std::ostream &os, const VectorX< symbolic::Variable > &vars) const
 NVI implementation of Display.
virtual std::string DoToLatex (const VectorX< symbolic::Variable > &vars, int precision) const
void set_num_outputs (int num_outputs)
void set_is_thread_safe (bool is_thread_safe)

Constructor & Destructor Documentation

◆ CentroidalMomentumConstraint() [1/3]

◆ CentroidalMomentumConstraint() [2/3]

◆ CentroidalMomentumConstraint() [3/3]

CentroidalMomentumConstraint ( const MultibodyPlant< AutoDiffXd > * plant,
std::optional< std::vector< ModelInstanceIndex > > model_instances,
systems::Context< AutoDiffXd > * plant_context,
bool angular_only )

Construct centroidal momentum constraint If angular_only = false, we impose the constraint CentroidalMomentum(q, v) - h_WC = 0 where CentroidalMomentum computes the spatial momentum of the robot about its center-of-mass, expressed in the world frame.

The decision variables are [q;v;h_WC]. If angular_only = true, we impose the constraint CentroidalAngularMomentum(q, v) - k_WC = 0 where CentroidalAngularMomentum(q, v) computes the angular momentum of the robot about its center-of-mass, expressed in the world frame. The decision variables are [q; v; k_WC]

Note
Currently, we can only construct this constraint using MultibodyPlant<AutoDiffXd> instead of MultibodyPlant<double>, since we can't compute the Jacobian of the momentum using MultibodyPlant<double> yet.
Parameters
plantThe plant for which the constraint is imposed.
model_instancesWe compute the model with these model instances in plant. If model_instances=std::nullopt, then we compute the momentum of all model instances except the world.

◆ ~CentroidalMomentumConstraint()

Member Function Documentation

◆ ComposeVariable()

template<typename T>
void ComposeVariable ( const Eigen::Ref< const VectorX< T > > & q,
const Eigen::Ref< const VectorX< T > > & v,
const Eigen::Ref< const VectorX< T > > & momentum,
VectorX< T > * vars ) const

◆ operator=() [1/2]

◆ operator=() [2/2]


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