Drake
Drake C++ Documentation
SpatialVelocity< T > Class Template Reference

Detailed Description

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
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/math/spatial_velocity.h>

Public Member Functions

 SpatialVelocity ()
 Default constructor. More...
 
 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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
dot (const SpatialForce< T > &force) const
 Calculates the power generated by a spatial force. More...
 
dot (const SpatialMomentum< T > &momentum) const
 Calculates twice (2x) a body B's kinetic energy measured in a frame M. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 SpatialVelocity (const SpatialVelocity &)=default
 
SpatialVelocityoperator= (const SpatialVelocity &)=default
 
 SpatialVelocity (SpatialVelocity &&)=default
 
SpatialVelocityoperator= (SpatialVelocity &&)=default
 
- Public Member Functions inherited from SpatialVector< SpatialVelocity, T >
 SpatialVector ()
 Default constructor. More...
 
 SpatialVector (const Eigen::Ref< const Vector3< T >> &w, const Eigen::Ref< const Vector3< T >> &v)
 Constructs a spatial vector from a rotational component w and a translational component v. More...
 
 SpatialVector (const Eigen::MatrixBase< OtherDerived > &V)
 Constructs a spatial vector V from an Eigen expression that represents a 6-element vector (3-element rotational vector on top of a 3-element translational vector). More...
 
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. More...
 
const T & operator[] (int i) const
 Const access to the i-th element of this spatial vector. More...
 
T & operator[] (int i)
 Mutable access to the i-th element of this spatial vector. More...
 
const Vector3< T > & rotational () const
 Const access to the rotational component of this spatial vector. More...
 
Vector3< T > & rotational ()
 Mutable access to the rotational component of this spatial vector. More...
 
const Vector3< T > & translational () const
 Const access to the translational component of this spatial vector. More...
 
Vector3< T > & translational ()
 Mutable access to the translational component of this spatial vector. More...
 
const T * data () const
 Returns a (const) bare pointer to the underlying data. More...
 
T * mutable_data ()
 Returns a (mutable) bare pointer to the underlying data. More...
 
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). More...
 
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. More...
 
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. More...
 
void SetNaN ()
 Sets all the elements in this SpatialVector to NaN. More...
 
SpatialQuantitySetZero ()
 Sets both the rotational and translational components of this SpatialVector to zero. More...
 
CoeffsEigenTypeget_coeffs ()
 Returns a mutable reference to the underlying storage. More...
 
const CoeffsEigenTypeget_coeffs () const
 Returns a constant reference to the underlying storage. More...
 
SpatialQuantity operator- () const
 Unary minus operator. More...
 
SpatialQuantityoperator+= (const SpatialQuantity &V)
 Addition assignment operator. More...
 
SpatialQuantityoperator-= (const SpatialQuantity &V)
 Subtraction assignment operator. More...
 
SpatialQuantityoperator *= (const T &s)
 Multiplication assignment operator. More...
 
 SpatialVector (const SpatialVector &)=default
 
 SpatialVector (SpatialVector &&)=default
 
SpatialVectoroperator= (const SpatialVector &)=default
 
SpatialVectoroperator= (SpatialVector &&)=default
 

Related Functions

(Note that these are not member functions.)

template<typename T >
SpatialVelocity< T > operator+ (const SpatialVelocity< T > &V1_E, const SpatialVelocity< T > &V2_E)
 Adds two spatial velocities by simply adding their 6 underlying elements. More...
 
template<typename T >
SpatialVelocity< T > operator- (const SpatialVelocity< T > &V1_E, const SpatialVelocity< T > &V2_E)
 Subtracts spatial velocities by simply subtracting their 6 underlying elements. More...
 

Additional Inherited Members

- Public Types inherited from SpatialVector< SpatialVelocity, T >
enum  
 Sizes for spatial quantities and its components in 3D (three dimensions). More...
 
using SpatialQuantity = SpatialVelocity< T >
 The more specialized spatial vector class templated on the scalar type T. More...
 
using CoeffsEigenType = Vector6< T >
 The type of the underlying in-memory representation using an Eigen vector. More...
 
- Static Public Member Functions inherited from SpatialVector< SpatialVelocity, T >
static SpatialQuantity Zero ()
 Factory to create a zero spatial vector, i.e., a SpatialVector whose rotational and translational components are both zero. More...
 

Constructor & Destructor Documentation

◆ SpatialVelocity() [1/5]

SpatialVelocity ( const SpatialVelocity< T > &  )
default

