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

Detailed Description

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

This class represents a spatial force F (also called a wrench) and has 6 elements with a torque 𝛕 (3-element vector) on top of a force 𝐟 (3-element vector).

Frequently, a spatial force represents the replacement of a set S of forces on a frame B with an equivalent set consisting of a torque 𝛕 applied to frame B which is equal to the moment of the set S about a point Bp of B together with a force 𝐟 applied to Bp, where 𝐟 is equal to set S's resultant force. This class assumes that both the torque 𝛕 and force 𝐟 have the same expressed-in frame E. This class only stores 6 elements (namely 𝛕 and 𝐟) and does not store the underlying frame B, application point Bp, or expressed-in frame E. The user is responsible for explicitly tracking these underlying quantities with monogram notation. For example, F_B_E denotes a spatial force on frame B with application point Bo (frame B's origin), expressed in frame E and contains tau_B_E (torque 𝛕 applied to frame B, expressed in frame E) and f_Bo_E (force 𝐟 applied to Bo, expressed in frame E).

The monogram notation F_Bp has a typeset equivalent \({F^{Bp}}\) which denotes the spatial force applied to point Bp of frame B. F_Bp contains a torque tau_B ( \({\tau^B}\)) applied to frame B and a force f_Bp ( \({f^{Bp}}\)) applied to point Bp of frame B. 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_force.h>

Public Member Functions

 SpatialForce ()
 Default constructor. More...
 
 SpatialForce (const Eigen::Ref< const Vector3< T >> &tau, const Eigen::Ref< const Vector3< T >> &f)
 Constructs a spatial force F from a torque 𝛕 (tau) and a force 𝐟. More...
 
template<typename Derived >
 SpatialForce (const Eigen::MatrixBase< Derived > &F)
 Constructs a spatial force F from an Eigen expression that represents a 6-element vector, i.e., a 3-element torque 𝛕 and a 3-element force 𝐟. More...
 
SpatialForce< T > & ShiftInPlace (const Vector3< T > &offset)
 In-place shift of a SpatialForce from one point fixed on frame B to another fixed on frame B. More...
 
SpatialForce< T > Shift (const Vector3< T > &offset) const
 Shifts a SpatialForce from one point fixed on frame B to another point fixed on frame B. More...
 
dot (const SpatialVelocity< T > &velocity) const
 Calculates the power generated by a spatial force. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 SpatialForce (const SpatialForce &)=default
 
SpatialForceoperator= (const SpatialForce &)=default
 
 SpatialForce (SpatialForce &&)=default
 
SpatialForceoperator= (SpatialForce &&)=default
 
- Public Member Functions inherited from SpatialVector< SpatialForce, 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=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
 

Static Public Member Functions

static void ShiftInPlace (EigenPtr< Matrix6X< T >> spatial_forces, const Vector3< T > &offset)
 Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B. More...
 
static void Shift (const Eigen::Ref< const Matrix6X< T >> &spatial_forces, const Vector3< T > &offset, EigenPtr< Matrix6X< T >> shifted_forces)
 Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B. More...
 
- Static Public Member Functions inherited from SpatialVector< SpatialForce, T >
static SpatialQuantity Zero ()
 Factory to create a zero spatial vector, i.e., a SpatialVector whose rotational and translational components are both zero. More...
 

Related Functions

(Note that these are not member functions.)

template<typename T >
SpatialForce< T > operator+ (const SpatialForce< T > &F1_E, const SpatialForce< T > &F2_E)
 Adds two spatial forces by simply adding their 6 underlying elements. More...
 
template<typename T >
SpatialForce< T > operator- (const SpatialForce< T > &F1_E, const SpatialForce< T > &F2_E)
 Subtracts spatial forces by simply subtracting their 6 underlying elements. More...
 

Additional Inherited Members

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

Constructor & Destructor Documentation

◆ SpatialForce() [1/5]

SpatialForce ( const SpatialForce< T > &  )
default

◆ SpatialForce() [2/5]

SpatialForce ( SpatialForce< T > &&  )
default

◆ SpatialForce() [3/5]

Default constructor.

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

◆ SpatialForce() [4/5]

SpatialForce ( const Eigen::Ref< const Vector3< T >> &  tau,
const Eigen::Ref< const Vector3< T >> &  f 
)

Constructs a spatial force F from a torque 𝛕 (tau) and a force 𝐟.

◆ SpatialForce() [5/5]

SpatialForce ( const Eigen::MatrixBase< Derived > &  F)
explicit

Constructs a spatial force F from an Eigen expression that represents a 6-element vector, i.e., a 3-element torque 𝛕 and a 3-element force 𝐟.

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

Member Function Documentation

◆ dot()

T dot ( const SpatialVelocity< T > &  velocity) const

Calculates the power generated by a spatial force.

For an arbitrary frame B, calculates the dot-product of this = F_B_E (frame B's spatial force, expressed in frame E) with V_MB_E (frame B's spatial velocity measured in a frame M, expressed in a frame E).

Parameters
[in]velocitywhich is V_MB_E, frame B's spatial velocity measured in frame M, expressed in the same frame E as this = F_B_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.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ Shift() [1/2]

