Drake
SpatialAcceleration< T > Class Template Reference

This class is used to represent a spatial acceleration that combines rotational (angular acceleration) and translational (linear acceleration) components. More...

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

Inheritance diagram for SpatialAcceleration< T >:
Collaboration diagram for SpatialAcceleration< T >:

Public Member Functions

 SpatialAcceleration ()
 Default constructor. More...
 
 SpatialAcceleration (const Eigen::Ref< const Vector3< T >> &alpha, const Eigen::Ref< const Vector3< T >> &a)
 SpatialAcceleration constructor from an angular acceleration alpha and a linear acceleration a. More...
 
template<typename Derived >
 SpatialAcceleration (const Eigen::MatrixBase< Derived > &A)
 SpatialAcceleration constructor from an Eigen expression that represents a six-dimensional vector. More...
 
SpatialAcceleration< T > & ShiftInPlace (const Vector3< T > &p_PoBo_E, const Vector3< T > &w_WP_E)
 In-place shift of this spatial acceleration A_WP of a frame P into the spatial acceleration A_WPb of a frame Pb which is an offset frame rigidly aligned with P, but with its origin shifted to a point Bo by an offset p_PoBo. More...
 
SpatialAcceleration< T > Shift (const Vector3< T > &p_PoBo_E, const Vector3< T > &w_WP_E) const
 Shifts this spatial acceleration A_WP of a frame P into the spatial acceleration A_WPb of a frame Pb which is an offset frame rigidly aligned with P, but with its origin shifted to a point Bo by an offset p_PoBo. More...
 
SpatialAcceleration< T > ComposeWithMovingFrameAcceleration (const Vector3< T > &p_PoBo_E, const Vector3< T > &w_WP_E, const SpatialVelocity< T > &V_PB_E, const SpatialAcceleration< T > &A_PB_E) const
 This method composes this spatial acceleration A_WP of a frame P measured in a frame W, with that of a third frame B moving in P with spatial acceleration A_PB. 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)
 SpatialVector constructor from an rotational component w and a linear component v. More...
 
 SpatialVector (const Eigen::MatrixBase< OtherDerived > &V)
 SpatialVector constructor from an Eigen expression that represents a six-dimensional vector. More...
 
int size () const
 The total size of the concatenation of the angular and linear components. More...
 
const T & operator[] (int i) const
 Const access to the i-th component of this spatial vector. More...
 
T & operator[] (int i)
 Mutable access to the i-th component 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...
 
bool IsApprox (const SpatialQuantity &other, double tolerance=Eigen::NumTraits< T >::epsilon()) const
 Compares this spatial vector to the provided spatial vector other within a specified precision. More...
 
void SetNaN ()
 Sets all entries in this SpatialVector to NaN. More...
 
SpatialQuantitySetZero ()
 Sets both rotational and translational components of this SpatialVector to zero. More...
 
CoeffsEigenTypeget_coeffs ()
 Returns a reference to the underlying storage. More...
 
const CoeffsEigenTypeget_coeffs () const
 Returns a constant reference to the underlying storage. More...
 
 SpatialVector (const SpatialVector &)=default
 
 SpatialVector (SpatialVector &&)=default
 
SpatialVectoroperator= (const SpatialVector &)=default
 
SpatialVectoroperator= (SpatialVector &&)=default
 

Additional Inherited Members

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

Detailed Description

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

This class is used to represent a spatial acceleration that combines rotational (angular acceleration) and translational (linear acceleration) components.

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

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

Template Parameters
TThe underlying scalar type. Must be a valid Eigen scalar.

Constructor & Destructor Documentation

SpatialAcceleration ( const SpatialAcceleration< T > &  )
default
SpatialAcceleration ( )
inline

Default constructor.

In Release builds the elements of the newly constructed spatial acceleration are left uninitialized resulting in a zero cost operation. However in Debug builds those entries are set to NaN so that operations using this uninitialized spatial acceleration fail fast, allowing fast bug detection.

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

SpatialAcceleration constructor from an angular acceleration alpha and a linear acceleration a.

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

SpatialAcceleration constructor from an Eigen expression that represents a six-dimensional vector.

