pydrake.multibody.math

Bindings for multibody math.

class pydrake.multibody.math.SpatialAcceleration

This class represents a spatial acceleration A and has 6 elements with an angular (rotational) acceleration α (3-element vector) on top of a translational (linear) acceleration 𝐚 (3-element vector). Spatial acceleration represents the rotational and translational acceleration of a frame B with respect to a measured-in frame M. This class assumes that both the angular acceleration α and translational acceleration 𝐚 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely α and 𝐚) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, A_MB_E denotes frame B’s spatial acceleration measured in frame M, expressed in frame E and contains alpha_MB_E (B’s angular acceleration measured in M, expressed in E) and a_MBo_E (Bo’s translational acceleration measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation A_MBp_E denotes frame Bp’s spatial acceleration measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for A_MB is \(\,{^MA^B}\) and its definition is \(^MA^B = \frac{^Md}{dt}\,{^MV^B}\,\), where \({^MV^B}\) is frame B’s spatial velocity in frame M and \(\frac{^Md}{dt}\) denotes the time derivative taken in frame M. To differentiate a vector, we need to specify in what frame the time derivative is taken, see [Mitiguy 2022, §7.2] for an in-depth discussion. Time derivatives in different frames are related by the “Transport Theorem”, which in Drake is implemented in drake::math::ConvertTimeDerivativeToOtherFrame(). In source code (monogram) notation, we write A_MB = DtM(V_MB), where DtM() denotes the time derivative in frame M. Details on vector differentiation is in section Dt_multibody_quantities.

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

Note

This class is templated; see SpatialAcceleration_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialAcceleration, alpha: numpy.ndarray[numpy.float64[3, 1]], a: numpy.ndarray[numpy.float64[3, 1]]) -> None

Constructs a spatial acceleration A from an angular acceleration α (alpha) and a translational acceleration 𝐚.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration, A: numpy.ndarray[numpy.float64[6, 1]]) -> None

Constructs a spatial acceleration A from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular acceleration α and a 3-element translational acceleration 𝐚. This constructor will assert the size of A is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameAcceleration(self: pydrake.multibody.math.SpatialAcceleration, position_of_moving_frame: numpy.ndarray[numpy.float64[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[numpy.float64[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity, acceleration_of_moving_frame: pydrake.multibody.math.SpatialAcceleration) pydrake.multibody.math.SpatialAcceleration

Compose this spatial acceleration (measured in some frame M) with the spatial acceleration of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial acceleration in frame M. Herein, this is the spatial acceleration of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame W and expressed in frame E.

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Parameter acceleration_of_moving_frame:

which is A_BC_E, frame C’s spatial acceleration measured in frame B, expressed in frame E.

Returns A_MC_E:

frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

SpatialVelocity::ComposeWithMovingFrameVelocity(). Use Shift() if frames B and C are both fixed to the same frame or body, i.e., velocity_of_moving_frame = 0 and acceleration_of_moving_frame = 0.

Note

The returned spatial acceleration A_MC_E contains an angular acceleration α_MC_E and translational acceleration a_MCo_E that are calculated as:

Click to expand C++ code...
α_MC_E  = α_MB_E + α_BC_E + ω_MB_E x ω_BC_E
 a_MCo_E = a_BCo_E + α_MB_E x p_BoCo_E + ω_MB_E x (ω_MB_E x p_BoCo_E)
         + 2 ω_MB_E x v_BCo_E + a_BCo_E

If frame C is rigidly fixed to frame B, A_BC_E = 0 and V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). The previous equations show composing spatial acceleration is not simply adding A_MB + A_BC and these equations differ significantly from their spatial velocity counterparts. For example, angular velocities simply add as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC,   but 3D angular acceleration is more complicated as
  α_MC = α_MB + α_BC + ω_MB x ω_BC

** Derivation **

  • Rotational acceleration component *

ω_MC (frame C’s angular velocity in frame M) can be calculated with the angular velocity addition theorem as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC

α_MC (frame C’s angular acceleration measured in frame M) is defined as the time-derivative in frame M of ω_MC, and can be calculated using the “Transport Theorem” (Golden rule for vector differentation) which converts the time-derivative of a vector in frame M to frame B, e.g., as DtM(ω_BC) = DtB(ω_BC) + ω_MB x ω_BC, as

Click to expand C++ code...
α_MC = DtM(ω_MC) = DtM(ω_MB) + DtM(ω_BC)
                   =     α_MB  + DtB(ω_BC) + ω_MB x ω_BC
                   =     α_MB  +     α_BC  + ω_MB x ω_BC   (End of proof).
  • Translational acceleration component *

v_MCo (frame C’s translational velocity in frame M) is calculated in SpatialVelocity::ComposeWithMovingFrameVelocity) as

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo

a_MCo (frame C’s translational acceleration measured in frame M) is defined as the time-derivative in frame M of v_MCo, calculated as

Click to expand C++ code...
a_MCo = DtM(v_MCo)                             Definition.
       = DtM(v_MBo + ω_MB x p_BoCo + v_BCo)     Substitution.
       = DtM(v_MBo) + DtM(ω_MB) x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)
       =     a_MBo  +     α_MB  x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)

The last two terms are modified using the “Transport Theorem” (Golden rule for vector differentation) which converts time-derivatives of vectors in frame M to frame B via DtM(vec) = DtB(vec) + ω_MB x vec.

Click to expand C++ code...
DtM(p_BoCo) = DtB(p_BoCo) + ω_MB x p_BoCo
             =     v_BCo   + ω_MB x p_BoCo
 DtM(v_BCo)  = DtB(v_BCo)  + ω_MB x v_BCo
             =     a_BCo   + ω_MB x v_BCo

Combining the last few equations proves the formula for a_MCo as:

Click to expand C++ code...
a_MCo = a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)
        + 2 ω_MB x v_BCo + a_BCo                           (End of proof).

Some terms in the previous equation have names, e.g.,

Click to expand C++ code...
centripetal acceleration   ω_MB x (ω_MB x p_BoCo)
  Coriolis acceleration    2 ω_MB x v_BCo
  Coincident point acceleration, i.e., acceleration of the point of frame
  B coincident with Co      a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)

Note: The coincident point acceleration can be calculated with a Shift().

Note: The three cross products appearing in the previous calculation of a_MCo can be reduced to one, possibly improving efficiency via

Click to expand C++ code...
ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)

To show this, we rearrange and substitute our expression for v_MCo.

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo        which rearranges to
  ω_MB x p_BoCo = v_MCo - v_MBo - v_BCo.             Substitution produces
  ω_MB x (ω_MB x p_BoCo) = ω_MB x (v_MCo - v_MBo - v_BCo)           Hence,
  ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)
get_coeffs(self: pydrake.multibody.math.SpatialAcceleration) numpy.ndarray[numpy.float64[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialAcceleration, R_FE: pydrake.math.RotationMatrix) pydrake.multibody.math.SpatialAcceleration

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

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

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialAcceleration) pydrake.multibody.math.SpatialAcceleration

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

