template<typename T>
class drake::multibody::SpatialVelocity< T >
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 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 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 Spatial Vectors and Multibody Quantities.
- Template Parameters
-
|
| | SpatialVelocity () |
| | Default constructor.
|
| | SpatialVelocity (const Eigen::Ref< const Vector3< T > > &w, const Eigen::Ref< const Vector3< T > > &v) |
| | Constructs a spatial velocity V from an angular velocity ω and a translational velocity v.
|
| template<typename Derived> |
| | SpatialVelocity (const Eigen::MatrixBase< Derived > &V) |
| | 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.
|
| void | ShiftInPlace (const Vector3< T > &offset) |
| | In-place shift of a SpatialVelocity from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.
|
| SpatialVelocity< T > | Shift (const Vector3< T > &offset) const |
| | 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.
|
| SpatialVelocity< T > | ComposeWithMovingFrameVelocity (const Vector3< T > &position_of_moving_frame, const SpatialVelocity< T > &velocity_of_moving_frame) const |
| | 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.
|
| T | dot (const SpatialForce< T > &force) const |
| | Calculates the power generated by a spatial force.
|
| T | dot (const SpatialMomentum< T > &momentum) const |
| | Calculates twice (2x) a body B's kinetic energy measured in a frame M.
|
| | SpatialVelocity (const SpatialVelocity &)=default |
| SpatialVelocity & | operator= (const SpatialVelocity &)=default |
| | SpatialVelocity (SpatialVelocity &&)=default |
| SpatialVelocity & | operator= (SpatialVelocity &&)=default |
| Public Member Functions inherited from SpatialVector< SpatialVelocity, T > |
| int | size () const |
| | For 3D (three-dimensional) analysis, the total size of the concatenated rotational vector (3 elements) and translational vector (3 elements) is six (6), which is known at compile time.
|
| const T & | operator[] (int i) const |
| | Const access to the i-th element of this spatial vector.
|
| const Vector3< T > & | rotational () const |
| | Const access to the rotational component of this spatial vector.
|
| const Vector3< T > & | translational () const |
| | Const access to the translational component of this spatial vector.
|
| const T * | data () const |
| | Returns a (const) bare pointer to the underlying data.
|
| T * | mutable_data () |
| | Returns a (mutable) bare pointer to the underlying data.
|
| std::tuple< const T, const T > | GetMaximumAbsoluteDifferences (const SpatialQuantity &other) const |
| | Returns the maximum absolute values of the differences in the rotational and translational components of this and other (i.e., the infinity norms of the difference in rotational and translational components).
|
| decltype(T()< T()) | IsNearlyEqualWithinAbsoluteTolerance (const SpatialQuantity &other, double rotational_tolerance, double translational_tolerance) const |
| | Compares the rotational and translational parts of this and other to check if they are the same to within specified absolute differences.
|
| decltype(T()< T()) | IsApprox (const SpatialQuantity &other, double tolerance=2 *std::numeric_limits< double >::epsilon()) const |
| | Determines whether all six corresponding elements of two spatial vectors are equal to each other to within a specified tolerance epsilon.
|
| void | SetNaN () |
| | Sets all the elements in this SpatialVector to NaN.
|
| SpatialQuantity & | SetZero () |
| | Sets both the rotational and translational components of this SpatialVector to zero.
|
| CoeffsEigenType & | get_coeffs () |
| | Returns a mutable reference to the underlying storage.
|
| SpatialQuantity | operator- () const |
| | Unary minus operator.
|
| SpatialQuantity & | operator+= (const SpatialQuantity &V) |
| | Addition assignment operator.
|
| SpatialQuantity & | operator-= (const SpatialQuantity &V) |
| | Subtraction assignment operator.
|
| SpatialQuantity & | operator*= (const T &s) |
| | Multiplication assignment operator.
|
| | SpatialVector (const SpatialVector &)=default |
| SpatialVector & | operator= (const SpatialVector &)=default |
template<typename T>
template<typename Derived>
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.
Calculates twice (2x) a body B's kinetic energy measured in a frame M.
For any frame (e.g., an 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).
- Parameters
-
| [in] | 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.
-
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.
-
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().
K_MB = 1/2 (L_MBp · V_MBp) = 1/2 (L_MBcm · V_MBcm)
template<typename T>
| void ShiftInPlace |
( |
const Vector3< T > & | offset | ) |
|
In-place shift of a SpatialVelocity from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body.
On entry, this is V_MB_E (frame B's spatial velocity measured in a frame M and expressed in a frame E). On return this is modified to V_MC_E (frame C's spatial velocity measured in frame M and expressed in frame E). The components of V_MC_E are calculated as:
ω_MC_E = ω_MB_E (angular velocity of `this` is unchanged).
v_MC_E = v_MB_E + ω_MB_E x p_BoCo_E (translational velocity changes).
- Parameters
-
| [in] | 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. |
- See also
- Shift() to shift spatial velocity without modifying this.