Under the hood, spatial accelerations are 6-element quantities that are pairs of ordinary 3-vectors. Elements 0-2 constitute the angular acceleration component while elements 3-5 constitute the translational acceleration. The argument A in this constructor is the concatenation of the rotational 3D component followed by the translational 3D component. This constructor will assert the size of A is six (6) at compile-time for fixed sized Eigen expressions and at run-time for dynamic sized Eigen expressions.

Member Function Documentation

SpatialAcceleration<T> ComposeWithMovingFrameAcceleration ( const Vector3< T > &  p_PoBo_E,
const Vector3< T > &  w_WP_E,
const SpatialVelocity< T > &  V_PB_E,
const SpatialAcceleration< T > &  A_PB_E 
) const
inline

This method composes this spatial acceleration A_WP of a frame P measured in a frame W, with that of a third frame B moving in P with spatial acceleration A_PB.

The result is the spatial acceleration A_WB of frame B measured in W. At the instant in which the accelerations are composed, frame B is located with its origin Bo at p_PoBo from P's origin Po.

See also
SpatialVelocity::ComposeWithMovingFrameVelocity() for the composition of SpatialVelocity quantities.
Note
This method is the extension to the Shift() operator, which computes the spatial acceleration frame P shifted to Bo as if frame B moved rigidly with P, that is, for when V_PB and A_PB are both zero. In other words the results from Shift() equal the results from this method when V_PB and A_PB are both zero.
Parameters
[in]p_PoBo_EShift vector from P's origin to B's origin, expressed in frame E. The "from" point Po must be the point whose acceleration is currently represented in this spatial acceleration, and E must be the same expressed-in frame as for this spatial acceleration.
[in]w_WP_EAngular velocity of frame P measured in frame A and expressed in frame E.
[in]V_PB_EThe spatial velocity of a third frame B in motion with respect to P, expressed in the same frame E as this spatial acceleration.
[in]A_PB_EThe spatial acceleration of a third frame B in motion with respect to P, expressed in the same frame E as this spatial acceleration.
Return values
A_WB_EThe spatial acceleration of frame B in W, expressed in frame E.

Derivation

The spatial velocity of frame B in W can be obtained by composing V_WP with V_PB:

  V_WB = V_WPb + V_PB = V_WP.Shift(p_PoBo) + V_PB                     (1)

This operation can be performed with the SpatialVelocity method ComposeWithMovingFrameVelocity().

Translational acceleration component

The translational velocity v_WBo of point Bo in W corresponds to the translational component in Eq. (1):

  v_WBo = v_WPo + w_WP x p_PoBo + v_PBo                               (2)

Therefore, for the translational acceleration we have:

  a_WBo = DtW(v_WBo)
        = DtW(v_WPo + w_WP x p_PoBo + v_PBo)
        = DtW(v_WPo) + DtW(w_WP x p_PoBo) + DtW(v_PBo)
        = a_WPo + DtW(w_WP) x p_PoBo + w_WP x DtW(p_PoBo) + DtW(v_PBo)
        = a_WPo + alpha_WP x p_PoBo + w_WP x DtW(p_PoBo) + DtW(v_PBo) (3)

with a_WPo = DtW(v_WPo) and alpha_WP = DtW(w_WP) by definition. The term DtW(p_PoBo) in Eq. (3) is obtained by converting the vector time derivative from DtW() to DtP(), see drake::math::ConvertTimeDerivativeToOtherFrame():

  DtW(p_PoBo) = DtP(p_PoBo) + w_WP x p_PoBo
              = v_PBo + w_WP x p_PoBo                                 (4)

since v_PBo = DtP(p_PoBo) by definition. Similarly, the term DtW(v_PBo) in Eq. (3) is also obtained by converting the time derivative from DtW() to DtP():

  DtW(v_PBo) = DtP(v_PBo) + w_WP x v_PBo
             = a_PBo + w_WP x v_PBo                                   (5)

with a_PBo = DtP(v_PBo) by definition. Using Eqs. (4) and (5) in Eq. (3) yields for the translational acceleration:

  a_WBo = a_WPo + alpha_WP x p_PoBo
        + w_WP x (v_PBo + w_WP x p_PoBo) + a_PBo + w_WP x v_PBo