Shift(self: pydrake.multibody.math.SpatialAcceleration, offset: numpy.ndarray[numpy.float64[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[numpy.float64[3, 1]]) pydrake.multibody.math.SpatialAcceleration

Shifts a SpatialAcceleration from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame M and expressed in frame E.

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how A_MC_E is calculated. Use ComposeWithMovingFrameAcceleration() if frame C is moving on frame B.

ShiftWithZeroAngularVelocity(self: pydrake.multibody.math.SpatialAcceleration, offset: numpy.ndarray[numpy.float64[3, 1]]) pydrake.multibody.math.SpatialAcceleration

(Advanced) Given this spatial acceleration A_MB of a frame B measured in a frame M, shifts SpatialAcceleration from frame B to a frame C (i.e., A_MB to A_MC), where both B and C are fixed to the same frame or rigid body and where ω_MB = 0 (frame B’s angular velocity in frame M is zero).

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

ShiftInPlace() for more information and how A_MC_E is calculated.

Note

ShiftWithZeroAngularVelocity() speeds the Shift() computation when ω_MB = 0, even if α_MB ≠ 0 (α_MB is stored in this).

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

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialAcceleration

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

template pydrake.multibody.math.SpatialAcceleration_

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

class pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

This class represents a spatial acceleration A and has 6 elements with an angular (rotational) acceleration α (3-element vector) on top of a translational (linear) acceleration 𝐚 (3-element vector). Spatial acceleration represents the rotational and translational acceleration of a frame B with respect to a measured-in frame M. This class assumes that both the angular acceleration α and translational acceleration 𝐚 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely α and 𝐚) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, A_MB_E denotes frame B’s spatial acceleration measured in frame M, expressed in frame E and contains alpha_MB_E (B’s angular acceleration measured in M, expressed in E) and a_MBo_E (Bo’s translational acceleration measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation A_MBp_E denotes frame Bp’s spatial acceleration measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for A_MB is \(\,{^MA^B}\) and its definition is \(^MA^B = \frac{^Md}{dt}\,{^MV^B}\,\), where \({^MV^B}\) is frame B’s spatial velocity in frame M and \(\frac{^Md}{dt}\) denotes the time derivative taken in frame M. To differentiate a vector, we need to specify in what frame the time derivative is taken, see [Mitiguy 2022, §7.2] for an in-depth discussion. Time derivatives in different frames are related by the “Transport Theorem”, which in Drake is implemented in drake::math::ConvertTimeDerivativeToOtherFrame(). In source code (monogram) notation, we write A_MB = DtM(V_MB), where DtM() denotes the time derivative in frame M. Details on vector differentiation is in section Dt_multibody_quantities.

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

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], alpha: numpy.ndarray[object[3, 1]], a: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial acceleration A from an angular acceleration α (alpha) and a translational acceleration 𝐚.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], A: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial acceleration A from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular acceleration α and a 3-element translational acceleration 𝐚. This constructor will assert the size of A is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameAcceleration(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], position_of_moving_frame: numpy.ndarray[object[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[object[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], acceleration_of_moving_frame: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

Compose this spatial acceleration (measured in some frame M) with the spatial acceleration of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial acceleration in frame M. Herein, this is the spatial acceleration of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame W and expressed in frame E.

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Parameter acceleration_of_moving_frame:

which is A_BC_E, frame C’s spatial acceleration measured in frame B, expressed in frame E.

Returns A_MC_E:

frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

SpatialVelocity::ComposeWithMovingFrameVelocity(). Use Shift() if frames B and C are both fixed to the same frame or body, i.e., velocity_of_moving_frame = 0 and acceleration_of_moving_frame = 0.

Note

The returned spatial acceleration A_MC_E contains an angular acceleration α_MC_E and translational acceleration a_MCo_E that are calculated as:

Click to expand C++ code...
α_MC_E  = α_MB_E + α_BC_E + ω_MB_E x ω_BC_E
 a_MCo_E = a_BCo_E + α_MB_E x p_BoCo_E + ω_MB_E x (ω_MB_E x p_BoCo_E)
         + 2 ω_MB_E x v_BCo_E + a_BCo_E

If frame C is rigidly fixed to frame B, A_BC_E = 0 and V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). The previous equations show composing spatial acceleration is not simply adding A_MB + A_BC and these equations differ significantly from their spatial velocity counterparts. For example, angular velocities simply add as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC,   but 3D angular acceleration is more complicated as
  α_MC = α_MB + α_BC + ω_MB x ω_BC

** Derivation **

  • Rotational acceleration component *

ω_MC (frame C’s angular velocity in frame M) can be calculated with the angular velocity addition theorem as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC

α_MC (frame C’s angular acceleration measured in frame M) is defined as the time-derivative in frame M of ω_MC, and can be calculated using the “Transport Theorem” (Golden rule for vector differentation) which converts the time-derivative of a vector in frame M to frame B, e.g., as DtM(ω_BC) = DtB(ω_BC) + ω_MB x ω_BC, as

Click to expand C++ code...
α_MC = DtM(ω_MC) = DtM(ω_MB) + DtM(ω_BC)
                   =     α_MB  + DtB(ω_BC) + ω_MB x ω_BC
                   =     α_MB  +     α_BC  + ω_MB x ω_BC   (End of proof).
  • Translational acceleration component *

v_MCo (frame C’s translational velocity in frame M) is calculated in SpatialVelocity::ComposeWithMovingFrameVelocity) as

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo

a_MCo (frame C’s translational acceleration measured in frame M) is defined as the time-derivative in frame M of v_MCo, calculated as

Click to expand C++ code...
a_MCo = DtM(v_MCo)                             Definition.
       = DtM(v_MBo + ω_MB x p_BoCo + v_BCo)     Substitution.
       = DtM(v_MBo) + DtM(ω_MB) x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)
       =     a_MBo  +     α_MB  x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)

The last two terms are modified using the “Transport Theorem” (Golden rule for vector differentation) which converts time-derivatives of vectors in frame M to frame B via DtM(vec) = DtB(vec) + ω_MB x vec.

Click to expand C++ code...
DtM(p_BoCo) = DtB(p_BoCo) + ω_MB x p_BoCo
             =     v_BCo   + ω_MB x p_BoCo
 DtM(v_BCo)  = DtB(v_BCo)  + ω_MB x v_BCo
             =     a_BCo   + ω_MB x v_BCo

Combining the last few equations proves the formula for a_MCo as:

Click to expand C++ code...
a_MCo = a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)
        + 2 ω_MB x v_BCo + a_BCo                           (End of proof).

Some terms in the previous equation have names, e.g.,

Click to expand C++ code...
centripetal acceleration   ω_MB x (ω_MB x p_BoCo)
  Coriolis acceleration    2 ω_MB x v_BCo
  Coincident point acceleration, i.e., acceleration of the point of frame
  B coincident with Co      a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)

Note: The coincident point acceleration can be calculated with a Shift().

Note: The three cross products appearing in the previous calculation of a_MCo can be reduced to one, possibly improving efficiency via

Click to expand C++ code...
ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)

To show this, we rearrange and substitute our expression for v_MCo.

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo        which rearranges to
  ω_MB x p_BoCo = v_MCo - v_MBo - v_BCo.             Substitution produces
  ω_MB x (ω_MB x p_BoCo) = ω_MB x (v_MCo - v_MBo - v_BCo)           Hence,
  ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)
get_coeffs(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], R_FE: pydrake.math.RotationMatrix_[AutoDiffXd]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

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

