|
| 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::TransformableGeometricObject * | getTransformableGeometricObject () |
| | 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...
|
| |
| 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 > |
| ForceVector & | operator= (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
. More...
|
| |
| ForceVector | transform_copy (const SpatialTransform &X) const |
| | Copy then transform a ForceVector by
. More...
|
| |
| EIGEN_STRONG_INLINE Vector3d | getAngularPart () const |
| |
| EIGEN_STRONG_INLINE Vector3d | getLinearPart () const |
| |
| template<typename OtherDerived > |
| SpatialVector & | operator= (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) |
| |
| 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...
|
| |
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.