Drake
Drake C++ Documentation

Detailed Description

Constrains the distance between a pair of geometries to be within a range [distance_lower, distance_upper].

#include <drake/multibody/inverse_kinematics/distance_constraint.h>

Public Member Functions

 DistanceConstraint (const multibody::MultibodyPlant< double > *const plant, SortedPair< geometry::GeometryId > geometry_pair, systems::Context< double > *plant_context, double distance_lower, double distance_upper)
 
 DistanceConstraint (const multibody::MultibodyPlant< AutoDiffXd > *const plant, SortedPair< geometry::GeometryId > geometry_pair, systems::Context< AutoDiffXd > *plant_context, double distance_lower, double distance_upper)
 Overloaded constructor. More...
 
 ~DistanceConstraint () override
 
Does not allow copy, move, or assignment
 DistanceConstraint (const DistanceConstraint &)=delete
 
DistanceConstraintoperator= (const DistanceConstraint &)=delete
 
 DistanceConstraint (DistanceConstraint &&)=delete
 
DistanceConstraintoperator= (DistanceConstraint &&)=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...
 
 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)
 

Constructor & Destructor Documentation

◆ DistanceConstraint() [1/4]

DistanceConstraint ( const DistanceConstraint )
delete

◆ DistanceConstraint() [2/4]

◆ DistanceConstraint() [3/4]

DistanceConstraint ( const multibody::MultibodyPlant< double > *const  plant,
SortedPair< geometry::GeometryId geometry_pair,
systems::Context< double > *  plant_context,
double  distance_lower,
double  distance_upper 
)
Parameters
plantThe plant to which the pair of geometries belong. plant should outlive this DistanceConstraint object.
geometry_pairThe pair of geometries between which the distance is constrained. Notice that we only consider the distance between a static geometry and a dynamic geometry, or a pair of dynamic geometries. We don't allow constraining the distance between two static geometries.
plant_contextThe context for the plant. plant_context should outlive this DistanceConstraint object.
distance_lowerThe lower bound on the distance.
distance_upperThe upper bound on the distance.

◆ DistanceConstraint() [4/4]

DistanceConstraint ( const multibody::MultibodyPlant< AutoDiffXd > *const  plant,
SortedPair< geometry::GeometryId geometry_pair,
systems::Context< AutoDiffXd > *  plant_context,
double  distance_lower,
double  distance_upper 
)

Overloaded constructor.

Constructs the constraint with MultibodyPlant<AutoDiffXd>.

◆ ~DistanceConstraint()

~DistanceConstraint ( )
override

Member Function Documentation

◆ operator=() [1/2]

DistanceConstraint& operator= ( const DistanceConstraint )
delete

◆ operator=() [2/2]

DistanceConstraint& operator= ( DistanceConstraint &&  )
delete

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