Shift(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], offset: numpy.ndarray[object[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

Shifts a SpatialAcceleration from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame M and expressed in frame E.

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how A_MC_E is calculated. Use ComposeWithMovingFrameAcceleration() if frame C is moving on frame B.

ShiftWithZeroAngularVelocity(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

(Advanced) Given this spatial acceleration A_MB of a frame B measured in a frame M, shifts SpatialAcceleration from frame B to a frame C (i.e., A_MB to A_MC), where both B and C are fixed to the same frame or rigid body and where ω_MB = 0 (frame B’s angular velocity in frame M is zero).

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

ShiftInPlace() for more information and how A_MC_E is calculated.

Note

ShiftWithZeroAngularVelocity() speeds the Shift() computation when ω_MB = 0, even if α_MB ≠ 0 (α_MB is stored in this).

translational(self: pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]

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

class pydrake.multibody.math.SpatialAcceleration_[Expression]

This class represents a spatial acceleration A and has 6 elements with an angular (rotational) acceleration α (3-element vector) on top of a translational (linear) acceleration 𝐚 (3-element vector). Spatial acceleration represents the rotational and translational acceleration of a frame B with respect to a measured-in frame M. This class assumes that both the angular acceleration α and translational acceleration 𝐚 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely α and 𝐚) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, A_MB_E denotes frame B’s spatial acceleration measured in frame M, expressed in frame E and contains alpha_MB_E (B’s angular acceleration measured in M, expressed in E) and a_MBo_E (Bo’s translational acceleration measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation A_MBp_E denotes frame Bp’s spatial acceleration measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for A_MB is \(\,{^MA^B}\) and its definition is \(^MA^B = \frac{^Md}{dt}\,{^MV^B}\,\), where \({^MV^B}\) is frame B’s spatial velocity in frame M and \(\frac{^Md}{dt}\) denotes the time derivative taken in frame M. To differentiate a vector, we need to specify in what frame the time derivative is taken, see [Mitiguy 2022, §7.2] for an in-depth discussion. Time derivatives in different frames are related by the “Transport Theorem”, which in Drake is implemented in drake::math::ConvertTimeDerivativeToOtherFrame(). In source code (monogram) notation, we write A_MB = DtM(V_MB), where DtM() denotes the time derivative in frame M. Details on vector differentiation is in section Dt_multibody_quantities.

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

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration_[Expression]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialAcceleration_[Expression], alpha: numpy.ndarray[object[3, 1]], a: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial acceleration A from an angular acceleration α (alpha) and a translational acceleration 𝐚.

  1. __init__(self: pydrake.multibody.math.SpatialAcceleration_[Expression], A: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial acceleration A from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular acceleration α and a 3-element translational acceleration 𝐚. This constructor will assert the size of A is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameAcceleration(self: pydrake.multibody.math.SpatialAcceleration_[Expression], position_of_moving_frame: numpy.ndarray[object[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[object[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity_[Expression], acceleration_of_moving_frame: pydrake.multibody.math.SpatialAcceleration_[Expression]) pydrake.multibody.math.SpatialAcceleration_[Expression]

Compose this spatial acceleration (measured in some frame M) with the spatial acceleration of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial acceleration in frame M. Herein, this is the spatial acceleration of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame W and expressed in frame E.

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Parameter acceleration_of_moving_frame:

which is A_BC_E, frame C’s spatial acceleration measured in frame B, expressed in frame E.

Returns A_MC_E:

frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

SpatialVelocity::ComposeWithMovingFrameVelocity(). Use Shift() if frames B and C are both fixed to the same frame or body, i.e., velocity_of_moving_frame = 0 and acceleration_of_moving_frame = 0.

Note

The returned spatial acceleration A_MC_E contains an angular acceleration α_MC_E and translational acceleration a_MCo_E that are calculated as:

Click to expand C++ code...
α_MC_E  = α_MB_E + α_BC_E + ω_MB_E x ω_BC_E
 a_MCo_E = a_BCo_E + α_MB_E x p_BoCo_E + ω_MB_E x (ω_MB_E x p_BoCo_E)
         + 2 ω_MB_E x v_BCo_E + a_BCo_E

If frame C is rigidly fixed to frame B, A_BC_E = 0 and V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). The previous equations show composing spatial acceleration is not simply adding A_MB + A_BC and these equations differ significantly from their spatial velocity counterparts. For example, angular velocities simply add as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC,   but 3D angular acceleration is more complicated as
  α_MC = α_MB + α_BC + ω_MB x ω_BC

** Derivation **

  • Rotational acceleration component *

ω_MC (frame C’s angular velocity in frame M) can be calculated with the angular velocity addition theorem as

Click to expand C++ code...
ω_MC = ω_MB + ω_BC

α_MC (frame C’s angular acceleration measured in frame M) is defined as the time-derivative in frame M of ω_MC, and can be calculated using the “Transport Theorem” (Golden rule for vector differentation) which converts the time-derivative of a vector in frame M to frame B, e.g., as DtM(ω_BC) = DtB(ω_BC) + ω_MB x ω_BC, as

Click to expand C++ code...
α_MC = DtM(ω_MC) = DtM(ω_MB) + DtM(ω_BC)
                   =     α_MB  + DtB(ω_BC) + ω_MB x ω_BC
                   =     α_MB  +     α_BC  + ω_MB x ω_BC   (End of proof).
  • Translational acceleration component *

v_MCo (frame C’s translational velocity in frame M) is calculated in SpatialVelocity::ComposeWithMovingFrameVelocity) as

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo

a_MCo (frame C’s translational acceleration measured in frame M) is defined as the time-derivative in frame M of v_MCo, calculated as

Click to expand C++ code...
a_MCo = DtM(v_MCo)                             Definition.
       = DtM(v_MBo + ω_MB x p_BoCo + v_BCo)     Substitution.
       = DtM(v_MBo) + DtM(ω_MB) x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)
       =     a_MBo  +     α_MB  x p_BoCo + ω_MB x DtM(p_BoCo) + DtM(v_BCo)

The last two terms are modified using the “Transport Theorem” (Golden rule for vector differentation) which converts time-derivatives of vectors in frame M to frame B via DtM(vec) = DtB(vec) + ω_MB x vec.

Click to expand C++ code...
DtM(p_BoCo) = DtB(p_BoCo) + ω_MB x p_BoCo
             =     v_BCo   + ω_MB x p_BoCo
 DtM(v_BCo)  = DtB(v_BCo)  + ω_MB x v_BCo
             =     a_BCo   + ω_MB x v_BCo

Combining the last few equations proves the formula for a_MCo as:

Click to expand C++ code...
a_MCo = a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)
        + 2 ω_MB x v_BCo + a_BCo                           (End of proof).

Some terms in the previous equation have names, e.g.,

Click to expand C++ code...
centripetal acceleration   ω_MB x (ω_MB x p_BoCo)
  Coriolis acceleration    2 ω_MB x v_BCo
  Coincident point acceleration, i.e., acceleration of the point of frame
  B coincident with Co      a_MBo + α_MB x p_BoCo + ω_MB x (ω_MB x p_BoCo)

Note: The coincident point acceleration can be calculated with a Shift().

Note: The three cross products appearing in the previous calculation of a_MCo can be reduced to one, possibly improving efficiency via

Click to expand C++ code...
ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)

To show this, we rearrange and substitute our expression for v_MCo.

Click to expand C++ code...
v_MCo = v_MBo + ω_MB x p_BoCo + v_BCo        which rearranges to
  ω_MB x p_BoCo = v_MCo - v_MBo - v_BCo.             Substitution produces
  ω_MB x (ω_MB x p_BoCo) = ω_MB x (v_MCo - v_MBo - v_BCo)           Hence,
  ω_MB x (ω_MB x p_BoCo) + 2 ω_MB x v_BCo = ω_MB x (v_MCo - v_MBo + v_BCo)
get_coeffs(self: pydrake.multibody.math.SpatialAcceleration_[Expression]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialAcceleration_[Expression], R_FE: pydrake.math.RotationMatrix_[Expression]) pydrake.multibody.math.SpatialAcceleration_[Expression]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialAcceleration_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialAcceleration_[Expression]) pydrake.multibody.math.SpatialAcceleration_[Expression]

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

Shift(self: pydrake.multibody.math.SpatialAcceleration_[Expression], offset: numpy.ndarray[object[3, 1]], angular_velocity_of_this_frame: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialAcceleration_[Expression]

Shifts a SpatialAcceleration from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Parameter angular_velocity_of_this_frame:

which is ω_MB_E, frame B’s angular velocity measured in frame M and expressed in frame E.

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how A_MC_E is calculated. Use ComposeWithMovingFrameAcceleration() if frame C is moving on frame B.

ShiftWithZeroAngularVelocity(self: pydrake.multibody.math.SpatialAcceleration_[Expression], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialAcceleration_[Expression]

(Advanced) Given this spatial acceleration A_MB of a frame B measured in a frame M, shifts SpatialAcceleration from frame B to a frame C (i.e., A_MB to A_MC), where both B and C are fixed to the same frame or rigid body and where ω_MB = 0 (frame B’s angular velocity in frame M is zero).

Parameter offset:

which is the position vector p_BoCo_E from Bo (frame B’s origin) to Co (frame C’s origin), expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial acceleration, where this is A_MB_E (frame B’s spatial acceleration measured in M, expressed in E).

Returns A_MC_E:

which is frame C’s spatial acceleration measured in frame M, expressed in frame E.

See also

ShiftInPlace() for more information and how A_MC_E is calculated.

Note

ShiftWithZeroAngularVelocity() speeds the Shift() computation when ω_MB = 0, even if α_MB ≠ 0 (α_MB is stored in this).

translational(self: pydrake.multibody.math.SpatialAcceleration_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialAcceleration_[Expression]

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

class pydrake.multibody.math.SpatialForce

This class represents a spatial force F (also called a wrench) and has 6 elements with a torque 𝛕 (3-element vector) on top of a force 𝐟 (3-element vector). Frequently, a spatial force represents the replacement of a set S of forces on a frame B with an equivalent set consisting of a torque 𝛕 applied to frame B which is equal to the moment of the set S about a point Bp of B together with a force 𝐟 applied to Bp, where 𝐟 is equal to set S’s resultant force. This class assumes that both the torque 𝛕 and force 𝐟 have the same expressed-in frame E. This class only stores 6 elements (namely 𝛕 and 𝐟) and does not store the underlying frame B, application point Bp, or expressed-in frame E. The user is responsible for explicitly tracking these underlying quantities with multibody_quantities “monogram notation”. For example, F_B_E denotes a spatial force on frame B with application point Bo (frame B’s origin), expressed in frame E and contains tau_B_E (torque 𝛕 applied to frame B, expressed in frame E) and f_Bo_E (force 𝐟 applied to Bo, expressed in frame E).

The monogram notation F_Bp has a typeset equivalent \({F^{Bp}}\) which denotes the spatial force applied to point Bp of frame B. F_Bp contains a torque tau_B (\({\tau^B}\)) applied to frame B and a force f_Bp (\({f^{Bp}}\)) applied to point Bp of frame B. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

Note

This class is templated; see SpatialForce_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialForce) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialForce, tau: numpy.ndarray[numpy.float64[3, 1]], f: numpy.ndarray[numpy.float64[3, 1]]) -> None

Constructs a spatial force F from a torque 𝛕 (tau) and a force 𝐟.

  1. __init__(self: pydrake.multibody.math.SpatialForce, F: numpy.ndarray[numpy.float64[6, 1]]) -> None

Constructs a spatial force F from an Eigen expression that represents a 6-element vector, i.e., a 3-element torque 𝛕 and a 3-element force 𝐟. This constructor will assert the size of F is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialForce, velocity: pydrake.multibody.math.SpatialVelocity) float

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = F_B_E (frame B’s spatial force, expressed in frame E) with V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E).

Parameter velocity:

which is V_MB_E, frame B’s spatial velocity measured in frame M, expressed in the same frame E as this = F_B_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

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

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialForce, R_FE: pydrake.math.RotationMatrix) pydrake.multibody.math.SpatialForce

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

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

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialForce) pydrake.multibody.math.SpatialForce

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

