Public Member Functions | List of all members
RobotDynamics::Math::SpatialForce Class Reference

A SpatialForce is a spatial vector with the angular part being three moments and the linear part being 3 linear forces. More...

#include <SpatialForce.hpp>

Inheritance diagram for RobotDynamics::Math::SpatialForce:
Inheritance graph
[legend]

Public Member Functions

SpatialForce changeFrameAndCopy (ReferenceFramePtr referenceFrame) const
 Copy and change frame. More...
 
FrameVector getFramedAngularPart () const
 Get angular part of spatial force as a frame vector. More...
 
FrameVector getFramedLinearPart () const
 Get linear part of spatial force as a frame vector. More...
 
Math::TransformableGeometricObjectgetTransformableGeometricObject ()
 Pure virtual method that FrameObjects are required to implement so the FrameObject::changeFrame method is able to access the TransformableGeometricObject which is required to implement the TransformableGeometricObject::transform method. More...
 
SpatialForce operator*= (double scale)
 Operator for scaling a spatial force vector. More...
 
SpatialForce operator+= (const SpatialForce &f)
 Overloaded += operator. Frame checks are performed. More...
 
SpatialForce operator-= (const SpatialForce &f)
 Overloaded -= operator. Frame checks are performed. More...
 
void setIncludingFrame (ReferenceFramePtr referenceFrame, const SpatialVector &v)
 
void setIncludingFrame (ReferenceFramePtr referenceFrame, double wx, double wy, double wz, double vx, double vy, double vz)
 
void setIncludingFrame (ReferenceFramePtr referenceFrame, const Vector3d &m, const Vector3d &f)
 
 SpatialForce ()
 Constructor. RobotDynamics::FrameObject::referenceFrame is initialized to nullptr. More...
 
 SpatialForce (ReferenceFramePtr referenceFrame)
 Constructor. Force vector elements will be zero. More...
 
 SpatialForce (ReferenceFramePtr referenceFrame, const double mx, const double my, const double mz, const double fx, const double fy, const double fz)
 Constructor. More...
 
 SpatialForce (ReferenceFramePtr referenceFrame, const Vector3d &m, const Vector3d f)
 Constructor. More...
 
 SpatialForce (const SpatialForce &spatialForce)
 Copy constructor. More...
 
 SpatialForce (ReferenceFramePtr referenceFrame, const SpatialVector &spatialVector)
 Constructor. More...
 
ForceVector toForceVector () const
 Get copy of this SpatialForce as type ForceVector. More...
 
- Public Member Functions inherited from RobotDynamics::Math::ForceVector
template<typename OtherDerived >
 ForceVector (const Eigen::MatrixBase< OtherDerived > &other)
 Constructor. More...
 
EIGEN_STRONG_INLINE ForceVector ()
 Empty constructor. More...
 
 ForceVector (const double mx, const double my, const double mz, const double fx, const double fy, const double fz)
 Constructor. More...
 
EIGEN_STRONG_INLINE double & fx ()
 Get reference to x-linear component. More...
 
EIGEN_STRONG_INLINE double fx () const
 Get copy of x-linear component. More...
 
EIGEN_STRONG_INLINE double & fy ()
 Get reference to y-linear component. More...
 
EIGEN_STRONG_INLINE double fy () const
 Get copy of y-linear component. More...
 
EIGEN_STRONG_INLINE double & fz ()
 Get reference to z-linear component. More...
 
EIGEN_STRONG_INLINE double fz () const
 Get copy of z-linear component. More...
 
EIGEN_STRONG_INLINE double & mx ()
 Get reference to x-angular component. More...
 
EIGEN_STRONG_INLINE double mx () const
 Get copy of x-angular component. More...
 
EIGEN_STRONG_INLINE double & my ()
 Get reference to y-angular component. More...
 
EIGEN_STRONG_INLINE double my () const
 Get copy of y-angular component. More...
 
EIGEN_STRONG_INLINE double & mz ()
 Get reference to z-angular component. More...
 