SpatialForce<T> Shift ( const Vector3< T > &  offset) const

Shifts a SpatialForce from one point fixed on frame B to another point fixed on frame B.

Parameters
[in]offsetwhich is the position vector p_BpBq_E from point Bp (fixed on frame B) to point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as this spatial force, where this is F_Bp_E (spatial force on Bp, expressed in frame E).
Return values
F_Bq_Ewhich is the spatial force on Bq, expressed in frame E.
See also
Member function ShiftInPlace() to shift one spatial force (modifying this) and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).

◆ Shift() [2/2]

static void Shift ( const Eigen::Ref< const Matrix6X< T >> &  spatial_forces,
const Vector3< T > &  offset,
EigenPtr< Matrix6X< T >>  shifted_forces 
)
static

Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B.

Parameters
[in]spatial_forceswhich is the 6 x n matrix F_Bp_E_all, where each of the n columns is a spatial force applied to a point Bp of frame B, and where each spatial forces is expressed in a frame E.
[in]offsetwhich is the position vector p_BpBq_E from point Bp (fixed on frame B) to a point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as in spatial_forces.
[out]shifted_forceswhich is the 6 x n matrix F_Bq_E_all, where each of the n columns is a spatial force which was shifted from point Bp (fixed on B) to point Bq (fixed on B). On output, each spatial force contained in shifted_forces is expressed in frame E.
Precondition
shifted_forces must be non-null and must point to a 6 x n matrix (i.e., it must be the same size as the input matrix spatial_forces).
See also
Static function ShiftInPlace() to shift multiple spatial forces with modification to the input parameter spatial_forces and member functions ShiftInPlace() and Shift() to shift one spatial force (with or without modifying this).
Note
Although this Shift() function will work properly if the input and output matrices are the same (i.e., spatial_forces = shifted_forces), it is faster and more efficient (avoids copying) to use ShiftInPlace().

◆ ShiftInPlace() [1/2]

SpatialForce<T>& ShiftInPlace ( const Vector3< T > &  offset)

In-place shift of a SpatialForce from one point fixed on frame B to another fixed on frame B.

On entry, this is F_Bp_E (spatial force on point Bp of frame B, expressed in a frame E). On return this is modified to F_Bq_E (spatial force on point Bq of frame B, expressed in frame E).

Parameters
[in]offsetwhich is the position vector p_BpBq_E from point Bp (fixed on frame B) to point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as this spatial force.
Return values
F_Bq_Ereference to this spatial force which has been modified to be the spatial force on point Bq of B, expressed in frame E. The components of F_Bq_E are calculated as:
   Ο„_B  = Ο„_B -  p_BpBq x f_Bp    (the torque 𝛕 stored in `this` changes).
 f_Bq_E = f_Bp_E              (the force 𝐟 stored in `this` is unchanged).
Note: There are related functions that shift spatial momentum and spatial velocity (see SpatialMomentum::Shift() and SpatialVelocity:Shift()).
See also
Member function Shift() to shift one spatial force without modifying this and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).

◆ ShiftInPlace() [2/2]

static void ShiftInPlace ( EigenPtr< Matrix6X< T >>  spatial_forces,
const Vector3< T > &  offset 
)
static

Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B.

Parameters
[in,out]spatial_forceswhich is the 6 x n matrix F_Bp_E_all, where each of the n columns is a spatial force expressed in a frame E. On input, each spatial force is applied to a point Bp of frame B. On output, each spatial force has been shifted to a point Bq of frame B. In other words, on output, spatial_forces = F_Bq_E_all.
[in]offsetwhich is the position vector p_BpBq_E from point Bp (fixed on frame B) to a point Bq (fixed on frame B), expressed in frame E. p_BpBq_E must have the same expressed-in frame E as in spatial_forces.
See also
Static function Shift() to shift multiple spatial forces without modifying the input parameter spatial_forces and member functions ShiftInPlace() and Shift() to shift one spatial force (with or without modifying this).

Friends And Related Function Documentation

◆ operator+()

SpatialForce< T > operator+ ( const SpatialForce< T > &  F1_E,
const SpatialForce< T > &  F2_E 
)
related

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

Parameters
[in]F1_Espatial force expressed in the same frame E as F2_E.
[in]F2_Espatial force expressed in the same frame E as F1_E.
Note
The general utility of this operator+() function seems limited to situations when F1 and F2 are associated with different sets of forces, but are applied to the same frame B, with same application point Bp, and have the same expressed-in frame E.

◆ operator-()

SpatialForce< T > operator- ( const SpatialForce< T > &  F1_E,
const SpatialForce< T > &  F2_E 
)
related

Subtracts spatial forces by simply subtracting their 6 underlying elements.

Parameters
[in]F1_Espatial force expressed in the same frame E as F2_E.
[in]F2_Espatial force expressed in the same frame E as F1_E.
Note
The general utility of this operator-() function seems limited to situations when F1 and F2 are associated with different sets of forces, but are applied to the same frame B, with same application point Bp, and have the same expressed-in frame E.

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