Shift(self: pydrake.multibody.math.SpatialForce, offset: numpy.ndarray[numpy.float64[3, 1]]) pydrake.multibody.math.SpatialForce

Shifts a SpatialForce from one point fixed on frame B to another point fixed on frame B.

Parameter offset:

which is the position vector p_BpBq_E from point Bp (fixed on frame B) to point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as this spatial force, where this is F_Bp_E (spatial force on Bp, expressed in frame E).

Returns F_Bq_E:

which is the spatial force on Bq, expressed in frame E.

See also

Member function ShiftInPlace() to shift one spatial force (modifying this) and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).

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

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialForce

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

template pydrake.multibody.math.SpatialForce_

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

class pydrake.multibody.math.SpatialForce_[AutoDiffXd]

This class represents a spatial force F (also called a wrench) and has 6 elements with a torque 𝛕 (3-element vector) on top of a force 𝐟 (3-element vector). Frequently, a spatial force represents the replacement of a set S of forces on a frame B with an equivalent set consisting of a torque 𝛕 applied to frame B which is equal to the moment of the set S about a point Bp of B together with a force 𝐟 applied to Bp, where 𝐟 is equal to set S’s resultant force. This class assumes that both the torque 𝛕 and force 𝐟 have the same expressed-in frame E. This class only stores 6 elements (namely 𝛕 and 𝐟) and does not store the underlying frame B, application point Bp, or expressed-in frame E. The user is responsible for explicitly tracking these underlying quantities with multibody_quantities “monogram notation”. For example, F_B_E denotes a spatial force on frame B with application point Bo (frame B’s origin), expressed in frame E and contains tau_B_E (torque 𝛕 applied to frame B, expressed in frame E) and f_Bo_E (force 𝐟 applied to Bo, expressed in frame E).

The monogram notation F_Bp has a typeset equivalent \({F^{Bp}}\) which denotes the spatial force applied to point Bp of frame B. F_Bp contains a torque tau_B (\({\tau^B}\)) applied to frame B and a force f_Bp (\({f^{Bp}}\)) applied to point Bp of frame B. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd], tau: numpy.ndarray[object[3, 1]], f: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial force F from a torque 𝛕 (tau) and a force 𝐟.

  1. __init__(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd], F: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial force F from an Eigen expression that represents a 6-element vector, i.e., a 3-element torque 𝛕 and a 3-element force 𝐟. This constructor will assert the size of F is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd], velocity: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = F_B_E (frame B’s spatial force, expressed in frame E) with V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E).

Parameter velocity:

which is V_MB_E, frame B’s spatial velocity measured in frame M, expressed in the same frame E as this = F_B_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

get_coeffs(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd], R_FE: pydrake.math.RotationMatrix_[AutoDiffXd]) pydrake.multibody.math.SpatialForce_[AutoDiffXd]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd]) pydrake.multibody.math.SpatialForce_[AutoDiffXd]

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

Shift(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialForce_[AutoDiffXd]

Shifts a SpatialForce from one point fixed on frame B to another point fixed on frame B.

Parameter offset:

which is the position vector p_BpBq_E from point Bp (fixed on frame B) to point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as this spatial force, where this is F_Bp_E (spatial force on Bp, expressed in frame E).

Returns F_Bq_E:

which is the spatial force on Bq, expressed in frame E.

See also

Member function ShiftInPlace() to shift one spatial force (modifying this) and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).