and finally, by grouping terms together:

  a_WBo = a_WPo + alpha_WP x p_PoBo
        + w_WP x w_WP x p_PoBo + 2 * w_WP x v_PBo + a_PBo             (6)

which includes the effect of angular acceleration of P in W alpha_WP x p_PoBo, the centrifugual acceleration w_WP x w_WP x p_PoBo, the Coriolis acceleration 2 * w_WP x v_PBo due to the motion of Bo in P and, the additional acceleration of Bo in P a_PBo.

Rotational acceleration component

The rotational velocity w_WB of frame B in W corresponds to the rotational component in Eq. (1):

  w_WB = w_WP + w_PB                                                  (7)

Therefore, the rotational acceleration of B in W corresponds to:

  alpha_WB = DtW(w_WB) = DtW(w_WP) + DtW(w_PB)
           = alpha_WP + DtW(w_PB)                                     (8)

where the last term in Eq. (8) can be converted to a time derivative in P as:

  DtW(w_PB) = DtP(w_PB) + w_WP x w_PB = alpha_PB + w_WP x w_PB        (9)

where alpha_PB = DtP(w_PB) by definition. Thus, the final expression for alpha_WB is obtained by using Eq. (9) into Eq. (8):

  alpha_WB = alpha_WP + alpha_PB + w_WP x w_PB                       (10)

Equation (10) shows that angular accelerations cannot be simply added as angular velocities can but there exists an additional term w_WP x w_PB.

The spatial acceleration

The rotational and translational components of the spatial acceleration are given by Eqs. (10) and (6) respectively:

  A_WB.rotational() = alpha_WB = {alpha_WP} + alpha_PB + w_WP x w_PB
  A_WB.translational() = a_WBo
                     = {a_WPo + alpha_WP x p_PoBo + w_WP x w_WP x p_PoBo}
                     + 2 * w_WP x v_PBo + a_PBo

where we have placed within curly brackets {} all the terms that also appear in the Shift() operation, which is equivalent to this method when V_PB and A_PB are both zero. In the equations above alpha_WP = A_WP.rotational() and a_WPo = A_WP.translational(). As usual, for computation, all quantities above must be expressed in a common frame E; we add an _E suffix to each symbol to indicate that.

Here is the call graph for this function:

Here is the caller graph for this function:

SpatialAcceleration& operator= ( SpatialAcceleration< T > &&  )
default
SpatialAcceleration& operator= ( const SpatialAcceleration< T > &  )
default
SpatialAcceleration<T> Shift ( const Vector3< T > &  p_PoBo_E,
const Vector3< T > &  w_WP_E 
) const
inline

Shifts this spatial acceleration A_WP of a frame P into the spatial acceleration A_WPb of a frame Pb which is an offset frame rigidly aligned with P, but with its origin shifted to a point Bo by an offset p_PoBo.

Frame Pb is instantaneously moving together with frame P as if rigidly attached to it. As an example of application, this operation can be used to compute A_WPb where P is a frame on a rigid body and Bo is another point on that same body. Therefore P and Pb move together with the spatial velocity V_PPb being zero at all times. This is an alternate signature for shifting a spatial acceleration that does not change the original object. See ShiftInPlace() for more information and a description of the arguments.

Here is the call graph for this function:

Here is the caller graph for this function:

SpatialAcceleration<T>& ShiftInPlace ( const Vector3< T > &  p_PoBo_E,
const Vector3< T > &  w_WP_E 
)
inline

In-place shift of this spatial acceleration A_WP of a frame P into the spatial acceleration A_WPb of a frame Pb which is an offset frame rigidly aligned with P, but with its origin shifted to a point Bo by an offset p_PoBo.

Frame Pb is instantaneously moving together with frame P as if rigidly attached to it. As an example of application, this operation can be used to compute A_WPb where P is a frame on a rigid body and Bo is another point on that same body. Therefore P and Pb move together with the spatial velocity V_PPb being zero at all times.

