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

A Math::SpatialInertia is a RigidBodyInertia explicitly expressed in a RobotDynamics::ReferenceFrame. The frame a Math::SpatialInertia is expressed in can be changed by calling RobotDynamics::FrameObject::changeFrame. More...

#include <SpatialRigidBodyInertia.hpp>

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

Public Member Functions

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...
 
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...
 
RigidBodyInertiaoperator= (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 $ I_r $ ad Math::SpatialMatrix $ M_I $, returns Math::SpatialMatrix $ M_r $ such that $ M_r = I_r - M_I $. 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...
 
- 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 Attributes inherited from RobotDynamics::Math::RigidBodyInertia
Vector3d h
 
double Ixx
 
double Iyx
 
double Iyy
 
double Izx
 
double Izy
 
double Izz
 
double m
 
- Protected Attributes inherited from RobotDynamics::FrameObject
ReferenceFramePtr referenceFrame
 

Detailed Description

A Math::SpatialInertia is a RigidBodyInertia explicitly expressed in a RobotDynamics::ReferenceFrame. The frame a Math::SpatialInertia is expressed in can be changed by calling RobotDynamics::FrameObject::changeFrame.

Definition at line 32 of file SpatialRigidBodyInertia.hpp.

Constructor & Destructor Documentation

RobotDynamics::Math::SpatialInertia::SpatialInertia ( )
inline

Empty constructor. Initializes FrameObject::referenceFrame to nullptr.

Definition at line 38 of file SpatialRigidBodyInertia.hpp.

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

Constructor.

Parameters
referenceFrame

Definition at line 46 of file SpatialRigidBodyInertia.hpp.

RobotDynamics::Math::SpatialInertia::SpatialInertia ( ReferenceFramePtr  referenceFrame,
double  mass,
const Vector3d com_mass,
const Matrix3d inertia 
)
inline

Constructor.

Parameters
referenceFrame
mass
com_massMass scaled center of mass vector
inertia3x3 inertia tensor

Definition at line 57 of file SpatialRigidBodyInertia.hpp.

RobotDynamics::Math::SpatialInertia::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 
)
inline

Constructor.

Parameters
referenceFrame
m
hMass scaled center of mass
Ixx
Iyx
Iyy
Izx
Izy
Izz

Definition at line 74 of file SpatialRigidBodyInertia.hpp.

RobotDynamics::Math::SpatialInertia::SpatialInertia ( ReferenceFramePtr  referenceFrame,
const RigidBodyInertia inertia 
)
inline

Constructor.

Parameters
referenceFrame
inertia

Definition at line 85 of file SpatialRigidBodyInertia.hpp.

RobotDynamics::Math::SpatialInertia::SpatialInertia ( const SpatialInertia inertia)
inline

Copy constructor.

Parameters
inertia

Definition at line 93 of file SpatialRigidBodyInertia.hpp.

Member Function Documentation

TransformableGeometricObject* RobotDynamics::Math::SpatialInertia::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 97 of file SpatialRigidBodyInertia.hpp.

RobotDynamics::Math::SpatialForce RobotDynamics::Math::SpatialInertia::operator* ( const RobotDynamics::Math::SpatialAcceleration a)
inline

Definition at line 121 of file SpatialRigidBodyInertia.hpp.

void RobotDynamics::Math::SpatialInertia::operator+= ( const SpatialInertia spatialInertia)
inline

Overloaded += operator. Performs frame checks.

Parameters
spatialInertia

Definition at line 115 of file SpatialRigidBodyInertia.hpp.

RigidBodyInertia RobotDynamics::Math::SpatialInertia::toRigidBodyInertia ( ) const
inline

Get a copy of a Math::SpatialInertia as type Math::RigidBodyInertia.

Returns
A copy as type Math::RigidBodyInertia

Definition at line 106 of file SpatialRigidBodyInertia.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