translational(self: pydrake.multibody.math.SpatialForce_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialForce_[AutoDiffXd]

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

class pydrake.multibody.math.SpatialForce_[Expression]

This class represents a spatial force F (also called a wrench) and has 6 elements with a torque 𝛕 (3-element vector) on top of a force 𝐟 (3-element vector). Frequently, a spatial force represents the replacement of a set S of forces on a frame B with an equivalent set consisting of a torque 𝛕 applied to frame B which is equal to the moment of the set S about a point Bp of B together with a force 𝐟 applied to Bp, where 𝐟 is equal to set S’s resultant force. This class assumes that both the torque 𝛕 and force 𝐟 have the same expressed-in frame E. This class only stores 6 elements (namely 𝛕 and 𝐟) and does not store the underlying frame B, application point Bp, or expressed-in frame E. The user is responsible for explicitly tracking these underlying quantities with multibody_quantities “monogram notation”. For example, F_B_E denotes a spatial force on frame B with application point Bo (frame B’s origin), expressed in frame E and contains tau_B_E (torque 𝛕 applied to frame B, expressed in frame E) and f_Bo_E (force 𝐟 applied to Bo, expressed in frame E).

The monogram notation F_Bp has a typeset equivalent \({F^{Bp}}\) which denotes the spatial force applied to point Bp of frame B. F_Bp contains a torque tau_B (\({\tau^B}\)) applied to frame B and a force f_Bp (\({f^{Bp}}\)) applied to point Bp of frame B. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialForce_[Expression]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialForce_[Expression], tau: numpy.ndarray[object[3, 1]], f: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial force F from a torque 𝛕 (tau) and a force 𝐟.

  1. __init__(self: pydrake.multibody.math.SpatialForce_[Expression], F: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial force F from an Eigen expression that represents a 6-element vector, i.e., a 3-element torque 𝛕 and a 3-element force 𝐟. This constructor will assert the size of F is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialForce_[Expression], velocity: pydrake.multibody.math.SpatialVelocity_[Expression]) pydrake.symbolic.Expression

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = F_B_E (frame B’s spatial force, expressed in frame E) with V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E).

Parameter velocity:

which is V_MB_E, frame B’s spatial velocity measured in frame M, expressed in the same frame E as this = F_B_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

get_coeffs(self: pydrake.multibody.math.SpatialForce_[Expression]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialForce_[Expression], R_FE: pydrake.math.RotationMatrix_[Expression]) pydrake.multibody.math.SpatialForce_[Expression]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialForce_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialForce_[Expression]) pydrake.multibody.math.SpatialForce_[Expression]

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

Shift(self: pydrake.multibody.math.SpatialForce_[Expression], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialForce_[Expression]

Shifts a SpatialForce from one point fixed on frame B to another point fixed on frame B.

Parameter offset:

which is the position vector p_BpBq_E from point Bp (fixed on frame B) to point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as this spatial force, where this is F_Bp_E (spatial force on Bp, expressed in frame E).

Returns F_Bq_E:

which is the spatial force on Bq, expressed in frame E.

See also

Member function ShiftInPlace() to shift one spatial force (modifying this) and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).

translational(self: pydrake.multibody.math.SpatialForce_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialForce_[Expression]

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

class pydrake.multibody.math.SpatialMomentum

This class represents a spatial momentum L and has 6 elements with an angular (rotational) momentum 𝐡 (3-element vector) on top of a translational (linear) momentum 𝐥 (3-element vector). A spatial momentum L stores the angular momentum 𝐡 and translational momentum 𝐥 of a system S about a point P, measured in a frame M, and expressed in a frame E. The system S may be a particle, a rigid or deformable body, or a set of particles and/or bodies. This class assumes that both the angular momentum 𝐡 and translational momentum 𝐥 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely 𝐡 and 𝐥) and does not store the underlying system S, about-point P, measured-in frame M, or expressed-in frame E. The user is responsible for explicitly tracking the underlying system, about-point, and frames with multibody_quantities “monogram notation”. For example, L_MSP_E denotes a system S’s spatial momentum about point P, measured in frame M, and expressed in frame E. L_MSP_E contains h_MSP_E (S’s angular momentum about point P, measured in M, expressed in E) and l_MS_E (S’s translational momentum measured in M, expressed in E). A body B’s spatial momentum about point Bo (B’s origin), measured in frame M, expressed in frame E has explicit monogram notation L_MBBo_E which can be abbreviated L_MBo_E. Similarly L_MSScm_E is abbreviated L_MScm_E (Scm is S’s center of mass). Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for L_MSP_E is \([^ML^{S/P}]_E\). For a set S of particles Qᵢ, L_MSP contains S’s angular momentum 𝐡 about-point P, measured in frame M and S’s translational momentum 𝐥 measured in frame M, defined as

Click to expand C++ code...
h_MSP = ∑ h_MQᵢP = ∑ p_PQᵢ x l_MQᵢ  where l_MQᵢ = mᵢ v_MQᵢ.
  l_MS  = ∑ l_MQᵢ  = ∑ mᵢ v_MQᵢ

where mᵢ is the mass of particle Qᵢ, v_MQᵢ is Qᵢ’s translational velocity measured in frame M, l_MQᵢ = mᵢ v_MQQᵢ is Qᵢ’s translational momentum measured in frame M, h_MQᵢP is Qᵢ’s angular momentum about point P measured in frame M, and p_PQᵢ is the position vector from point P to Qᵢ. These definitions extend to a body (continuum of particles) by using the density ρ(r) of the body at each material location r as:

Click to expand C++ code...
h_MSP = ∫p_PQ(r) x v_MQ(r) ρ(r) d³r
  l_MS  = ∫v_MQ(r) ρ(r) d³r

Note

This class is templated; see SpatialMomentum_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialMomentum, h: numpy.ndarray[numpy.float64[3, 1]], l: numpy.ndarray[numpy.float64[3, 1]]) -> None

Constructs a spatial momentum L from an angular momentum 𝐡 and a translational momentum 𝐥.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum, L: numpy.ndarray[numpy.float64[6, 1]]) -> None

Constructs a spatial momentum L from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular momentum 𝐡 and a 3-element translational momentum 𝐥. This constructor will assert the size of L is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialMomentum, velocity: pydrake.multibody.math.SpatialVelocity) float

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E) with V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E).

Parameter velocity:

which is V_MBp_E, frame Bp’s spatial velocity measured in frame M, and expressed in the same frame E as this = L_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialMomentum) numpy.ndarray[numpy.float64[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialMomentum, R_FE: pydrake.math.RotationMatrix) pydrake.multibody.math.SpatialMomentum

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

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

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialMomentum) pydrake.multibody.math.SpatialMomentum

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

Shift(self: pydrake.multibody.math.SpatialMomentum, offset: numpy.ndarray[numpy.float64[3, 1]]) pydrake.multibody.math.SpatialMomentum

Shifts a SpatialMomentum from an about-point P to an about-point Q.

Parameter offset:

which is the position vector p_PQ_E from point P to point Q, expressed in frame E. p_PQ_E must have the same expressed-in frame E as this spatial momentum, where this is L_MSP_E (system S’s spatial momentum about P, measured in frame M, expressed in frame E).

Returns L_MSQ_E:

which is system S’s spatial momentum about point Q, measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how L_MSQ_E is calculated.

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

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialMomentum

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

