Drake
SpatialVelocity< T > Class Template Reference

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

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

Inheritance diagram for SpatialVelocity< T >:
[legend]
Collaboration diagram for SpatialVelocity< T >:
[legend]

Public Member Functions

 SpatialVelocity ()
 Default constructor. More...
 
 SpatialVelocity (const Eigen::Ref< const Vector3< T >> &w, const Eigen::Ref< const Vector3< T >> &v)
 SpatialVelocity constructor from an angular velocity w and a linear velocity v. More...
 
template<typename Derived >
 SpatialVelocity (const Eigen::MatrixBase< Derived > &V)
 SpatialVelocity constructor from an Eigen expression that represents a six-dimensional vector. More...
 
SpatialVelocity< T > & ShiftInPlace (const Vector3< T > &p_BpBq_E)
 In-place shift of a SpatialVelocity from one point on a rigid body or frame to another point on the same body or frame. More...
 
SpatialVelocity< T > Shift (const Vector3< T > &p_BpBq_E) const
 Shift of a SpatialVelocity from one point on a rigid body or frame to another point on the same body or frame. More...
 
SpatialVelocity< T > ComposeWithMovingFrameVelocity (const Vector3< T > &p_PoBo_E, const SpatialVelocity< T > &V_PB_E) const
 This method composes this spatial velocity V_WP of a frame P measured in a frame W, with that of a third frame B moving in P with spatial velocity V_PB. More...
 
dot (const SpatialForce< T > &F_Q_E) const
 Given this spatial velocity V_IBp_E of point P of body B, measured in an inertial frame I and expressed in a frame E, this method computes the 6-dimensional dot product with the spatial force F_Bp_E applied to point P, and expressed in the same frame E in which the spatial velocity is expressed. 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)
 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< SpatialVelocity, T >
enum  
 Sizes for spatial quantities and its components in three dimensions. More...
 
using SpatialQuantity = SpatialVelocity< 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< SpatialVelocity, T >
static SpatialQuantity Zero ()
 Factory to create a zero SpatialVector, i.e. More...
 

Detailed Description

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

This class is used to represent a spatial velocity (also called a twist) that combines rotational (angular) and translational (linear) velocity components.

Spatial velocities are 6-element quantities that are pairs of ordinary 3-vectors. Elements 0-2 are the angular velocity component while elements 3-5 are the translational velocity. Spatial velocities represent the motion of a "moving frame" B measured with respect to a "measured-in" frame A. In addition, the two contained vectors must be expressed in the same "expressed-in" frame E, which may be distinct from either A or B. Finally, while angular velocity is identical for any frame fixed to a rigid body, translational velocity refers to a particular point. Only the vector values are stored in a SpatialVelocity object; the three frames and the point must be understood from context. 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 V is used to designate a spatial velocity quantity. We write a point P fixed to body (or frame) B as \(B_P\) which appears in code and comments as Bp. Then we write a particular spatial velocity as V_ABp_E where the _E suffix indicates that the expressed-in frame is E. This symbol represents the angular velocity of frame B in frame A, and the translational velocity of point P in A, where P is fixed to frame B, with both vectors expressed in E. Very often the point of interest will be the body origin Bo; if no point is shown the origin is understood, so V_AB_E means V_ABo_E. For a more detailed introduction on spatial vectors and the monogram notation please refer to section Spatial Vectors.

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

Constructor & Destructor Documentation

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

Default constructor.

In Release builds the elements of the newly constructed spatial velocity 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 velocity fail fast, allowing fast bug detection.

SpatialVelocity ( const Eigen::Ref< const Vector3< T >> &  w,
const Eigen::Ref< const Vector3< T >> &  v 
)
inline

SpatialVelocity constructor from an angular velocity w and a linear velocity v.

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

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

This constructor will assert the size of V is six (6) at compile-time for fixed sized Eigen expressions and at run-time for dynamic sized Eigen expressions.

Member Function Documentation

SpatialVelocity<T> ComposeWithMovingFrameVelocity ( const Vector3< T > &  p_PoBo_E,
const SpatialVelocity< T > &  V_PB_E 
) const
inline