◆ SpatialVelocity() [2/5]

SpatialVelocity ( SpatialVelocity< T > &&  )
default

◆ SpatialVelocity() [3/5]

Default constructor.

In Release builds, all 6 elements of a newly constructed spatial velocity are uninitialized (for speed). In Debug builds, the 6 elements are set to NaN so that invalid operations on an uninitialized spatial velocity fail fast (fast bug detection).

◆ SpatialVelocity() [4/5]

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.

◆ SpatialVelocity() [5/5]

SpatialVelocity ( const Eigen::MatrixBase< Derived > &  V)
explicit

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.

Member Function Documentation

◆ ComposeWithMovingFrameVelocity()

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.

Herein, this is the spatial velocity of a frame (designated B) in frame M and the 𝐨𝐭𝐡𝐞𝐫 frame is designated C.

Parameters
[in]position_of_moving_framewhich 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).
[in]velocity_of_moving_framewhich is V_BC_E, frame C's spatial velocity measured in frame B, expressed in frame E.
Return values
V_MC_Eframe 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:
 ω_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() [1/2]

T dot ( const SpatialForce< T > &  force) const

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).

Parameters
[in]forcewhich 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.
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.

◆ dot() [2/2]

T dot ( const SpatialMomentum< T > &  momentum) const

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]momentumwhich 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)

◆ operator=() [1/2]

SpatialVelocity& operator= ( SpatialVelocity< T > &&  )
default

◆ operator=() [2/2]

SpatialVelocity& operator= ( const SpatialVelocity< T > &  )
default

◆ Shift()

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.

Parameters
[in]offsetwhich 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).
Return values
V_MC_Ewhich 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.

◆ ShiftInPlace()

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]offsetwhich 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.

Friends And Related Function Documentation

◆ operator+()

SpatialVelocity< T > operator+ ( const SpatialVelocity< T > &  V1_E,
const SpatialVelocity< T > &  V2_E 
)
related

Adds two spatial velocities by simply adding their 6 underlying elements.

Parameters
[in]V1_Espatial velocity expressed in the same frame E as V2_E.
[in]V2_Espatial velocity expressed in the same frame E as V1_E.
Note
The general utility of this operator+() function is questionable and it should only be used if you are sure it makes sense. One use case is for calculating the spatial velocity V_MC of a frame C measured in a frame M when frame C is moving on a frame B and one has pre-calculated V_MBc (frame Bc's spatial velocity measured in frame M, where frame Bc is instantaneously coincident with frame C). For this use case, the operator+ function returns V_MC_E = V_MBc_E + V_BC_E, where the precalculated V_MBc_E is equal to V_MBo_E.Shift(p_BoCo_E).
See also
Shift(), ShiftInPlace(), and ComposeWithMovingFrameVelocity().

◆ operator-()

SpatialVelocity< T > operator- ( const SpatialVelocity< T > &  V1_E,
const SpatialVelocity< T > &  V2_E 
)
related

Subtracts spatial velocities by simply subtracting their 6 underlying elements.

Parameters
[in]V1_Espatial velocity expressed in the same frame E as V2_E.
[in]V2_Espatial velocity expressed in the same frame E as V1_E.
Note
The general utility of this operator-() function is questionable and it should only be used if you are sure it makes sense. One use case is for calculating relative spatial velocity, e.g., a frame C's spatial velocity relative to a frame B, measure in a frame M. This use case calculates V_M_BC_E = V_MC_E - V_MB_E, which contains ω_BC (C's angular velocity measured in B) and v_M_BoCo (Co's velocity relative to Bo, measured in M), where both ω_BC and v_M_BoCo are expressed in frame E.
 ω_BC  = ω_MC - ω_MB
 v_M_BoCo = v_MCo - v_MBo = DtM(p_BoCo)
where DtM(p_BoCo) is the time-derivative in frame M of p_BoCo (position vector from Bo to Co). A second use case has to do with a frame C that is moving on a frame B and calculates frame C's spatial velocity measured in frame B. It assumes you have pre-calculated V_MBc (frame Bc's spatial velocity measured in frame M, where frame Bc is fixed to B and instantaneously coincident with frame C. This use case returns V_BC_E = V_MC_E - V_MBc_E, where the precalculated V_MBc_E is equal to V_MBo_E.Shift(p_BoBc_E).
See also
Shift(), ShiftInPlace(), and ComposeWithMovingFrameVelocity().

The documentation for this class was generated from the following files: