pydrake.multibody.rational
RationalForwardKinematics module
- class pydrake.multibody.rational.RationalForwardKinematics
- __init__(self: pydrake.multibody.rational.RationalForwardKinematics, plant: pydrake.multibody.plant.MultibodyPlant) None
- CalcBodyPoseAsMultilinearPolynomial(self: pydrake.multibody.rational.RationalForwardKinematics, q_star: numpy.ndarray[numpy.float64[m, 1]], body_index: pydrake.multibody.tree.BodyIndex, expressed_body_index: pydrake.multibody.tree.BodyIndex) pydrake.multibody.rational.RationalForwardKinematicsPose
Computes the pose X_AB as a multilinear polynomial function. The indeterminates of the polynomials are cos_delta() and sin_delta(). To compute the pose as a rational function of indeterminates s(), we recommend to first call this function to compute the pose as a multilinear polynomial functions, and then call ConvertMultilinearPolynomialToRationalFunction() to convert these polynomials to rational function with indeterminates s().
- Parameter
q_star
: The nominal posture q*.
- Parameter
body_index
: Frame B, the body whose pose is computed.
- Parameter
expressed_body_index
: Frame A, the body in whose frame the pose is expressed.
- Returns
X_AB The pose of body
body_index
expressed inexpressed_body_index
.
- Parameter
- ComputeQValue(*args, **kwargs)
Overloaded function.
ComputeQValue(self: pydrake.multibody.rational.RationalForwardKinematics, s_val: numpy.ndarray[numpy.float64[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]]) -> numpy.ndarray[numpy.float64[m, 1]]
Computes values of q from s_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
ComputeQValue(self: pydrake.multibody.rational.RationalForwardKinematics, s_val: numpy.ndarray[object[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]]) -> numpy.ndarray[object[m, 1]]
Computes values of q from s_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
ComputeQValue(self: pydrake.multibody.rational.RationalForwardKinematics, s_val: numpy.ndarray[object[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]]) -> numpy.ndarray[object[m, 1]]
Computes values of q from s_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
- ComputeSValue(*args, **kwargs)
Overloaded function.
ComputeSValue(self: pydrake.multibody.rational.RationalForwardKinematics, q_val: numpy.ndarray[numpy.float64[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]], angles_wrap_to_inf: bool = False) -> numpy.ndarray[numpy.float64[m, 1]]
Computes values of s from q_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
- Parameter
angles_wrap_to_inf
: If set to True, then for a revolute joint whose (θ −θ*) >=π/2 (or <= −π/2), we set the corresponding s to ∞ (or −∞), $*Default:* is false.
ComputeSValue(self: pydrake.multibody.rational.RationalForwardKinematics, q_val: numpy.ndarray[object[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]]) -> numpy.ndarray[object[m, 1]]
Computes values of s from q_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
- Parameter
angles_wrap_to_inf
: If set to True, then for a revolute joint whose (θ −θ*) >=π/2 (or <= −π/2), we set the corresponding s to ∞ (or −∞), $*Default:* is false.
ComputeSValue(self: pydrake.multibody.rational.RationalForwardKinematics, q_val: numpy.ndarray[object[m, 1]], q_star_val: numpy.ndarray[numpy.float64[m, 1]]) -> numpy.ndarray[object[m, 1]]
Computes values of s from q_val and q_star_val, while handling the index matching between q and s (we don’t guarantee that s(i) is computed from q(i)).
- Parameter
angles_wrap_to_inf
: If set to True, then for a revolute joint whose (θ −θ*) >=π/2 (or <= −π/2), we set the corresponding s to ∞ (or −∞), $*Default:* is false.
- ConvertMultilinearPolynomialToRationalFunction(self: pydrake.multibody.rational.RationalForwardKinematics, e: pydrake.symbolic.Polynomial) pydrake.symbolic.RationalFunction
Given a polynomial whose indeterminates are cos_delta() and sin_delta() (typically this polynomial is obtained from calling CalcBodyPoseAsMultilinearPolynomial()), converts this polynomial to a rational function with indeterminates s().
- plant(self: pydrake.multibody.rational.RationalForwardKinematics) pydrake.multibody.plant.MultibodyPlant
- s(self: pydrake.multibody.rational.RationalForwardKinematics) numpy.ndarray[object[m, 1]]
- class pydrake.multibody.rational.RationalForwardKinematicsPose
Note
This class is templated; see
RationalForwardKinematicsPose_
for the list of instantiations.- __init__(*args, **kwargs)
- position(self: pydrake.multibody.rational.RationalForwardKinematicsPose) numpy.ndarray[object[3, 1]]
- rotation(self: pydrake.multibody.rational.RationalForwardKinematicsPose) numpy.ndarray[object[3, 3]]
- template pydrake.multibody.rational.RationalForwardKinematicsPose_
Instantiations:
RationalForwardKinematicsPose_[Polynomial]
,RationalForwardKinematicsPose_[RationalFunction]
- class pydrake.multibody.rational.RationalForwardKinematicsPose_[RationalFunction]
- __init__(*args, **kwargs)
- position(self: pydrake.multibody.rational.RationalForwardKinematicsPose_[RationalFunction]) numpy.ndarray[object[3, 1]]
- rotation(self: pydrake.multibody.rational.RationalForwardKinematicsPose_[RationalFunction]) numpy.ndarray[object[3, 3]]