The shift operation modifies this spatial acceleration A_WP_E of a frame P measured in a frame W and expressed in a frame E, to become A_WPb_E, representing the acceleration of a frame Pb result of shifting frame P to point Bo which instantaneously moves together with frame P. This requires adjusting the linear acceleration component to account for:

  1. the angular acceleration alpha_WP of frame P in W.
  2. the centrifugal acceleration due to the angular velocity w_WP of frame P in W.

We are given the vector from the origin Po of frame P to point Bo, which becomes the origin of the shifted frame Pb, as the position vector p_PoBo_E expressed in the same frame E as this spatial acceleration. The operation performed, in coordinate-free form, is:

  alpha_WPb  = alpha_WP,  i.e. the angular acceleration is unchanged.
  a_WBo = a_WPo + alpha_WP x p_PoBo + w_WP x w_WP x p_PoBo

where alpha and a represent the angular and linear acceleration components respectively. See notes at the end of this documentation for a detailed derivation.

For computation, all quantities above must be expressed in a common frame E; we add an _E suffix to each symbol to indicate that.

This operation is performed in-place modifying the original object.

Parameters
[in]p_PoBo_EShift vector from the origin Po of frame P to point Bo, expressed in frame E. The "from" frame P must be the frame whose acceleration is currently represented in this spatial acceleration, and E must be the same expressed-in frame as for this spatial acceleration.
[in]w_WP_EAngular velocity of frame P measured in frame W and expressed in frame E.
Returns
A reference to this spatial acceleration which is now A_WPb_E, that is, the spatial acceleration of frame Pb, still measured in frame W and expressed in frame E.
See also
Shift() to compute the shifted spatial acceleration without modifying this original object.

Derivation

Translational acceleration component

Recall that frame Pb is an offset frame rigidly aligned with P, but with its origin shifted to a point Bo by an offset p_PoBo. Frame Pb is instantaneously moving together with frame P as if rigidly attached to it. The translational velocity v_WPb of frame Pb's origin, point Bo, in W can be obtained by the shift operation as:

  v_WPb = v_WPo + w_WP x p_PoBo                                       (1)

Therefore, for the translational acceleration we have:

  a_WBo = DtW(v_WPb)
        = DtW(v_WPo + w_WP x p_PoBo)
        = DtW(v_WPo) + DtW(w_WP x p_PoBo)
        = a_WPo + DtW(w_WP) x p_PoBo + w_WP x DtW(p_PoBo)
        = a_WPo + alpha_WP x p_PoBo + w_WP x DtW(p_PoBo)              (2)

with a_WPo = DtW(v_WPo) and alpha_WP = DtW(w_WP) by definition. The last term in Eq. (2) is obtained by converting the vector time derivative from DtW() to DtP(), see drake::math::ConvertTimeDerivativeToOtherFrame():

  DtW(p_PoBo) = DtP(p_PoBo) + w_WP x p_PoBo
              = w_WP x p_PoBo                                         (3)

since v_PBo = DtP(p_PoBo) = 0 because the position of point Bo is fixed in frame P. Using Eq. (3) in Eq. (2) finally yields for the translational acceleration:

  a_WBo = a_WPo + alpha_WP x p_PoBo + w_WP x w_WP x p_PoBo            (4)

Rotational acceleration component

The rotational velocity of frame Pb simply equals that of frame P since they are moving together in rigid motion, therefore w_WPb = w_WP. From this, the rotational acceleration of frame Pb in W is obtained as:

  alpha_WPb = DtW(w_WPb) = DtW(w_WP) = alpha_WP                       (5)

which should be immediately obvious considering that frame Pb rotates together with frame P.

With the rotational, Eq. (5), and translational, Eq. (4), components of acceleration derived above, we can write for A_WPb:

  A_WPb.rotational() = alpha_WPb = alpha_WP
  A_WPb.translational() = a_WBo
                        = a_WPo + alpha_WP x p_PoBo + w_WP x w_WP x p_PoBo

with alpha_WP = A_WP.rotational() and a_WPo = A_WP.translational(). As usual, for computation, all quantities above must be expressed in a common frame E; we add an _E suffix to each symbol to indicate that.

Here is the call graph for this function:

Here is the caller graph for this function:


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