pydrake.multibody.inverse_kinematics

InverseKinematics module

class pydrake.multibody.inverse_kinematics.AngleBetweenVectorsConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

Constrains that the angle between a vector a and another vector b is between [θ_lower, θ_upper]. a is fixed to a frame A, while b is fixed to a frame B. Mathematically, if we denote a_unit_A as a expressed in frame A after normalization (a_unit_A has unit length), and b_unit_B as b expressed in frame B after normalization, the constraint is cos(θ_upper) ≤ a_unit_Aᵀ * R_AB * b_unit_B ≤ cos(θ_lower)

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.AngleBetweenVectorsConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], frameA: pydrake.multibody.tree.Frame_[float], a_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[float], b_B: numpy.ndarray[float64[3, 1]], angle_lower: float, angle_upper: float, plant_context: pydrake.systems.framework.Context_[float]) -> None

Constructs an AngleBetweenVectorsConstraint.

Parameter plant:
The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
Parameter frameA:
The Frame object for frame A.
Parameter a_A:
The vector a fixed to frame A, expressed in frame A.
Parameter frameB:
The Frame object for frame B.
Parameter b_B:
The vector b fixed to frame B, expressed in frameB.
Parameter angle_lower:
The lower bound on the angle between a and b. It is denoted as θ_lower in the class documentation.
Parameter angle_upper:
The upper bound on the angle between a and b. it is denoted as θ_upper in the class documentation.
Parameter 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.
Precondition:
frameA and frameB must belong to plant.
Raises:ValueError if plant is nullptr.
Raises:ValueError if a_A is close to zero.
Raises:ValueError if b_B is close to zero.
Raises:ValueError if angle_lower is negative.
Raises:ValueError if angle_upper ∉ [angle_lower, π].
Raises:ValueError if plant_context is nullptr.
  1. __init__(self: pydrake.multibody.inverse_kinematics.AngleBetweenVectorsConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frameA: pydrake.multibody.tree.Frame_[AutoDiffXd], a_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[AutoDiffXd], b_B: numpy.ndarray[float64[3, 1]], angle_lower: float, angle_upper: float, plant_context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>

class pydrake.multibody.inverse_kinematics.DistanceConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

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

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.DistanceConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], geometry_pair: Tuple[pydrake.geometry.GeometryId], plant_context: pydrake.systems.framework.Context_[float], distance_lower: float, distance_upper: float) -> None
Parameter plant:
The plant to which the pair of geometries belong. plant should outlive this DistanceConstraint object.
Parameter geometry_pair:
The 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.
Parameter plant_context:
The context for the plant. plant_context should outlive this DistanceConstraint object.
Parameter distance_lower:
The lower bound on the distance.
Parameter distance_upper:
The upper bound on the distance.
  1. __init__(self: pydrake.multibody.inverse_kinematics.DistanceConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], geometry_pair: Tuple[pydrake.geometry.GeometryId], plant_context: pydrake.systems.framework.Context_[AutoDiffXd], distance_lower: float, distance_upper: float) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>

class pydrake.multibody.inverse_kinematics.GazeTargetConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

Constrains a target point T to be within a cone K. The point T (“T” stands for “target”) is fixed in a frame B, with position p_BT. The cone originates from a point S (“S” stands for “source”), fixed in frame A with position p_AS, with the axis of the cone being n, also fixed in frame A. The half angle of the cone is θ. A common usage of this constraint is that a camera should gaze at some target; namely the target falls within a gaze cone, originating from the camera eye.