This method composes this spatial velocity V_WP of a frame P measured in a frame W, with that of a third frame B moving in P with spatial velocity V_PB.

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

The composition cannot be performed directly since frames P and B do not have the same origins. To perform the composition V_WB, the velocity of P needs to be shifted to point Bo:

  V_WB_E = V_WPb_E + V_PB_E = V_WP_E.Shift(p_PoBo_E) + V_PB_E

where p_PoBo is the position vector from P's origin to B's origin and V_WPb is the spatial velocity of a new frame Pb which is an offset frame rigidly aligned with P, but with its origin shifted to B's origin. The key is that in the expression above, the two spatial velocities being added must be for frames with the same origin point, in this case Bo.

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

Note
If frame B moves rigidly together with frame P, as in a rigid body, V_PB = 0 and the result of this method equals that of the Shift() operation.
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 velocity is currently represented in this spatial velocity, and E must be the same expressed-in frame as for this spatial velocity.
[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 velocity.
Return values
V_WB_EThe spatial velocity of frame B in W resulting from the composition of this spatial velocity V_WP and B's velocity in P, V_PB. The result is expressed in the same frame E as this spatial velocity.

Here is the call graph for this function:

Here is the caller graph for this function:

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

Given this spatial velocity V_IBp_E of point P of body B, measured in an inertial frame I and expressed in a frame E, this method computes the 6-dimensional dot product with the spatial force F_Bp_E applied to point P, and expressed in the same frame E in which the spatial velocity is expressed.

This dot-product represents the power generated by the spatial force when its body and application point have this spatial velocity. Although the two spatial vectors must be expressed in the same frame, the result is independent of that frame.

Warning
The result of this method cannot be interpreted as power unless this spatial velocity is measured in an inertial frame I, which cannot be enforced by this class.

Here is the call graph for this function:

Here is the caller graph for this function:

SpatialVelocity& operator= ( SpatialVelocity< T > &&  )
default
SpatialVelocity& operator= ( const SpatialVelocity< T > &  )
default
SpatialVelocity<T> Shift ( const Vector3< T > &  p_BpBq_E) const
inline

Shift of a SpatialVelocity from one point on a rigid body or frame to another point on the same body or frame.

This is an alternate signature for shifting a spatial velocity's point that does not change the original object. See ShiftInPlace() for more information.

Parameters
[in]p_BpBq_EShift vector from point P of body B to point Q of B, expressed in frame E. The "from" point Bp must be the point whose velocity is currently represented in this spatial velocity, and E must be the same expressed-in frame as for this spatial velocity.
Return values
V_ABq_EThe spatial velocity of frame B at point Q, measured in frame A and expressed in frame E.
See also
ShiftInPlace() to compute the shifted spatial velocity in-place modifying the original object.

Here is the call graph for this function:

Here is the caller graph for this function:

SpatialVelocity<T>& ShiftInPlace ( const Vector3< T > &  p_BpBq_E)
inline

In-place shift of a SpatialVelocity from one point on a rigid body or frame to another point on the same body or frame.

this spatial velocity V_ABp_E of a frame B at a point P fixed on B, measured in a frame A, and expressed in a frame E, is modified to become V_ABq_E, representing the velocity of another point Q on B instead (see class comment for more about this notation). This requires adjusting the translational (linear) velocity component to account for the velocity difference between P and Q due to the angular velocity of B in A.

We are given the vector from point P to point Q, as a position vector p_BpBq_E (or p_PQ_E) expressed in the same frame E as the spatial velocity. The operation performed, in coordinate-free form, is:

  w_AB  = w_AB,  i.e. the angular velocity is unchanged.
  v_ABq = v_ABp + w_AB x p_BpBq

where w and v represent the angular and linear velocity components respectively.

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_BpBq_EShift vector from point P of body B to point Q of B, expressed in frame E. The "from" point Bp must be the point whose velocity is currently represented in this spatial velocity, and E must be the same expressed-in frame as for this spatial velocity.
Returns
A reference to this spatial velocity which is now V_ABq_E, that is, the spatial velocity of frame B at point Q, still measured in frame A and expressed in frame E.
See also
Shift() to compute the shifted spatial velocity without modifying this original object.

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 files: