Drake
Drake C++ Documentation
SpatialVelocityConstraint Class Referencefinal

Detailed Description

Constrains the spatial velocity of a frame C, rigidly attached to a frame B, measured and expressed in frame A.

It should be bound with decision variables corresponding to the multibody state x=[q,v] of the plant passed to the constructor.

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

Classes

struct  AngularVelocityBounds
 Parametrizes bounds on the magnitude and direction of the angular velocity vector. More...
 

Public Member Functions

 SpatialVelocityConstraint (const MultibodyPlant< AutoDiffXd > *plant, const Frame< AutoDiffXd > &frameA, const Eigen::Ref< const Eigen::Vector3d > &v_AC_lower, const Eigen::Ref< const Eigen::Vector3d > &v_AC_upper, const Frame< AutoDiffXd > &frameB, const Eigen::Ref< const Eigen::Vector3d > &p_BCo, systems::Context< AutoDiffXd > *plant_context, const std::optional< AngularVelocityBounds > &w_AC_bounds=std::nullopt)
 Constructs SpatialVelocityConstraint object. More...
 
 ~SpatialVelocityConstraint () final
 
Does not allow copy, move, or assignment
 SpatialVelocityConstraint (const SpatialVelocityConstraint &)=delete
 
SpatialVelocityConstraintoperator= (const SpatialVelocityConstraint &)=delete
 
 SpatialVelocityConstraint (SpatialVelocityConstraint &&)=delete
 
SpatialVelocityConstraintoperator= (SpatialVelocityConstraint &&)=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. More...
 
 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. More...
 
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. More...
 
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. More...
 
 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. More...
 
void Eval (const Eigen::Ref< const AutoDiffVecXd > &x, AutoDiffVecXd *y) const
 Evaluates the expression. More...
 
void Eval (const Eigen::Ref< const VectorX< symbolic::Variable >> &x, VectorX< symbolic::Expression > *y) const
 Evaluates the expression. More...
 
void set_description (const std::string &description)
 Set a human-friendly description for the evaluator. More...
 
const std::string & get_description () const
 Getter for a human-friendly description for the evaluator. More...
 
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. More...
 
std::ostream & Display (std::ostream &os) const
 Formats this evaluator into the given stream, without displaying the decision variables it is bound to. More...
 
std::string ToLatex (const VectorX< symbolic::Variable > &vars, int precision=3) const
 Returns a LaTeX string describing this evaluator. More...
 
int num_vars () const
 Getter for the number of variables, namely the number of rows in x, as used in Eval(x, y). More...
 
int num_outputs () const
 Getter for the number of outputs, namely the number of rows in y, as used in Eval(x, y). More...
 
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) . More...
 
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. More...
 
bool is_thread_safe () const
 Returns whether it is safe to call Eval in parallel. More...
 
 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. More...
 
void UpdateUpperBound (const Eigen::Ref< const Eigen::VectorXd > &new_ub)
 Updates the upper bound. More...
 
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. More...
 
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. More...
 
virtual std::ostream & DoDisplay (std::ostream &os, const VectorX< symbolic::Variable > &vars) const
 NVI implementation of Display. More...
 
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

◆ SpatialVelocityConstraint() [1/3]

◆ SpatialVelocityConstraint() [2/3]

◆ SpatialVelocityConstraint() [3/3]

SpatialVelocityConstraint ( const MultibodyPlant< AutoDiffXd > *  plant,
const Frame< AutoDiffXd > &  frameA,
const Eigen::Ref< const Eigen::Vector3d > &  v_AC_lower,
const Eigen::Ref< const Eigen::Vector3d > &  v_AC_upper,
const Frame< AutoDiffXd > &  frameB,
const Eigen::Ref< const Eigen::Vector3d > &  p_BCo,
systems::Context< AutoDiffXd > *  plant_context,
const std::optional< AngularVelocityBounds > &  w_AC_bounds = std::nullopt 
)

Constructs SpatialVelocityConstraint object.

Parameters
plantThe MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
frameAThe frame in which frame C's spatial velocity is measured and expressed.
v_AC_lowerThe lower bound on the translational velocity of C, expressed in frame A.
v_AC_upperThe upper bound on the translational velocity of C, expressed in frame A.
frameBThe frame to which frame C is rigidly attached.
p_BCoThe position of the origin of frame C, rigidly attached to frame B, expressed in frame B. We take R_BC to be the identity rotation.
plant_contextThe Context that has been allocated for this plant. We will update the context when evaluating the constraint. plant_context should be alive during the lifetime of this constraint.
w_AC_boundsIf provided, then the number of constraints will be 5: 3 for translational velocities and then two more for the angular velocity magnitude and angle.
Precondition
frameA and frameB must belong to plant.
v_AC_lower(i) <= v_AC_upper(i) for i = 1, 2, 3.
Exceptions
std::exceptionif plant is nullptr.
std::exceptionif plant_context is nullptr.
std::exceptionif invalid w_AC_bounds are provided.

◆ ~SpatialVelocityConstraint()

Member Function Documentation

◆ operator=() [1/2]

SpatialVelocityConstraint& operator= ( const SpatialVelocityConstraint )
delete

◆ operator=() [2/2]


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