Mathematically the constraint is p_ST_Aᵀ * n_unit_A ≥ 0 (p_ST_Aᵀ * n_unit_A)² ≥ (cosθ)²p_ST_Aᵀ * p_ST_A where p_ST_A is the vector from S to T, expressed in frame A. n_unit_A is the unit length directional vector representing the center ray of the cone.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.GazeTargetConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], frameA: pydrake.multibody.tree.Frame_[float], p_AS: numpy.ndarray[float64[3, 1]], n_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[float], p_BT: numpy.ndarray[float64[3, 1]], cone_half_angle: float, plant_context: pydrake.systems.framework.Context_[float]) -> None
Parameter plant:
The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
Parameter frameA:
The frame to which the gaze cone is fixed.
Parameter p_AS:
The position of the cone source point S, measured and expressed in frame A.
Parameter n_A:
The directional vector representing the center ray of the cone, expressed in frame A.
Parameter frameB:
The frame to which the target point T is fixed.
Parameter p_BT:
The position of the target point T, measured and expressed in frame B.
Parameter cone_half_angle:
The half angle of the cone. We denote it as θ in the class documentation. cone_half_angle is in radians.
Parameter 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.
Precondition:
frameA and frameB must belong to plant.
Raises:ValueError if plant is nullptr.
Raises:ValueError if n_A is close to zero.
Raises:ValueError if cone_half_angle ∉ [0, π/2].
Raises:ValueError if plant_context is nullptr.
  1. __init__(self: pydrake.multibody.inverse_kinematics.GazeTargetConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frameA: pydrake.multibody.tree.Frame_[AutoDiffXd], p_AS: numpy.ndarray[float64[3, 1]], n_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BT: numpy.ndarray[float64[3, 1]], cone_half_angle: float, plant_context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>

class pydrake.multibody.inverse_kinematics.InverseKinematics

Solves an inverse kinematics (IK) problem on a MultibodyPlant, to find the postures of the robot satisfying certain constraints. The decision variables include the generalized position of the robot.

AddAngleBetweenVectorsConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, frameA: pydrake.multibody.tree.Frame_[float], na_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[float], nb_B: numpy.ndarray[float64[3, 1]], angle_lower: float, angle_upper: float) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Constrains that the angle between a vector na and another vector nb is between [θ_lower, θ_upper]. na is fixed to a frame A, while nb is fixed to a frame B. Mathematically, if we denote na_unit_A as na expressed in frame A after normalization (na_unit_A has unit length), and nb_unit_B as nb expressed in frame B after normalization, the constraint is cos(θ_upper) ≤ na_unit_Aᵀ * R_AB * nb_unit_B ≤ cos(θ_lower), where R_AB is the rotation matrix, representing the orientation of frame B expressed in frame A.

Parameter frameA:
The frame to which na is fixed.
Parameter na_A:
The vector na fixed to frame A, expressed in frame A.
Precondition:
na_A should be a non-zero vector.
Raises:ValueError if na_A is close to zero.
Parameter frameB:
The frame to which nb is fixed.
Parameter nb_B:
The vector nb fixed to frame B, expressed in frame B.
Precondition:
nb_B should be a non-zero vector.
Raises:ValueError if nb_B is close to zero.
Parameter angle_lower:
The lower bound on the angle between na and nb. It is denoted as θ_lower in the documentation. angle_lower is in radians.
Precondition:
angle_lower >= 0.
Raises:ValueError if angle_lower is negative.
Parameter angle_upper:
The upper bound on the angle between na and nb. it is denoted as θ_upper in the class documentation. angle_upper is in radians.
Precondition:
angle_lower <= angle_upper <= pi.
Raises:ValueError if angle_upper is outside the bounds.
AddDistanceConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, geometry_pair: Tuple[pydrake.geometry.GeometryId], distance_lower: float, distance_upper: float) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Adds the constraint that the distance between a pair of geometries is within some bounds.

