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.
T | The 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... | |
void | 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... | |
T | dot (const SpatialVelocity< T > &velocity) const |
Calculates the power generated by a spatial force. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
SpatialForce (const SpatialForce &)=default | |
SpatialForce & | operator= (const SpatialForce &)=default |
SpatialForce (SpatialForce &&)=default | |
SpatialForce & | operator= (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=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... | |
SpatialQuantity & | SetZero () |
Sets both the rotational and translational components of this SpatialVector to zero. More... | |
CoeffsEigenType & | get_coeffs () |
Returns a mutable reference to the underlying storage. More... | |
const CoeffsEigenType & | get_coeffs () const |
Returns a constant reference to the underlying storage. More... | |
SpatialQuantity | operator- () const |
Unary minus operator. More... | |
SpatialQuantity & | operator+= (const SpatialQuantity &V) |
Addition assignment operator. More... | |
SpatialQuantity & | operator-= (const SpatialQuantity &V) |
Subtraction assignment operator. More... | |
SpatialQuantity & | operator *= (const T &s) |
Multiplication assignment operator. More... | |
SpatialVector (const SpatialVector &)=default | |
SpatialVector (SpatialVector &&)=default | |
SpatialVector & | operator= (const SpatialVector &)=default |
SpatialVector & | operator= (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... | |
Related Functions inherited from SpatialVector< SpatialForce, T > | |
std::ostream & | operator<< (std::ostream &o, const SpatialVector< SpatialQuantity, T > &V) |
Stream insertion operator to write SpatialVector objects into a std::ostream . 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... | |
|
default |
|
default |
SpatialForce | ( | ) |
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 | ( | 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 π.
|
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.
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).
[in] | velocity | which is V_MB_E, frame B's spatial velocity measured in frame M, expressed in the same frame E as this = F_B_E. |
|
default |
|
default |
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.
[in] | offset | which 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). |
F_Bq_E | which is the spatial force on Bq, expressed in frame E. |
this
) and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).
|
static |
Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B.
[in] | spatial_forces | which 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] | offset | which 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_forces | which 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. |
this
). void 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). 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).
[in] | offset | which 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. |
this
and static functions ShiftInPlace() and Shift() to shift multiple spatial forces (with or without modifying the input parameter spatial_forces).
|
static |
Shifts a matrix of spatial forces from one point fixed on frame B to another point fixed on frame B.
[in,out] | spatial_forces | which 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] | offset | which 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. |
this
).
|
related |
Adds two spatial forces by simply adding their 6 underlying elements.
[in] | F1_E | spatial force expressed in the same frame E as F2_E. |
[in] | F2_E | spatial force expressed in the same frame E as F1_E. |
|
related |
Subtracts spatial forces by simply subtracting their 6 underlying elements.
[in] | F1_E | spatial force expressed in the same frame E as F2_E. |
[in] | F2_E | spatial force expressed in the same frame E as F1_E. |