EIGEN_STRONG_INLINE double mz () const
 Get copy of z-angular component. More...
 
ForceVector operator+= (const ForceVector &v)
 Overloaded plus-equals operator. More...
 
template<typename OtherDerived >
ForceVectoroperator= (const Eigen::MatrixBase< OtherDerived > &other)
 
EIGEN_STRONG_INLINE void set (const ForceVector &f)
 Setter. More...
 
EIGEN_STRONG_INLINE SpatialVector toSpatialVector () const
 Get a copy of a ForceVector as type SpatialVector. More...
 
void transform (const SpatialTransform &X)
 Performs the following in place transform

\[ f = \begin{bmatrix} X.E & -X.E(X.r\times) \\ \mathbf{0} & X.E \end{bmatrix} f \]

. More...

 
ForceVector transform_copy (const SpatialTransform &X) const
 Copy then transform a ForceVector by

\[ f_2 = \begin{bmatrix} X.E & -X.E(X.r\times) \\ \mathbf{0} & X.E \end{bmatrix} f_1 \]

. More...

 
- Public Member Functions inherited from RobotDynamics::Math::SpatialVector
EIGEN_STRONG_INLINE Vector3d getAngularPart () const
 
EIGEN_STRONG_INLINE Vector3d getLinearPart () const
 
template<typename OtherDerived >
SpatialVectoroperator= (const Eigen::MatrixBase< OtherDerived > &other)
 
EIGEN_STRONG_INLINE void set (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5)
 
EIGEN_STRONG_INLINE void set (const Vector3d &angularPart, const Vector3d &linearPart)
 
void setAngularPart (const Vector3d &v)
 
void setLinearPart (const Vector3d &v)
 
template<typename OtherDerived >
 SpatialVector (const Eigen::MatrixBase< OtherDerived > &other)
 
EIGEN_STRONG_INLINE SpatialVector ()
 
EIGEN_STRONG_INLINE SpatialVector (const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5)
 
- Public Member Functions inherited from RobotDynamics::FrameObject
virtual void changeFrame (ReferenceFramePtr desiredFrame)
 Change the ReferenceFrame this FrameObject is expressed in. More...
 
void checkReferenceFramesMatch (const FrameObject *frameObject) const
 Check if two ReferenceFrameHolders hold the same ReferenceFrame. More...
 
void checkReferenceFramesMatch (FrameObject *frameObject) const
 
 FrameObject (ReferenceFramePtr referenceFrame)
 
ReferenceFramePtr getReferenceFrame () const
 Get a pointer to the reference frame this FrameObject is expressed in. More...
 
void setReferenceFrame (ReferenceFramePtr frame)
 Set frame objects internal reference frame. More...
 
virtual ~FrameObject ()
 Destructor. More...
 

Additional Inherited Members

- Public Types inherited from RobotDynamics::Math::SpatialVector
typedef Eigen::Matrix< double, 6, 1 > Base
 
- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 

Detailed Description

A SpatialForce is a spatial vector with the angular part being three moments and the linear part being 3 linear forces.

Definition at line 32 of file SpatialForce.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::SpatialForce::SpatialForce ( )
inline

Constructor. RobotDynamics::FrameObject::referenceFrame is initialized to nullptr.

Definition at line 38 of file SpatialForce.hpp.

RobotDynamics::Math::SpatialForce::SpatialForce ( ReferenceFramePtr  referenceFrame)
inlineexplicit

Constructor. Force vector elements will be zero.

Parameters
referenceFrameFrame spatial force will be expressed in

Definition at line 46 of file SpatialForce.hpp.

RobotDynamics::Math::SpatialForce::SpatialForce ( ReferenceFramePtr  referenceFrame,
const double  mx,
const double  my,
const double  mz,
const double  fx,
const double  fy,
const double  fz 
)
inline

Constructor.

Parameters
referenceFrameReferenceFrame this force vector is expressed in
mxx-Momentum
myy-Momentum
mzz-Momentum
fxx-Force
fyy-Force
fzz-Force