Parameter geometry_pair:
The 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.
Parameter distance_lower:
The lower bound on the distance.
Parameter distance_upper:
The upper bound on the distance.
AddGazeTargetConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, frameA: pydrake.multibody.tree.Frame_[float], p_AS: numpy.ndarray[float64[3, 1]], n_A: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[float], p_BT: numpy.ndarray[float64[3, 1]], cone_half_angle: float) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Constrains a target point T to be within a cone K. The point T (“T” stands for “target”) is fixed in a frame B, with position p_BT. The cone originates from a point S (“S” stands for “source”), fixed in frame A with position p_AS, with the axis of the cone being n, also fixed in frame A. The half angle of the cone is θ. A common usage of this constraint is that a camera should gaze at some target; namely the target falls within a gaze cone, originating from the camera eye.

Parameter frameA:
The frame where the gaze cone is fixed to.
Parameter p_AS:
The position of the cone source point S, measured and expressed in frame A.
Parameter n_A:
The directional vector representing the center ray of the cone, expressed in frame A.
Precondition:
n_A cannot be a zero vector.
Raises:ValueError is n_A is close to a zero vector.
Parameter frameB:
The frame where the target point T is fixed to.
Parameter p_BT:
The position of the target point T, measured and expressed in frame B.
Parameter cone_half_angle:
The half angle of the cone. We denote it as θ in the documentation. cone_half_angle is in radians.
Precondition:
0 <= cone_half_angle <= pi.
Raises:ValueError if cone_half_angle is outside of the bound.
AddMinimumDistanceConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, minimum_distance: float, threshold_distance: float = 1.0) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Adds the constraint that the pairwise distance between objects should be no smaller than minimum_distance. We consider the distance between pairs of 1. Anchored (static) object and a dynamic object. 2. A dynamic object and another dynamic object, if one is not the parent link of the other.

Parameter minimum_distance:
The minimum allowed value, dₘᵢₙ, of the signed distance between any candidate pair of geometries.
Parameter influence_distance_offset:
The difference (in meters) between the influence distance, d_influence, and the minimum distance, dₘᵢₙ. This value must be finite and strictly positive, as it is used to scale the signed distances between pairs of geometries. Smaller values may improve performance, as fewer pairs of geometries need to be considered in each constraint evaluation. $*Default:* 1 meter

See also

MinimumDistanceConstraint for more details on the constraint formulation.

Precondition:
The MultibodyPlant passed to the constructor of this has registered its geometry with a SceneGraph.
Precondition:
0 < influence_distance_offset < ∞
AddOrientationConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, frameAbar: pydrake.multibody.tree.Frame_[float], R_AbarA: pydrake.math.RotationMatrix_[float], frameBbar: pydrake.multibody.tree.Frame_[float], R_BbarB: pydrake.math.RotationMatrix_[float], theta_bound: float) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Constrains that the angle difference θ between the orientation of frame A and the orientation of frame B to satisfy θ ≤ θ_bound. Frame A is fixed to frame A_bar, with orientation R_AbarA measured in frame A_bar. Frame B is fixed to frame B_bar, with orientation R_BbarB measured in frame B_bar. The angle difference between frame A’s orientation R_WA and B’s orientation R_WB is θ, (θ ∈ [0, π]), if there exists a rotation axis a, such that rotating frame A by angle θ about axis a aligns it with frame B. Namely R_AB = I + sinθ â + (1-cosθ)â² (1) where R_AB is the orientation of frame B expressed in frame A. â is the skew symmetric matrix of the rotation axis a. Equation (1) is the Rodrigues formula that computes the rotation matrix from a rotation axis a and an angle θ, https://en.wikipedia.org/wiki/Rodrigues%27_rotation_formula If the users want frame A and frame B to align perfectly, they can set θ_bound = 0. Mathematically, this constraint is imposed as trace(R_AB) ≥ 2cos(θ_bound) + 1 (1) To derive (1), using Rodrigues formula R_AB = I + sinθ â + (1-cosθ)â² where trace(R_AB) = 2cos(θ) + 1 ≥ 2cos(θ_bound) + 1

