pydrake.multibody.math

Bindings for multibody math.

pydrake.multibody.math.SpatialAcceleration

alias of pydrake.multibody.math.SpatialAcceleration_[float]

template pydrake.multibody.math.SpatialAcceleration_

Instantiations: SpatialAcceleration_[float], SpatialAcceleration_[AutoDiffXd], SpatialAcceleration_[Expression]

class SpatialAcceleration_[float]

This class is used to represent a spatial acceleration that combines rotational (angular acceleration) and translational (linear acceleration) components. While a SpatialVelocity V_XY represents the motion of a “moving frame” Y measured with respect to a “measured-in” frame X, the SpatialAcceleration A_XY represents the rate of change of this spatial velocity V_XY in frame X. That is \(^XA^Y = \frac{^Xd}{dt}\,{^XV^Y}\) where \(\frac{^Xd}{dt}\) denotes the time derivative taken in frame X. That is, to compute an acceleration we need to specify in what frame the time derivative is taken, see [Mitiguy 2016, §6.1] for a more in depth discussion on this. Time derivatives can be taken in different frames, and they transform according to the “Transport Theorem”, which is in Drake is implemented in drake::math::ConvertTimeDerivativeToOtherFrame(). In source code comments we write A_XY = DtX(V_XY), where DtX() is the operator that takes the time derivative in the X frame. By convention, and unless otherwise stated, we assume that the frame in which the time derivative is taken is the “measured-in” frame, i.e. the time derivative used in A_XY is in frame X by default (i.e. DtX()). To perform numerical computations, we need to specify an “expressed-in” frame E (which may be distinct from either X or Y), so that components can be expressed as real numbers. Only the vector values are stored in a SpatialAcceleration object; the frames must be understood from context and it is the responsibility of the user to keep track of them. That is best accomplished through disciplined notation. In source code we use monogram notation where capital A is used to designate a spatial acceleration quantity. The same monogram notation rules for SpatialVelocity are also used for SpatialAcceleration. That is, the spatial acceleration of a frame Y measured in X and expressed in E is denoted with A_XY_E. For a more detailed introduction on spatial vectors and the monogram notation please refer to section multibody_spatial_vectors.

[Mitiguy 2016] Mitiguy, P., 2016. Advanced Dynamics & Motion Simulation.

Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.
SetZero(self: pydrake.multibody.math.SpatialAcceleration_[float]) → pydrake.multibody.math.SpatialAcceleration_[float]

Sets both rotational and translational components of this SpatialVector to zero.

Zero() → pydrake.multibody.math.SpatialAcceleration_[float]

Factory to create a zero SpatialVector, i.e. rotational and translational components are both zero.

get_coeffs(self: pydrake.multibody.math.SpatialAcceleration_[float]) → numpy.ndarray[float64[6, 1]]

Returns a constant reference to the underlying storage.