template pydrake.multibody.math.SpatialMomentum_

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

class pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]

This class represents a spatial momentum L and has 6 elements with an angular (rotational) momentum 𝐡 (3-element vector) on top of a translational (linear) momentum 𝐥 (3-element vector). A spatial momentum L stores the angular momentum 𝐡 and translational momentum 𝐥 of a system S about a point P, measured in a frame M, and expressed in a frame E. The system S may be a particle, a rigid or deformable body, or a set of particles and/or bodies. This class assumes that both the angular momentum 𝐡 and translational momentum 𝐥 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely 𝐡 and 𝐥) and does not store the underlying system S, about-point P, measured-in frame M, or expressed-in frame E. The user is responsible for explicitly tracking the underlying system, about-point, and frames with multibody_quantities “monogram notation”. For example, L_MSP_E denotes a system S’s spatial momentum about point P, measured in frame M, and expressed in frame E. L_MSP_E contains h_MSP_E (S’s angular momentum about point P, measured in M, expressed in E) and l_MS_E (S’s translational momentum measured in M, expressed in E). A body B’s spatial momentum about point Bo (B’s origin), measured in frame M, expressed in frame E has explicit monogram notation L_MBBo_E which can be abbreviated L_MBo_E. Similarly L_MSScm_E is abbreviated L_MScm_E (Scm is S’s center of mass). Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for L_MSP_E is \([^ML^{S/P}]_E\). For a set S of particles Qᵢ, L_MSP contains S’s angular momentum 𝐡 about-point P, measured in frame M and S’s translational momentum 𝐥 measured in frame M, defined as

Click to expand C++ code...
h_MSP = ∑ h_MQᵢP = ∑ p_PQᵢ x l_MQᵢ  where l_MQᵢ = mᵢ v_MQᵢ.
  l_MS  = ∑ l_MQᵢ  = ∑ mᵢ v_MQᵢ

where mᵢ is the mass of particle Qᵢ, v_MQᵢ is Qᵢ’s translational velocity measured in frame M, l_MQᵢ = mᵢ v_MQQᵢ is Qᵢ’s translational momentum measured in frame M, h_MQᵢP is Qᵢ’s angular momentum about point P measured in frame M, and p_PQᵢ is the position vector from point P to Qᵢ. These definitions extend to a body (continuum of particles) by using the density ρ(r) of the body at each material location r as:

Click to expand C++ code...
h_MSP = ∫p_PQ(r) x v_MQ(r) ρ(r) d³r
  l_MS  = ∫v_MQ(r) ρ(r) d³r
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd], h: numpy.ndarray[object[3, 1]], l: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial momentum L from an angular momentum 𝐡 and a translational momentum 𝐥.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd], L: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial momentum L from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular momentum 𝐡 and a 3-element translational momentum 𝐥. This constructor will assert the size of L is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd], velocity: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E) with V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E).

Parameter velocity:

which is V_MBp_E, frame Bp’s spatial velocity measured in frame M, and expressed in the same frame E as this = L_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd], R_FE: pydrake.math.RotationMatrix_[AutoDiffXd]) pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]) pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]

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

Shift(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]

Shifts a SpatialMomentum from an about-point P to an about-point Q.

Parameter offset:

which is the position vector p_PQ_E from point P to point Q, expressed in frame E. p_PQ_E must have the same expressed-in frame E as this spatial momentum, where this is L_MSP_E (system S’s spatial momentum about P, measured in frame M, expressed in frame E).

Returns L_MSQ_E:

which is system S’s spatial momentum about point Q, measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how L_MSQ_E is calculated.

translational(self: pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]

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

class pydrake.multibody.math.SpatialMomentum_[Expression]

This class represents a spatial momentum L and has 6 elements with an angular (rotational) momentum 𝐡 (3-element vector) on top of a translational (linear) momentum 𝐥 (3-element vector). A spatial momentum L stores the angular momentum 𝐡 and translational momentum 𝐥 of a system S about a point P, measured in a frame M, and expressed in a frame E. The system S may be a particle, a rigid or deformable body, or a set of particles and/or bodies. This class assumes that both the angular momentum 𝐡 and translational momentum 𝐥 are expressed in the same expressed-in frame E. This class only stores 6 elements (namely 𝐡 and 𝐥) and does not store the underlying system S, about-point P, measured-in frame M, or expressed-in frame E. The user is responsible for explicitly tracking the underlying system, about-point, and frames with multibody_quantities “monogram notation”. For example, L_MSP_E denotes a system S’s spatial momentum about point P, measured in frame M, and expressed in frame E. L_MSP_E contains h_MSP_E (S’s angular momentum about point P, measured in M, expressed in E) and l_MS_E (S’s translational momentum measured in M, expressed in E). A body B’s spatial momentum about point Bo (B’s origin), measured in frame M, expressed in frame E has explicit monogram notation L_MBBo_E which can be abbreviated L_MBo_E. Similarly L_MSScm_E is abbreviated L_MScm_E (Scm is S’s center of mass). Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

The typeset for L_MSP_E is \([^ML^{S/P}]_E\). For a set S of particles Qᵢ, L_MSP contains S’s angular momentum 𝐡 about-point P, measured in frame M and S’s translational momentum 𝐥 measured in frame M, defined as

Click to expand C++ code...
h_MSP = ∑ h_MQᵢP = ∑ p_PQᵢ x l_MQᵢ  where l_MQᵢ = mᵢ v_MQᵢ.
  l_MS  = ∑ l_MQᵢ  = ∑ mᵢ v_MQᵢ

where mᵢ is the mass of particle Qᵢ, v_MQᵢ is Qᵢ’s translational velocity measured in frame M, l_MQᵢ = mᵢ v_MQQᵢ is Qᵢ’s translational momentum measured in frame M, h_MQᵢP is Qᵢ’s angular momentum about point P measured in frame M, and p_PQᵢ is the position vector from point P to Qᵢ. These definitions extend to a body (continuum of particles) by using the density ρ(r) of the body at each material location r as:

Click to expand C++ code...
h_MSP = ∫p_PQ(r) x v_MQ(r) ρ(r) d³r
  l_MS  = ∫v_MQ(r) ρ(r) d³r
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum_[Expression]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialMomentum_[Expression], h: numpy.ndarray[object[3, 1]], l: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial momentum L from an angular momentum 𝐡 and a translational momentum 𝐥.

  1. __init__(self: pydrake.multibody.math.SpatialMomentum_[Expression], L: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial momentum L from an Eigen expression that represents a 6-element vector, i.e., a 3-element angular momentum 𝐡 and a 3-element translational momentum 𝐥. This constructor will assert the size of L is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

dot(self: pydrake.multibody.math.SpatialMomentum_[Expression], velocity: pydrake.multibody.math.SpatialVelocity_[Expression]) pydrake.symbolic.Expression

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E) with V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E).

Parameter velocity:

which is V_MBp_E, frame Bp’s spatial velocity measured in frame M, and expressed in the same frame E as this = L_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialMomentum_[Expression]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialMomentum_[Expression], R_FE: pydrake.math.RotationMatrix_[Expression]) pydrake.multibody.math.SpatialMomentum_[Expression]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialMomentum_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialMomentum_[Expression]) pydrake.multibody.math.SpatialMomentum_[Expression]

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