Parameter frameAbar:
frame A_bar, the frame A is fixed to frame A_bar.
Parameter R_AbarA:
The orientation of frame A measured in frame A_bar.
Parameter frameBbar:
frame B_bar, the frame B is fixed to frame B_bar.
Parameter R_BbarB:
The orientation of frame B measured in frame B_bar.
Parameter theta_bound:
The bound on the angle difference between frame A’s orientation and frame B’s orientation. It is denoted as θ_bound in the documentation. theta_bound is in radians.
AddPositionConstraint(self: pydrake.multibody.inverse_kinematics.InverseKinematics, frameB: pydrake.multibody.tree.Frame_[float], p_BQ: numpy.ndarray[float64[3, 1]], frameA: pydrake.multibody.tree.Frame_[float], p_AQ_lower: numpy.ndarray[float64[3, 1]], p_AQ_upper: numpy.ndarray[float64[3, 1]]) → pydrake.solvers.mathematicalprogram.Binding_Constraint

Adds the kinematic constraint that a point Q, fixed in frame B, should lie within a bounding box expressed in another frame A as p_AQ_lower <= p_AQ <= p_AQ_upper, where p_AQ is the position of point Q measured and expressed in frame A.

Parameter frameB:
The frame in which point Q is fixed.
Parameter p_BQ:
The position of the point Q, rigidly attached to frame B, measured and expressed in frame B.
Parameter frameA:
The frame in which the bounding box p_AQ_lower <= p_AQ <= p_AQ_upper is expressed.
Parameter p_AQ_lower:
The lower bound on the position of point Q, measured and expressed in frame A.
Parameter p_AQ_upper:
The upper bound on the position of point Q, measured and expressed in frame A.
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.InverseKinematics, plant: pydrake.multibody.plant.MultibodyPlant_[float]) -> None

Constructs an inverse kinematics problem for a MultibodyPlant. This constructor will create and own a context for

Parameter plant:
.
Parameter plant:
The robot on which the inverse kinematics problem will be solved.

Note

The inverse kinematics problem constructed in this way doesn’t permit collision related constraint (such as calling AddMinimumDistanceConstraint). To enable collision related constraint, call InverseKinematics(const MultibodyPlant<double>& plant, systems::Context<double>* plant_context);

  1. __init__(self: pydrake.multibody.inverse_kinematics.InverseKinematics, plant: pydrake.multibody.plant.MultibodyPlant_[float], plant_context: pydrake.systems.framework.Context_[float]) -> None

Constructs an inverse kinematics problem for a MultibodyPlant. If the user wants to solve the problem with collision related constraint (like calling AddMinimumDistanceConstraint), please use this constructor.

Parameter plant:
The robot on which the inverse kinematics problem will be solved. This plant should have been connected to a SceneGraph within a Diagram
Parameter context:
The context for the plant. This context should be a part of the Diagram context. To construct a plant connected to a SceneGraph, with the corresponding plant_context, the steps are // 1. Add a diagram containing the MultibodyPlant and SceneGraph systems::DiagramBuilder<double> builder; auto items = AddMultibodyPlantSceneGraph(&builder); // 2. Add collision geometries to the plant Parser(&(items.plant)).AddModelFromFile(“model.sdf”); // 3. Construct the diagram auto diagram = builder.Build(); // 4. Create diagram context. auto diagram_context= diagram->CreateDefaultContext(); // 5. Get the context for the plant. auto plant_context = &(diagram->GetMutableSubsystemContext(items.plant, diagram_context.get()));
context(self: pydrake.multibody.inverse_kinematics.InverseKinematics) → pydrake.systems.framework.Context_[float]

Getter for the plant context.

get_mutable_context(self: pydrake.multibody.inverse_kinematics.InverseKinematics) → pydrake.systems.framework.Context_[float]

Getter for the mutable plant context.

get_mutable_prog(self: pydrake.multibody.inverse_kinematics.InverseKinematics) → pydrake.solvers.mathematicalprogram.MathematicalProgram