rotational(self: pydrake.multibody.math.SpatialAcceleration_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the rotational component of this spatial vector.

translational(self: pydrake.multibody.math.SpatialAcceleration_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the translational component of this spatial vector.

pydrake.multibody.math.SpatialForce

alias of pydrake.multibody.math.SpatialForce_[float]

template pydrake.multibody.math.SpatialForce_

Instantiations: SpatialForce_[float], SpatialForce_[AutoDiffXd], SpatialForce_[Expression]

class SpatialForce_[float]

This class is used to represent a spatial force (also called a wrench) that combines both rotational (torque) and translational force components. Spatial forces are 6-element quantities that are pairs of ordinary 3-vectors. Elements 0-2 are the torque component while elements 3-5 are the force component. Both vectors must be expressed in the same frame, and the translational force is applied to a particular point of a body, but neither the frame nor the point are stored with a SpatialForce object; they must be understood from context. It is the responsibility of the user to keep track of the application point and the expressed-in frame. That is best accomplished through disciplined notation. In source code we use monogram notation where capital F is used to designate a spatial force quantity. We write a point P fixed to body (or frame) B as \(B_P\) which appears in code and comments as Bp. Then we write a particular spatial force as F_Bp_E where the _E suffix indicates that the expressed-in frame is E. This symbol represents a torque applied to body B, and a force applied to point P on B, with both vectors expressed in E. Very often the application point will be the body origin Bo; if no point is shown the origin is understood, so F_B_E means F_Bo_E. For a more detailed introduction on spatial vectors and the monogram notation please refer to section multibody_spatial_vectors.

Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.
SetZero(self: pydrake.multibody.math.SpatialForce_[float]) → pydrake.multibody.math.SpatialForce_[float]

Sets both rotational and translational components of this SpatialVector to zero.

Zero() → pydrake.multibody.math.SpatialForce_[float]

Factory to create a zero SpatialVector, i.e. rotational and translational components are both zero.

get_coeffs(self: pydrake.multibody.math.SpatialForce_[float]) → numpy.ndarray[float64[6, 1]]

Returns a constant reference to the underlying storage.

rotational(self: pydrake.multibody.math.SpatialForce_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the rotational component of this spatial vector.

translational(self: pydrake.multibody.math.SpatialForce_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the translational component of this spatial vector.

pydrake.multibody.math.SpatialVelocity

alias of pydrake.multibody.math.SpatialVelocity_[float]

template pydrake.multibody.math.SpatialVelocity_

Instantiations: SpatialVelocity_[float], SpatialVelocity_[AutoDiffXd], SpatialVelocity_[Expression]

class SpatialVelocity_[float]

This class is used to represent a spatial velocity (also called a twist) that combines rotational (angular) and translational (linear) velocity components. Spatial velocities are 6-element quantities that are pairs of ordinary 3-vectors. Elements 0-2 are the angular velocity component while elements 3-5 are the translational velocity. Spatial velocities represent the motion of a “moving frame” B measured with respect to a “measured-in” frame A. In addition, the two contained vectors must be expressed in the same “expressed-in” frame E, which may be distinct from either A or B. Finally, while angular velocity is identical for any frame fixed to a rigid body, translational velocity refers to a particular point. Only the vector values are stored in a SpatialVelocity object; the three frames and the point must be understood from context. It is the responsibility of the user to keep track of them. That is best accomplished through disciplined notation. In source code we use monogram notation where capital V is used to designate a spatial velocity quantity. We write a point P fixed to body (or frame) B as \(B_P\) which appears in code and comments as Bp. Then we write a particular spatial velocity as V_ABp_E where the _E suffix indicates that the expressed-in frame is E. This symbol represents the angular velocity of frame B in frame A, and the translational velocity of point P in A, where P is fixed to frame B, with both vectors expressed in E. Very often the point of interest will be the body origin Bo; if no point is shown the origin is understood, so V_AB_E means V_ABo_E. For a more detailed introduction on spatial vectors and the monogram notation please refer to section multibody_spatial_vectors.

Template parameter T:
The underlying scalar type. Must be a valid Eigen scalar.
SetZero(self: pydrake.multibody.math.SpatialVelocity_[float]) → pydrake.multibody.math.SpatialVelocity_[float]

Sets both rotational and translational components of this SpatialVector to zero.

Zero() → pydrake.multibody.math.SpatialVelocity_[float]

Factory to create a zero SpatialVector, i.e. rotational and translational components are both zero.

get_coeffs(self: pydrake.multibody.math.SpatialVelocity_[float]) → numpy.ndarray[float64[6, 1]]

Returns a constant reference to the underlying storage.

rotational(self: pydrake.multibody.math.SpatialVelocity_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the rotational component of this spatial vector.

translational(self: pydrake.multibody.math.SpatialVelocity_[float]) → numpy.ndarray[float64[3, 1]]

Const access to the translational component of this spatial vector.