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

Detailed Description

template<typename T>
class drake::multibody::SpatialAcceleration< T >

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 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 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 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 Time Derivatives of Multibody Quantities.

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

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 SpatialAcceleration ()
 Default constructor. More...
 
 SpatialAcceleration (const Eigen::Ref< const Vector3< T >> &alpha, const Eigen::Ref< const Vector3< T >> &a)
 Constructs a spatial acceleration A from an angular acceleration α (alpha) and a translational acceleration 𝐚. More...
 
template<typename Derived >
 SpatialAcceleration (const Eigen::MatrixBase< Derived > &A)
 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 𝐚. More...
 
void ShiftInPlace (const Vector3< T > &offset, const Vector3< T > &angular_velocity_of_this_frame)
 In-place shift of a SpatialAcceleration from a frame B to a frame C, where both B and C are fixed to the same frame or rigid body. More...
 
SpatialAcceleration< T > Shift (const Vector3< T > &offset, const Vector3< T > &angular_velocity_of_this_frame) const
 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. More...
 
SpatialAcceleration< T > ShiftWithZeroAngularVelocity (const Vector3< T > &offset) const
 (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). More...
 
SpatialAcceleration< T > ComposeWithMovingFrameAcceleration (const Vector3< T > &position_of_moving_frame, const Vector3< T > &angular_velocity_of_this_frame, const SpatialVelocity< T > &velocity_of_moving_frame, const SpatialAcceleration< T > &acceleration_of_moving_frame) const
 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. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 SpatialAcceleration (const SpatialAcceleration &)=default
 
SpatialAccelerationoperator= (const SpatialAcceleration &)=default
 
 SpatialAcceleration (SpatialAcceleration &&)=default
 
SpatialAccelerationoperator= (SpatialAcceleration &&)=default
 
- Public Member Functions inherited from SpatialVector< SpatialAcceleration, 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 >
SpatialAcceleration< T > operator+ (const SpatialAcceleration< T > &A1_E, const SpatialAcceleration< T > &A2_E)
 Adds two spatial accelerations by simply adding their 6 underlying elements. More...
 
template<typename T >
SpatialAcceleration< T > operator- (const SpatialAcceleration< T > &A1_E, const SpatialAcceleration< T > &A2_E)
 Subtracts spatial accelerations by simply subtracting their 6 underlying elements. More...
 

Additional Inherited Members

- Public Types inherited from SpatialVector< SpatialAcceleration, T >
enum  
 Sizes for spatial quantities and its components in 3D (three dimensions). More...
 
using SpatialQuantity = SpatialAcceleration< 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< SpatialAcceleration, 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

◆ SpatialAcceleration() [1/5]

SpatialAcceleration ( const SpatialAcceleration< T > &  )
default

◆ SpatialAcceleration() [2/5]

◆ SpatialAcceleration() [3/5]

Default constructor.

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

◆ SpatialAcceleration() [4/5]

SpatialAcceleration ( const Eigen::Ref< const Vector3< T >> &  alpha,
const Eigen::Ref< const Vector3< T >> &  a 
)

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

◆ SpatialAcceleration() [5/5]

SpatialAcceleration ( const Eigen::MatrixBase< Derived > &  A)
explicit

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.

Member Function Documentation

◆ ComposeWithMovingFrameAcceleration()

SpatialAcceleration<T> ComposeWithMovingFrameAcceleration ( const Vector3< T > &  position_of_moving_frame,
const Vector3< T > &  angular_velocity_of_this_frame,
const SpatialVelocity< T > &  velocity_of_moving_frame,
const SpatialAcceleration< T > &  acceleration_of_moving_frame 
) const

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.

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 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).
[in]angular_velocity_of_this_framewhich is ω_MB_E, frame B's angular velocity measured in frame W and expressed in frame E.
[in]velocity_of_moving_framewhich is V_BC_E, frame C's spatial velocity measured in frame B, expressed in frame E.
[in]acceleration_of_moving_framewhich is A_BC_E, frame C's spatial acceleration measured in frame B, expressed in frame E.
Return values
A_MC_Eframe 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:
 α_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
  ω_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

  ω_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

  α_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

  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

 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.

 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:

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

  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

  ω_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.

          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)

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ Shift()