Getter for the optimization program constructed by InverseKinematics.

prog(self: pydrake.multibody.inverse_kinematics.InverseKinematics) → pydrake.solvers.mathematicalprogram.MathematicalProgram

Getter for the optimization program constructed by InverseKinematics.

q(self: pydrake.multibody.inverse_kinematics.InverseKinematics) → numpy.ndarray[object[m, 1]]

Getter for q. q is the decision variable for the generalized positions of the robot.

class pydrake.multibody.inverse_kinematics.MinimumDistanceConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

Constrain the signed distance between all candidate pairs of geometries (according to the logic of SceneGraphInspector::GetCollisionCandidates()) to be no smaller than a specified minimum distance.

The formulation of the constraint is

0 ≤ SmoothMax( φ((dᵢ - d_influence)/(d_influence - dₘᵢₙ)) / φ(-1) ) ≤ 1

where dᵢ is the signed distance of the i-th pair, dₘᵢₙ is the minimum allowable distance, d_influence is the “influence distance” (the distance below which a pair of geometries influences the constraint), φ is a multibody::MinimumDistancePenaltyFunction, and SmoothMax(d) is smooth approximation of max(d). We require that dₘᵢₙ < d_influence. The input scaling (dᵢ - d_influence)/(d_influence - dₘᵢₙ) ensures that at the boundary of the feasible set (when dᵢ == dₘᵢₙ), we evaluate the penalty function at -1, where it is required to have a non-zero gradient.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.MinimumDistanceConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], minimum_distance: float, plant_context: pydrake.systems.framework.Context_[float], penalty_function: Callable[[float, float, float], None] = None, influence_distance_offset: float = 1) -> None

Constructs a MinimumDistanceConstraint.

Parameter plant:
The multibody system on which the constraint will be evaluated.
Parameter minimum_distance:
The minimum allowed value, dₘᵢₙ, of the signed distance between any candidate pair of geometries.
Parameter penalty_function:
The penalty function formulation.
Default: QuadraticallySmoothedHinge
$Parameter influence_distance_offset:

The difference (in meters) between the influence distance, d_influence, and the minimum distance, dₘᵢₙ (see class documentation). This value must be finite and strictly positive, as it is used to scale the signed distances between pairs of geometries. Smaller values may improve performance, as fewer pairs of geometries need to be considered in each constraint evaluation. $*Default:* 1 meter

Raises:
  • ValueError if plant has not registered its geometry with a
  • SceneGraph object.
Raises:

ValueError if influence_distance_offset = ∞.

Raises:

ValueError if influence_distance_offset ≤ 0.

  1. __init__(self: pydrake.multibody.inverse_kinematics.MinimumDistanceConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], minimum_distance: float, plant_context: pydrake.systems.framework.Context_[AutoDiffXd], penalty_function: Callable[[float, float, float], None] = None, influence_distance_offset: float = 1) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>

class pydrake.multibody.inverse_kinematics.OrientationConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

Constrains that the angle difference θ between the orientation of frame A and the orientation of frame B to satisfy θ ≤ θ_bound. The angle difference between frame A’s orientation R_WA and B’s orientation R_WB is θ (θ ∈ [0, π]), if there exists a rotation axis a, such that rotating frame A by angle θ about axis a aligns it with frame B. Namely R_AB = I + sinθ â + (1-cosθ)â² (1) where R_AB is the orientation of frame B expressed in frame A. â is the skew symmetric matrix of the rotation axis a. Equation (1) is the Rodrigues formula that computes the rotation matrix froma rotation axis a and an angle θ, https://en.wikipedia.org/wiki/Rodrigues%27_rotation_formula If the users want frame A and frame B to align perfectly, they can set θ_bound = 0. Mathematically, this constraint is imposed as trace(R_AB) ≥ 2cos(θ_bound) + 1 (1) To derive (1), using Rodrigues formula R_AB = I + sinθ â + (1-cosθ)â² where trace(R_AB) = 2cos(θ) + 1 ≥ 2cos(θ_bound) + 1

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.OrientationConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], frameAbar: pydrake.multibody.tree.Frame_[float], R_AbarA: pydrake.math.RotationMatrix_[float], frameBbar: pydrake.multibody.tree.Frame_[float], R_BbarB: pydrake.math.RotationMatrix_[float], theta_bound: float, plant_context: pydrake.systems.framework.Context_[float]) -> None

