Constrains the position of a point Q, rigidly attached to a frame B, to be within a bounding box measured and expressed in frame A.
Namely p_AQ_lower <= p_AQ <= p_AQ_upper.
#include <drake/multibody/inverse_kinematics/position_constraint.h>
Public Member Functions | |
PositionConstraint (const MultibodyPlant< double > *plant, const Frame< double > &frameA, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_lower, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_upper, const Frame< double > &frameB, const Eigen::Ref< const Eigen::Vector3d > &p_BQ, systems::Context< double > *plant_context) | |
Constructs PositionConstraint object. More... | |
PositionConstraint (const MultibodyPlant< AutoDiffXd > *plant, const Frame< AutoDiffXd > &frameA, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_lower, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_upper, const Frame< AutoDiffXd > &frameB, const Eigen::Ref< const Eigen::Vector3d > &p_BQ, systems::Context< AutoDiffXd > *plant_context) | |
Overloaded constructor. More... | |
PositionConstraint (const MultibodyPlant< double > *plant, const Frame< double > &frameAbar, const std::optional< math::RigidTransformd > &X_AbarA, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_lower, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_upper, const Frame< double > &frameB, const Eigen::Ref< const Eigen::Vector3d > &p_BQ, systems::Context< double > *plant_context) | |
Overloaded constructor. More... | |
PositionConstraint (const MultibodyPlant< AutoDiffXd > *plant, const Frame< AutoDiffXd > &frameAbar, const std::optional< math::RigidTransformd > &X_AbarA, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_lower, const Eigen::Ref< const Eigen::Vector3d > &p_AQ_upper, const Frame< AutoDiffXd > &frameB, const Eigen::Ref< const Eigen::Vector3d > &p_BQ, systems::Context< AutoDiffXd > *plant_context) | |
Overloaded constructor. More... | |
~PositionConstraint () override | |
Does not allow copy, move, or assignment | |
PositionConstraint (const PositionConstraint &)=delete | |
PositionConstraint & | operator= (const PositionConstraint &)=delete |
PositionConstraint (PositionConstraint &&)=delete | |
PositionConstraint & | operator= (PositionConstraint &&)=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 | |
Constraint & | operator= (const Constraint &)=delete |
Constraint (Constraint &&)=delete | |
Constraint & | operator= (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 | |
EvaluatorBase & | operator= (const EvaluatorBase &)=delete |
EvaluatorBase (EvaluatorBase &&)=delete | |
EvaluatorBase & | operator= (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) |
|
delete |
|
delete |
PositionConstraint | ( | const MultibodyPlant< double > * | plant, |
const Frame< double > & | frameA, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_lower, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_upper, | ||
const Frame< double > & | frameB, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_BQ, | ||
systems::Context< double > * | plant_context | ||
) |
Constructs PositionConstraint object.
plant | The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint. |
frameA | The frame in which point Q's position is measured. |
p_AQ_lower | The lower bound on the position of point Q, measured and expressed in frame A. |
p_AQ_upper | The upper bound on the position of point Q, measured and expressed in frame A. |
frameB | The frame to which point Q is rigidly attached. |
p_BQ | The position of the point Q, rigidly attached to frame B, measured and expressed in frame B. |
plant_context | The 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. |
frameA
and frameB
must belong to plant
. std::exception | if plant is nullptr. |
std::exception | if plant_context is nullptr. |
PositionConstraint | ( | const MultibodyPlant< AutoDiffXd > * | plant, |
const Frame< AutoDiffXd > & | frameA, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_lower, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_upper, | ||
const Frame< AutoDiffXd > & | frameB, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_BQ, | ||
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.
PositionConstraint | ( | const MultibodyPlant< double > * | plant, |
const Frame< double > & | frameAbar, | ||
const std::optional< math::RigidTransformd > & | X_AbarA, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_lower, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_upper, | ||
const Frame< double > & | frameB, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_BQ, | ||
systems::Context< double > * | plant_context | ||
) |
Overloaded constructor.
Except that the constructor takes in a frame A̅ and a pose X_AAbar between the frame A and A̅. We will constrain the position of point Q expressed in the frame A to lie within a bounding box of A.
plant | The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint. |
frameAbar | The frame A̅ in which point Q's position is measured. |
X_AbarA | relative transform between the frame A̅ and A. If empty, then we use identity transform. |
p_AQ_lower | The lower bound on the position of point Q, measured and expressed in frame A. |
p_AQ_upper | The upper bound on the position of point Q, measured and expressed in frame A. |
frameB | The frame to which point Q is rigidly attached. |
p_BQ | The position of the point Q, rigidly attached to frame B, measured and expressed in frame B. |
plant_context | The 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. |
frameA
and frameB
must belong to plant
. std::exception | if plant is nullptr. |
std::exception | if plant_context is nullptr. |
PositionConstraint | ( | const MultibodyPlant< AutoDiffXd > * | plant, |
const Frame< AutoDiffXd > & | frameAbar, | ||
const std::optional< math::RigidTransformd > & | X_AbarA, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_lower, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_AQ_upper, | ||
const Frame< AutoDiffXd > & | frameB, | ||
const Eigen::Ref< const Eigen::Vector3d > & | p_BQ, | ||
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.
|
override |
|
delete |
|
delete |