|
double | operator* (const SpatialMotion &vector) |
| Operator that returns the kinetic energy. Given a momentum, and motion vector , the resulting kinetic energy is computed by . Frame checks will be performed. More...
|
|
void | set (const SpatialInertia &inertia, const SpatialMotion &vector) |
| Set a momentums value by computing a momentum from the supplied SpatialInertia and SpatialMotion. Frame checks will be performed. More...
|
|
void | setIncludingFrame (ReferenceFramePtr referenceFrame, const RigidBodyInertia &inertia, const MotionVector &vector) |
| Set a momentum by multiplying the supplied motion vector by the supplied inertia. Set the stored RobotDynamics::FrameObject::referenceFrame to the supplied ReferenceFrame pointer. No frame checks will be performed. More...
|
|
void | setIncludingFrame (ReferenceFramePtr referenceFrame, const ForceVector &f) |
| Constructor. More...
|
|
| SpatialMomentum () |
| Constructor. RobotDynamics::ReferenceFrame is initialized to nullptr. More...
|
|
| SpatialMomentum (ReferenceFramePtr referenceFrame, const double kx, const double ky, const double kz, const double lx, const double ly, const double lz) |
| Costructor. More...
|
|
| SpatialMomentum (ReferenceFramePtr referenceFrame, const Vector3d &k, const Vector3d l) |
| Constructor. More...
|
|
| SpatialMomentum (const SpatialMomentum &SpatialMomentum) |
| Copy constructor. More...
|
|
| SpatialMomentum (ReferenceFramePtr referenceFrame, const ForceVector &forceVector) |
| Constructor. More...
|
|
| SpatialMomentum (ReferenceFramePtr referenceFrame) |
| Constructor. More...
|
|
| SpatialMomentum (const SpatialInertia &inertia, const SpatialMotion &vector) |
| Constructor. Momentum is computed from SpatialInertia and SpatialMotion by . Frame checks are performed. More...
|
|
EIGEN_STRONG_INLINE double & | kx () |
|
EIGEN_STRONG_INLINE double | kx () const |
|
EIGEN_STRONG_INLINE double & | ky () |
|
EIGEN_STRONG_INLINE double | ky () const |
|
EIGEN_STRONG_INLINE double & | kz () |
|
EIGEN_STRONG_INLINE double | kz () const |
|
EIGEN_STRONG_INLINE double & | lx () |
|
EIGEN_STRONG_INLINE double | lx () const |
|
EIGEN_STRONG_INLINE double & | ly () |
|
EIGEN_STRONG_INLINE double | ly () const |
|
EIGEN_STRONG_INLINE double & | lz () |
|
EIGEN_STRONG_INLINE double | lz () const |
|
| Momentum () |
|
| Momentum (const double kx, const double ky, const double kz, const double lx, const double ly, const double lz) |
|
| Momentum (const Vector3d &k, const Vector3d l) |
|
| Momentum (const Momentum &momentum) |
|
| Momentum (const ForceVector &forceVector) |
|
| Momentum (const RigidBodyInertia &inertia, const MotionVector &vector) |
|
EIGEN_STRONG_INLINE double | operator* (const MotionVector &vector) |
| Operator for computing kinetic energy. With momentum, and Math::MotionVector, this performs performs . More...
|
|
Momentum | operator+= (const Momentum &v) |
| Overloaded plus-equals operator. More...
|
|
Momentum | operator-= (const Momentum &v) |
| Overloaded plus-equals operator. More...
|
|
void | set (const RigidBodyInertia &inertia, const MotionVector &vector) |
| Set momentum by computing it from the inertia and velocity. More...
|
|
Momentum | transform_copy (const SpatialTransform &X) const |
| Copy then transform a ForceVector by
. 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 SpatialMomentum is a Momentum expressed in a RobotDynamics::ReferenceFrame. The angular portion of the vector is referred to as and the linear portion as .
Definition at line 32 of file SpatialMomentum.hpp.