Drake
Drake C++ Documentation
PointToPointDistanceConstraint Class Reference

Detailed Description

Constrain that the distance between a point P1 on frame B1 and another point P2 on frame B2 is within a range [distance_lower, distance_upper].

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

Public Member Functions

 PointToPointDistanceConstraint (const MultibodyPlant< double > *plant, const Frame< double > &frame1, const Eigen::Ref< const Eigen::Vector3d > &p_B1P1, const Frame< double > &frame2, const Eigen::Ref< const Eigen::Vector3d > &p_B2P2, double distance_lower, double distance_upper, systems::Context< double > *plant_context)
 Constrain that the distance between a point P1 attached to frame B1 and another point P2 attached to frame B2 is within the range [distance_lower, distance_upper]. More...
 
 PointToPointDistanceConstraint (const MultibodyPlant< AutoDiffXd > *plant, const Frame< AutoDiffXd > &frame1, const Eigen::Ref< const Eigen::Vector3d > &p_B1P1, const Frame< AutoDiffXd > &frame2, const Eigen::Ref< const Eigen::Vector3d > &p_B2P2, double distance_lower, double distance_upper, systems::Context< AutoDiffXd > *plant_context)
 Overloaded constructor. More...
 
 ~PointToPointDistanceConstraint () override
 
Does not allow copy, move, or assignment
 PointToPointDistanceConstraint (const PointToPointDistanceConstraint &)=delete
 
PointToPointDistanceConstraintoperator= (const PointToPointDistanceConstraint &)=delete
 
 PointToPointDistanceConstraint (PointToPointDistanceConstraint &&)=delete
 
PointToPointDistanceConstraintoperator= (PointToPointDistanceConstraint &&)=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

◆ PointToPointDistanceConstraint() [1/4]

◆ PointToPointDistanceConstraint() [2/4]

◆ PointToPointDistanceConstraint() [3/4]

PointToPointDistanceConstraint ( const MultibodyPlant< double > *  plant,
const Frame< double > &  frame1,
const Eigen::Ref< const Eigen::Vector3d > &  p_B1P1,
const Frame< double > &  frame2,
const Eigen::Ref< const Eigen::Vector3d > &  p_B2P2,
double  distance_lower,
double  distance_upper,
systems::Context< double > *  plant_context 
)

Constrain that the distance between a point P1 attached to frame B1 and another point P2 attached to frame B2 is within the range [distance_lower, distance_upper].

Mathematically, we impose the constraint distance_lower² <= distance(P1, P2)² <= distance_upper². We impose the constraint on the distance square instead of distance directly, because the gradient of distance is not well defined at distance=0, the gradient of the distance square is well defined everywhere.

Parameters
plantThe MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
frame1The frame in which P1 is attached to.
p_B1P1The position of P1 measured and expressed in B1.
frame2The frame in which P2 is attached to.
p_B2P2The position of P2 measured and expressed in B2.
distance_lowerThe lower bound on the distance, must be non-negative.
distance_upperThe upper bound on the distance, must be non-negative.
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.

◆ PointToPointDistanceConstraint() [4/4]

PointToPointDistanceConstraint ( const MultibodyPlant< AutoDiffXd > *  plant,
const Frame< AutoDiffXd > &  frame1,
const Eigen::Ref< const Eigen::Vector3d > &  p_B1P1,
const Frame< AutoDiffXd > &  frame2,
const Eigen::Ref< const Eigen::Vector3d > &  p_B2P2,
double  distance_lower,
double  distance_upper,
systems::Context< AutoDiffXd > *  plant_context 
)

Overloaded constructor.

Same as the constructor with the double version (using MultibodyPlant<double> and Context<double>), except the gradient of the constraint is computed from autodiff.

◆ ~PointToPointDistanceConstraint()

Member Function Documentation

◆ operator=() [1/2]

◆ operator=() [2/2]


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