Definition at line 60 of file SpatialForce.hpp.

RobotDynamics::Math::SpatialForce::SpatialForce ( ReferenceFramePtr  referenceFrame,
const Vector3d m,
const Vector3d  f 
)
inline

Constructor.

Parameters
referenceFrameReferenceFrame this force vector is expressed in
mVector containing the angular component
fVector containing the linear component

Definition at line 71 of file SpatialForce.hpp.

RobotDynamics::Math::SpatialForce::SpatialForce ( const SpatialForce spatialForce)
inline

Copy constructor.

Parameters
spatialForce

Definition at line 115 of file SpatialForce.hpp.

RobotDynamics::Math::SpatialForce::SpatialForce ( ReferenceFramePtr  referenceFrame,
const SpatialVector spatialVector 
)
inline

Constructor.

Parameters
referenceFrameReferenceFrame this force vector is expressed in
spatialVector

Definition at line 124 of file SpatialForce.hpp.

Member Function Documentation

SpatialForce RobotDynamics::Math::SpatialForce::changeFrameAndCopy ( ReferenceFramePtr  referenceFrame) const
inline

Copy and change frame.

Parameters
referenceFrame
Returns
Copied spatial transform with frame changed

Definition at line 86 of file SpatialForce.hpp.

FrameVector RobotDynamics::Math::SpatialForce::getFramedAngularPart ( ) const
inline

Get angular part of spatial force as a frame vector.

Returns
FrameVector consisting of the reference frame and the angular portion

Definition at line 106 of file SpatialForce.hpp.

FrameVector RobotDynamics::Math::SpatialForce::getFramedLinearPart ( ) const
inline

Get linear part of spatial force as a frame vector.

Returns
FrameVector consisting of the reference frame and the linear portion

Definition at line 97 of file SpatialForce.hpp.

Math::TransformableGeometricObject* RobotDynamics::Math::SpatialForce::getTransformableGeometricObject ( )
inlinevirtual

Pure virtual method that FrameObjects are required to implement so the FrameObject::changeFrame method is able to access the TransformableGeometricObject which is required to implement the TransformableGeometricObject::transform method.

Returns

Implements RobotDynamics::FrameObject.

Definition at line 76 of file SpatialForce.hpp.

SpatialForce RobotDynamics::Math::SpatialForce::operator*= ( double  scale)
inline

Operator for scaling a spatial force vector.

Parameters
scaleEach force element will be multiplied by this scale
Returns
$ f_sp = f_sp * scale $

Definition at line 160 of file SpatialForce.hpp.

SpatialForce RobotDynamics::Math::SpatialForce::operator+= ( const SpatialForce f)
inline

Overloaded += operator. Frame checks are performed.

Parameters
f
Returns
$ f_sp=f_sp+f $

Definition at line 178 of file SpatialForce.hpp.

SpatialForce RobotDynamics::Math::SpatialForce::operator-= ( const SpatialForce f)
inline

Overloaded -= operator. Frame checks are performed.

Parameters
f
Returns
$ f_sp=f_sp-f $

Definition at line 198 of file SpatialForce.hpp.

void RobotDynamics::Math::SpatialForce::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
const SpatialVector v 
)
inline

Definition at line 137 of file SpatialForce.hpp.

void RobotDynamics::Math::SpatialForce::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
double  wx,
double  wy,
double  wz,
double  vx,
double  vy,
double  vz 
)
inline

Definition at line 143 of file SpatialForce.hpp.

void RobotDynamics::Math::SpatialForce::setIncludingFrame ( ReferenceFramePtr  referenceFrame,
const Vector3d m,
const Vector3d f 
)
inline

Definition at line 149 of file SpatialForce.hpp.

ForceVector RobotDynamics::Math::SpatialForce::toForceVector ( ) const
inline

Get copy of this SpatialForce as type ForceVector.

Returns
A SpatialForce as type ForceVector

Definition at line 132 of file SpatialForce.hpp.


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


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28