|
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...
|
|
RobotDynamics::Math::SpatialForce | operator* (const RobotDynamics::Math::SpatialAcceleration &a) |
|
void | operator+= (const SpatialInertia &spatialInertia) |
| Overloaded += operator. Performs frame checks. More...
|
|
| SpatialInertia () |
| Empty constructor. Initializes FrameObject::referenceFrame to nullptr. More...
|
|
| SpatialInertia (ReferenceFramePtr referenceFrame) |
| Constructor. More...
|
|
| SpatialInertia (ReferenceFramePtr referenceFrame, double mass, const Vector3d &com_mass, const Matrix3d &inertia) |
| Constructor. More...
|
|
| SpatialInertia (ReferenceFramePtr referenceFrame, double m, const Vector3d &h, const double Ixx, const double Iyx, const double Iyy, const double Izx, const double Izy, const double Izz) |
| Constructor. More...
|
|
| SpatialInertia (ReferenceFramePtr referenceFrame, const RigidBodyInertia &inertia) |
| Constructor. More...
|
|
| SpatialInertia (const SpatialInertia &inertia) |
| Copy constructor. More...
|
|
RigidBodyInertia | toRigidBodyInertia () const |
| Get a copy of a Math::SpatialInertia as type Math::RigidBodyInertia. More...
|
|
Public Member Functions inherited from RobotDynamics::Math::RigidBodyInertia |
void | createFromMatrix (const SpatialMatrix &Ic) |
| Create a Math::RigidBodyInertia object from a 6x6 Math::SpatialMatrix. More...
|
|
Matrix63 | multiplyMatrix63 (Matrix63 m) const |
| A helper method that returns a 6x3 matrix that is a Math::RigidBodyInertia multiplied by a 6x3 matrix. More...
|
|
void | operator+= (const RigidBodyInertia &rbi) |
| Overloaded plus-equals operator. Adds two inertia matrices. More...
|
|
RigidBodyInertia & | operator= (const RigidBodyInertia &other) |
|
| RigidBodyInertia () |
| Constructor. More...
|
|
| RigidBodyInertia (double mass, const Vector3d &com_mass, const Matrix3d &inertia) |
| Constructor. More...
|
|
| RigidBodyInertia (double m, const Vector3d &h, const double Ixx, const double Iyx, const double Iyy, const double Izx, const double Izy, const double Izz) |
| Constructor. More...
|
|
| RigidBodyInertia (const RigidBodyInertia &inertia) |
| Copy constructor. More...
|
|
void | set (const RigidBodyInertia &I) |
| Setter. More...
|
|
void | set (double m, const Vector3d &h, const double Ixx, const double Iyx, const double Iyy, const double Izx, const double Izy, const double Izz) |
| Setter. More...
|
|
void | setSpatialMatrix (SpatialMatrix &mat) const |
| Store a Math::RigidBodyInertia in the Math::SpatialMatrix. More...
|
|
SpatialMatrix | subtractSpatialMatrix (const SpatialMatrix &m) const |
| Given Math::RigidBodyInertia ad Math::SpatialMatrix , returns Math::SpatialMatrix such that . More...
|
|
SpatialVector | timesSpatialVector (const SpatialVector &v) const |
| Multiply a Math::RigidBodyInertia by a Math::SpatialVector and return the result as a new Math::SpatialVector. More...
|
|
SpatialMatrix | toMatrix () const |
|
void | transform (const SpatialTransform &X) |
| Transform a Math::RigidBodyInertia matrix. More...
|
|
RigidBodyInertia | transform_copy (const SpatialTransform &X) const |
| Copy, transform, and return a Math::RigidBodyInertia. More...
|
|
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...
|
|