SpatialAcceleration<T> Shift ( const Vector3< T > &  offset,
const Vector3< T > &  angular_velocity_of_this_frame 
) const

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.

Parameters
[in]offsetwhich 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).
[in]angular_velocity_of_this_framewhich is ω_MB_E, frame B's angular velocity measured in frame M and expressed in frame E.
Return values
A_MC_Ewhich 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.

◆ ShiftInPlace()

void ShiftInPlace ( const Vector3< T > &  offset,
const Vector3< T > &  angular_velocity_of_this_frame 
)

In-place shift of a SpatialAcceleration 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 A_MB_E (frame B's spatial acceleration measured in a frame M and expressed in a frame E). On return this is modified to A_MC_E (frame C's spatial acceleration measured in frame M and expressed in frame E). The components of A_MC_E are calculated as:

  α_MC_E = α_MB_E           (angular acceleration of `this` is unchanged).
 a_MCo_E = a_MBo_E + α_MB_E x p_BoCo_E + ω_MB_E x (ω_MB_E x p_BoCo_E)
Parameters
[in]offsetwhich 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.
[in]angular_velocity_of_this_framewhich is ω_MB_E, frame B's angular velocity measured in frame W and expressed in frame E.
See also
Shift() to shift spatial acceleration without modifying this. Use ComposeWithMovingFrameAcceleration() if frame C is moving on frame B.

Derivation

Rotational acceleration component

Frame B and frame C are fixed (e.g., welded) to the same rigid object. Hence frames B and C always rotate together at the same rate and:

  ω_MC_E = ω_MB_E
  α_MC_E = α_MB_E

Translational acceleration component

Since frames B and C are fixed to the same rigid object, the translational velocity of Co (frame C's origin) measured in frame M can be calculated as

  v_MCo = v_MBo + ω_MB x p_BoCo

Point Co's translational acceleration in frame M is:

  a_MCo = DtM(v_MCo)                      (definition of acceleration).
        = DtM(v_MBo  + ω_MB x p_BoCo)     (substitution)
        = DtM(v_MBo) + DtM(ω_MB) x p_BoCo + ω_MB x DtM(p_BoCo)
        =     a_MBo  +     α_MB  x p_BoCo + ω_MB x DtM(p_BoCo)

The "Transport Theorem" converts the time-derivative of the last term from DtM() to DtB() – see math::ConvertTimeDerivativeToOtherFrame(), as

  DtM(p_BoCo) = DtB(p_BoCo) + ω_MB x p_BoCo
              =          0  + ω_MB x p_BoCo

◆ ShiftWithZeroAngularVelocity()

SpatialAcceleration<T> ShiftWithZeroAngularVelocity ( const Vector3< T > &  offset) const

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

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

Friends And Related Function Documentation

◆ operator+()

SpatialAcceleration< T > operator+ ( const SpatialAcceleration< T > &  A1_E,
const SpatialAcceleration< T > &  A2_E 
)
related

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

Parameters
[in]A1_Espatial acceleration expressed in the same frame E as A2_E.
[in]A2_Espatial acceleration expressed in the same frame E as A1_E.
Note
The general utility of this operator+() function is questionable and it should only be used if you are sure it makes sense.
See also
Shift(), ShiftInPlace(), and ComposeWithMovingFrameAcceleration().

◆ operator-()

SpatialAcceleration< T > operator- ( const SpatialAcceleration< T > &  A1_E,
const SpatialAcceleration< T > &  A2_E 
)
related

Subtracts spatial accelerations by simply subtracting their 6 underlying elements.

Parameters
[in]A1_Espatial acceleration expressed in the same frame E as A2_E.
[in]A2_Espatial acceleration expressed in the same frame E as A1_E.
Note
The general utility of this operator-() function is questionable and it should only be used if you are sure it makes sense.
See also
Shift(), ShiftInPlace(), and ComposeWithMovingFrameAcceleration().

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