Shift(self: pydrake.multibody.math.SpatialMomentum_[Expression], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialMomentum_[Expression]

Shifts a SpatialMomentum from an about-point P to an about-point Q.

Parameter offset:

which is the position vector p_PQ_E from point P to point Q, expressed in frame E. p_PQ_E must have the same expressed-in frame E as this spatial momentum, where this is L_MSP_E (system S’s spatial momentum about P, measured in frame M, expressed in frame E).

Returns L_MSQ_E:

which is system S’s spatial momentum about point Q, measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how L_MSQ_E is calculated.

translational(self: pydrake.multibody.math.SpatialMomentum_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialMomentum_[Expression]

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

class pydrake.multibody.math.SpatialVelocity

This class represents a spatial velocity V (also called a twist) and has 6 elements with an angular (rotational) velocity ω (3-element vector) on top of a translational (linear) velocity v (3-element vector). Spatial velocity represents the rotational and translational motion of a frame B with respect to a measured-in frame M. This class assumes that both the angular velocity ω and translational velocity v are expressed in the same expressed-in frame E. This class only stores 6 elements (namely ω and v) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, V_MB_E denotes frame B’s spatial velocity measured in frame M, expressed in frame E and contains ω_MB_E (B’s angular velocity measured in M, expressed in E) and v_MBo_E (Bo’s translational velocity measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation V_MBp_E denotes the spatial velocity of frame Bp measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

Note

This class is templated; see SpatialVelocity_ for the list of instantiations.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialVelocity, w: numpy.ndarray[numpy.float64[3, 1]], v: numpy.ndarray[numpy.float64[3, 1]]) -> None

Constructs a spatial velocity V from an angular velocity ω and a translational velocity v.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity, V: numpy.ndarray[numpy.float64[6, 1]]) -> None

Constructs a spatial velocity V from an Eigen expression that represents a 6-element vector, i.e., two 3-element vectors, namely an angular velocity ω and a translational velocity v. This constructor will assert the size of V is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameVelocity(self: pydrake.multibody.math.SpatialVelocity, position_of_moving_frame: numpy.ndarray[numpy.float64[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity) pydrake.multibody.math.SpatialVelocity

Compose this spatial velocity (measured in some frame M) with the spatial velocity of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial velocity measured in frame M. Herein, this is the spatial velocity of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in a frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is V_MB_E (frame B’s spatial velocity measured in M, expressed in E).

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Returns V_MC_E:

frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

The returned spatial velocity V_MC_E contains an angular velocity ω_MC_E and translational velocity v_MCo_E that are calculated as:

Click to expand C++ code...
ω_MC_E  = ω_MB_E + ω_BC_E
 v_MCo_E = v_MBo_E + ω_MB_E x p_BoCo_E + v_BCo_E

If frame C is rigidly fixed to frame B, V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). In other words, use Shift() if velocity_of_moving_frame = 0.

See also

SpatialAcceleration::ComposeWithMovingFrameAcceleration().

dot(*args, **kwargs)

Overloaded function.

  1. dot(self: pydrake.multibody.math.SpatialVelocity, force: drake::multibody::SpatialForce<double>) -> float

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E) with F_B_E (frame B’s spatial force, expressed in frame E).

Parameter force:

which is F_B_E, frame B’s spatial force, expressed in the same frame E as this = V_MB_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

  1. dot(self: pydrake.multibody.math.SpatialVelocity, momentum: drake::multibody::SpatialMomentum<double>) -> float

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E) with L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E).

Parameter momentum:

which is L_MBp_E, body B’s spatial momentum measured in frame M, about frame Bp’s origin, expressed in the same frame E as this = V_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialVelocity) numpy.ndarray[numpy.float64[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialVelocity, R_FE: pydrake.math.RotationMatrix) pydrake.multibody.math.SpatialVelocity

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

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

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialVelocity) pydrake.multibody.math.SpatialVelocity

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

Shift(self: pydrake.multibody.math.SpatialVelocity, offset: numpy.ndarray[numpy.float64[3, 1]]) pydrake.multibody.math.SpatialVelocity

Shifts a SpatialVelocity from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from frame B’s origin to frame C’s origin, expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial velocity (this = V_MB_E).

Returns V_MC_E:

which is frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how V_MC_E is calculated.

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

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialVelocity

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

template pydrake.multibody.math.SpatialVelocity_

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

class pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

This class represents a spatial velocity V (also called a twist) and has 6 elements with an angular (rotational) velocity ω (3-element vector) on top of a translational (linear) velocity v (3-element vector). Spatial velocity represents the rotational and translational motion of a frame B with respect to a measured-in frame M. This class assumes that both the angular velocity ω and translational velocity v are expressed in the same expressed-in frame E. This class only stores 6 elements (namely ω and v) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, V_MB_E denotes frame B’s spatial velocity measured in frame M, expressed in frame E and contains ω_MB_E (B’s angular velocity measured in M, expressed in E) and v_MBo_E (Bo’s translational velocity measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation V_MBp_E denotes the spatial velocity of frame Bp measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], w: numpy.ndarray[object[3, 1]], v: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial velocity V from an angular velocity ω and a translational velocity v.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], V: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial velocity V from an Eigen expression that represents a 6-element vector, i.e., two 3-element vectors, namely an angular velocity ω and a translational velocity v. This constructor will assert the size of V is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameVelocity(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], position_of_moving_frame: numpy.ndarray[object[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

Compose this spatial velocity (measured in some frame M) with the spatial velocity of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial velocity measured in frame M. Herein, this is the spatial velocity of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in a frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is V_MB_E (frame B’s spatial velocity measured in M, expressed in E).

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Returns V_MC_E:

frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

The returned spatial velocity V_MC_E contains an angular velocity ω_MC_E and translational velocity v_MCo_E that are calculated as:

Click to expand C++ code...
ω_MC_E  = ω_MB_E + ω_BC_E
 v_MCo_E = v_MBo_E + ω_MB_E x p_BoCo_E + v_BCo_E

If frame C is rigidly fixed to frame B, V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). In other words, use Shift() if velocity_of_moving_frame = 0.

See also

SpatialAcceleration::ComposeWithMovingFrameAcceleration().

dot(*args, **kwargs)

Overloaded function.

  1. dot(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], force: drake::multibody::SpatialForce<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >) -> pydrake.autodiffutils.AutoDiffXd

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E) with F_B_E (frame B’s spatial force, expressed in frame E).

Parameter force:

which is F_B_E, frame B’s spatial force, expressed in the same frame E as this = V_MB_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

  1. dot(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], momentum: drake::multibody::SpatialMomentum<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >) -> pydrake.autodiffutils.AutoDiffXd

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E) with L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E).

Parameter momentum:

which is L_MBp_E, body B’s spatial momentum measured in frame M, about frame Bp’s origin, expressed in the same frame E as this = V_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], R_FE: pydrake.math.RotationMatrix_[AutoDiffXd]) pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

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