Constructs an OrientationConstraint object. The frame A is fixed to a frame A̅, with orientatation R_AbarA measured in frame A̅. The frame B is fixed to a frame B̅, with orientation R_BbarB measured in frame B. We constrain the angle between frame A and B to be less than theta_bound.

Parameter plant:
The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
Parameter frameAbar:
The frame A̅ in the model to which frame A is fixed.
Parameter R_AbarA:
The orientation of frame A measured in frame A̅.
Parameter frameBbar:
The frame B̅ in the model to which frame B is fixed.
Parameter R_BbarB:
The orientation of frame B measured in frame B̅.
Parameter theta_bound:
The bound on the angle difference between frame A’s orientation and frame B’s orientation. It is denoted as θ_bound in the class documentation. theta_bound is in radians.
Parameter plant_context:
The Context that has been allocated for this tree. We will update the context when evaluating the constraint. plant_context should be alive during the lifetime of this constraint.
Raises:

ValueError if plant is nullptr.

Raises:
  • RuntimeError if frameAbar or frameBbar does not belong to
  • plant.
Raises:

ValueError if angle_bound < 0.

Raises:

ValueError if plant_context is nullptr.

  1. __init__(self: pydrake.multibody.inverse_kinematics.OrientationConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frameAbar: pydrake.multibody.tree.Frame_[AutoDiffXd], R_AbarA: pydrake.math.RotationMatrix_[float], frameBbar: pydrake.multibody.tree.Frame_[AutoDiffXd], R_BbarB: pydrake.math.RotationMatrix_[float], theta_bound: float, plant_context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>

class pydrake.multibody.inverse_kinematics.PositionConstraint

Bases: pydrake.solvers.mathematicalprogram.Constraint

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.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.inverse_kinematics.PositionConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[float], frameA: pydrake.multibody.tree.Frame_[float], p_AQ_lower: numpy.ndarray[float64[3, 1]], p_AQ_upper: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[float], p_BQ: numpy.ndarray[float64[3, 1]], plant_context: pydrake.systems.framework.Context_[float]) -> None

Constructs PositionConstraint object.

Parameter plant:
The MultibodyPlant on which the constraint is imposed. plant should be alive during the lifetime of this constraint.
Parameter frameA:
The frame in which point Q’s position is measured.
Parameter p_AQ_lower:
The lower bound on the position of point Q, measured and expressed in frame A.
Parameter p_AQ_upper:
The upper bound on the position of point Q, measured and expressed in frame A.
Parameter frameB:
The frame to which point Q is rigidly attached.
Parameter p_BQ:
The position of the point Q, rigidly attached to frame B, measured and expressed in frame B.
Parameter 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.
Precondition:
frameA and frameB must belong to plant.
Precondition:
p_AQ_lower(i) <= p_AQ_upper(i) for i = 1, 2, 3.
Raises:ValueError if plant is nullptr.
Raises:ValueError if plant_context is nullptr.
  1. __init__(self: pydrake.multibody.inverse_kinematics.PositionConstraint, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frameA: pydrake.multibody.tree.Frame_[AutoDiffXd], p_AQ_lower: numpy.ndarray[float64[3, 1]], p_AQ_upper: numpy.ndarray[float64[3, 1]], frameB: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BQ: numpy.ndarray[float64[3, 1]], plant_context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None

Overloaded constructor. Constructs the constraint using MultibodyPlant<AutoDiffXd>