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
-
|
| | SpatialForce () |
| | Default constructor.
|
| | 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 π.
|
| 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 π.
|
| 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.
|
| 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.
|
| T | dot (const SpatialVelocity< T > &velocity) const |
| | Calculates the power generated by a spatial force.
|
| | SpatialForce (const SpatialForce &)=default |
| SpatialForce & | operator= (const SpatialForce &)=default |
| | SpatialForce (SpatialForce &&)=default |
| SpatialForce & | operator= (SpatialForce &&)=default |
| Public Member Functions inherited from SpatialVector< SpatialForce, T > |
| 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.
|
| const T & | operator[] (int i) const |
| | Const access to the i-th element of this spatial vector.
|
| const Vector3< T > & | rotational () const |
| | Const access to the rotational component of this spatial vector.
|
| const Vector3< T > & | translational () const |
| | Const access to the translational component of this spatial vector.
|
| const T * | data () const |
| | Returns a (const) bare pointer to the underlying data.
|
| T * | mutable_data () |
| | Returns a (mutable) bare pointer to the underlying data.
|
| 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).
|
| 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.
|
| 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.
|
| void | SetNaN () |
| | Sets all the elements in this SpatialVector to NaN.
|
| SpatialQuantity & | SetZero () |
| | Sets both the rotational and translational components of this SpatialVector to zero.
|
| CoeffsEigenType & | get_coeffs () |
| | Returns a mutable reference to the underlying storage.
|
| SpatialQuantity | operator- () const |
| | Unary minus operator.
|
| SpatialQuantity & | operator+= (const SpatialQuantity &V) |
| | Addition assignment operator.
|
| SpatialQuantity & | operator-= (const SpatialQuantity &V) |
| | Subtraction assignment operator.
|
| SpatialQuantity & | operator*= (const T &s) |
| | Multiplication assignment operator.
|
| | SpatialVector (const SpatialVector &)=default |
| SpatialVector & | operator= (const SpatialVector &)=default |
template<typename T>
| 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).
- Parameters
-
| [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. |
- 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).