Shift(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

Shifts a SpatialVelocity from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from frame B’s origin to frame C’s origin, expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial velocity (this = V_MB_E).

Returns V_MC_E:

which is frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how V_MC_E is calculated.

translational(self: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]

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

class pydrake.multibody.math.SpatialVelocity_[Expression]

This class represents a spatial velocity V (also called a twist) and has 6 elements with an angular (rotational) velocity ω (3-element vector) on top of a translational (linear) velocity v (3-element vector). Spatial velocity represents the rotational and translational motion of a frame B with respect to a measured-in frame M. This class assumes that both the angular velocity ω and translational velocity v are expressed in the same expressed-in frame E. This class only stores 6 elements (namely ω and v) and does not store the underlying frames B, M, E. The user is responsible for explicitly tracking the underlying frames with multibody_quantities “monogram notation”. For example, V_MB_E denotes frame B’s spatial velocity measured in frame M, expressed in frame E and contains ω_MB_E (B’s angular velocity measured in M, expressed in E) and v_MBo_E (Bo’s translational velocity measured in M, expressed in E), where Bo is frame B’s origin point. For an multibody_frames_and_bodies “offset frame” Bp, the monogram notation V_MBp_E denotes the spatial velocity of frame Bp measured in M, expressed in E. Details on spatial vectors and monogram notation are in sections multibody_spatial_vectors and multibody_quantities.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity_[Expression]) -> None

    Constructs to all NaNs.

    Note:

    This is different from C++, which in Release builds may leave memory uninitialized. In pydrake, the function call overhead already trumps any overhead from NAN-initialization, so we err on the side of safety.

  2. __init__(self: pydrake.multibody.math.SpatialVelocity_[Expression], w: numpy.ndarray[object[3, 1]], v: numpy.ndarray[object[3, 1]]) -> None

Constructs a spatial velocity V from an angular velocity ω and a translational velocity v.

  1. __init__(self: pydrake.multibody.math.SpatialVelocity_[Expression], V: numpy.ndarray[object[6, 1]]) -> None

Constructs a spatial velocity V from an Eigen expression that represents a 6-element vector, i.e., two 3-element vectors, namely an angular velocity ω and a translational velocity v. This constructor will assert the size of V is six (6) either at compile-time for fixed sized Eigen expressions or at run-time for dynamic sized Eigen expressions.

ComposeWithMovingFrameVelocity(self: pydrake.multibody.math.SpatialVelocity_[Expression], position_of_moving_frame: numpy.ndarray[object[3, 1]], velocity_of_moving_frame: pydrake.multibody.math.SpatialVelocity_[Expression]) pydrake.multibody.math.SpatialVelocity_[Expression]

Compose this spatial velocity (measured in some frame M) with the spatial velocity of another frame to form the 𝐨𝐭𝐡𝐞𝐫 frame’s spatial velocity measured in frame M. Herein, this is the spatial velocity of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameter position_of_moving_frame:

which is the position vector p_BoCo_E (from frame B’s origin Bo to frame C’s origin Co), expressed in a frame E. p_BoCo_E must have the same expressed-in frame E as this, where this is V_MB_E (frame B’s spatial velocity measured in M, expressed in E).

Parameter velocity_of_moving_frame:

which is V_BC_E, frame C’s spatial velocity measured in frame B, expressed in frame E.

Returns V_MC_E:

frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

The returned spatial velocity V_MC_E contains an angular velocity ω_MC_E and translational velocity v_MCo_E that are calculated as:

Click to expand C++ code...
ω_MC_E  = ω_MB_E + ω_BC_E
 v_MCo_E = v_MBo_E + ω_MB_E x p_BoCo_E + v_BCo_E

If frame C is rigidly fixed to frame B, V_BC_E = 0 and this method produces a Shift() operation (albeit inefficiently). In other words, use Shift() if velocity_of_moving_frame = 0.

See also

SpatialAcceleration::ComposeWithMovingFrameAcceleration().

dot(*args, **kwargs)

Overloaded function.

  1. dot(self: pydrake.multibody.math.SpatialVelocity_[Expression], force: drake::multibody::SpatialForce<drake::symbolic::Expression>) -> pydrake.symbolic.Expression

Calculates the power generated by a spatial force. For an arbitrary frame B, calculates the dot-product of this = V_MB_E (frame B’s spatial velocity measured in a frame M, expressed in a frame E) with F_B_E (frame B’s spatial force, expressed in frame E).

Parameter force:

which is F_B_E, frame B’s spatial force, expressed in the same frame E as this = V_MB_E.

Returns

Power of spatial force F_B_E in frame M, i.e., F_B_E ⋅ V_MB_E.

Note

Just as equating force 𝐅 to mass * acceleration as 𝐅 = m𝐚 relies on acceleration 𝐚 being measured in a world frame (also called an inertial or Newtonian frame), equating power = dK/dt (where K is kinetic energy) relies on K being measured in a world frame. Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors F_B_E and V_MB_E must have the same expressed-in frame E, the returned scalar is independent of frame E.

  1. dot(self: pydrake.multibody.math.SpatialVelocity_[Expression], momentum: drake::multibody::SpatialMomentum<drake::symbolic::Expression>) -> pydrake.symbolic.Expression

Calculates twice (2x) a body B’s kinetic energy measured in a frame M. For any frame (e.g., an multibody_frames_and_bodies “offset frame”) Bp that is fixed to a rigid body B, calculates the dot-product of this = V_MBp_E (frame Bp’s spatial velocity measured in frame M, expressed in frame E) with L_MBp_E (body B’s spatial momentum measured in frame M, about Bp’s origin, expressed in frame E).

Parameter momentum:

which is L_MBp_E, body B’s spatial momentum measured in frame M, about frame Bp’s origin, expressed in the same frame E as this = V_MBp_E.

Returns

2*K_MB, twice (2x) body B’s kinetic energy measured in frame M.

Note

In general, kinetic energy calculations are only useful when frame M is a world frame (also called a Newtonian or inertial frame). Hence, it is unusual to use this method unless frame M is the world frame W.

Note

Although the spatial vectors V_MBp_E and L_MBp_E must have the same expressed-in frame E, the resulting scalar K_MB is independent of frame E.

Note

As shown below, K_MB can be calculated from any frame Bp fixed on B, including body B’s center of mass frame Bcm. This is due to how spatial momentum and spatial velocity shift from Bcm to Bp. For more information, see SpatialMomentum::Shift() and SpatialVelocity::Shift().

Click to expand C++ code...
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
get_coeffs(self: pydrake.multibody.math.SpatialVelocity_[Expression]) numpy.ndarray[object[6, 1]]

Returns a constant reference to the underlying storage.

Rotate(self: pydrake.multibody.math.SpatialVelocity_[Expression], R_FE: pydrake.math.RotationMatrix_[Expression]) pydrake.multibody.math.SpatialVelocity_[Expression]

Provides a Python-only implementation of rotating / re-expressing a spatial vector.

Note

This is done because defining __rmatmul__ on this class does not disambiguate against the definitions of RotationMatrix.__matmul__.

rotational(self: pydrake.multibody.math.SpatialVelocity_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the rotational component of this spatial vector.

SetZero(self: pydrake.multibody.math.SpatialVelocity_[Expression]) pydrake.multibody.math.SpatialVelocity_[Expression]

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

Shift(self: pydrake.multibody.math.SpatialVelocity_[Expression], offset: numpy.ndarray[object[3, 1]]) pydrake.multibody.math.SpatialVelocity_[Expression]

Shifts a SpatialVelocity from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.

Parameter offset:

which is the position vector p_BoCo_E from frame B’s origin to frame C’s origin, expressed in frame E. p_BoCo_E must have the same expressed-in frame E as this spatial velocity (this = V_MB_E).

Returns V_MC_E:

which is frame C’s spatial velocity measured in frame M, expressed in frame E.

Note

Shift() differs from ShiftInPlace() in that Shift() does not modify this whereas ShiftInPlace() does modify this.

See also

ShiftInPlace() for more information and how V_MC_E is calculated.

translational(self: pydrake.multibody.math.SpatialVelocity_[Expression]) numpy.ndarray[object[3, 1]]

Const access to the translational component of this spatial vector.

static Zero() pydrake.multibody.math.SpatialVelocity_[Expression]

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