Inertial Class Reference

A class for inertial information about a link. More...

#include <physics/physics.hh>

Public Member Functions

 Inertial ()
 Default Constructor. More...
 
 Inertial (double _mass)
 Constructor. More...
 
 Inertial (const Inertial &_inertial)
 Copy constructor. More...
 
virtual ~Inertial ()
 Destructor. More...
 
const math::Vector3GetCoG () const
 Get the center of gravity. More...
 
Inertial GetInertial (const math::Pose &_frameOffset) const
 Get equivalent Inertia values with the Link frame offset, while holding the Pose of CoG constant in the world frame. More...
 
double GetIXX () const
 Get IXX. More...
 
double GetIXY () const
 Get IXY. More...
 
double GetIXZ () const
 Get IXZ. More...
 
double GetIYY () const
 Get IYY. More...
 
double GetIYZ () const
 Get IXZ. More...
 
double GetIZZ () const
 Get IZZ. More...
 
double GetMass () const
 Get the mass. More...
 
math::Matrix3 GetMOI (const math::Pose &_pose) const
 Get the equivalent inertia from a point in local Link frame If you specify GetMOI(this->GetPose()), you should get back the Moment of Inertia (MOI) exactly as specified in the SDF. More...
 
math::Matrix3 GetMOI () const
 returns Moments of Inertia as a Matrix3 More...
 
const math::Pose GetPose () const
 Get the pose about which the mass and inertia matrix is specified in the Link frame. More...
 
math::Vector3 GetPrincipalMoments () const
 Get the principal moments of inertia (Ixx, Iyy, Izz). More...
 
math::Vector3 GetProductsofInertia () const
 Get the products of inertia (Ixy, Ixz, Iyz). More...
 
void Load (sdf::ElementPtr _sdf)
 Load from SDF values. More...
 
Inertial operator+ (const Inertial &_inertial) const
 Addition operator. More...
 
const Inertialoperator+= (const Inertial &_inertial)
 Addition equal operator. More...
 
Inertialoperator= (const Inertial &_inertial)
 Equal operator. More...
 
void ProcessMsg (const msgs::Inertial &_msg)
 Update parameters from a message. More...
 
void Reset ()
 Reset all the mass properties. More...
 
void Rotate (const math::Quaternion &_rot)
 Rotate this mass. More...
 
void SetCoG (double _cx, double _cy, double _cz)
 Set the center of gravity. More...
 
void SetCoG (const math::Vector3 &_center)
 Set the center of gravity. More...
 
void SetCoG (double _cx, double _cy, double _cz, double _rx, double _ry, double _rz)
 Set the center of gravity and rotation offset of inertial coordinate frame relative to Link frame. More...
 
void SetCoG (const math::Pose &_c)
 Set the center of gravity. More...
 
void SetInertiaMatrix (double _ixx, double _iyy, double _izz, double _ixy, double _ixz, double iyz)
 Set the mass matrix. More...
 
void SetIXX (double _v)
 Set IXX. More...
 
void SetIXY (double _v)
 Set IXY. More...
 
void SetIXZ (double _v)
 Set IXZ. More...
 
void SetIYY (double _v)
 Set IYY. More...
 
void SetIYZ (double _v)
 Set IYZ. More...
 
void SetIZZ (double _v)
 Set IZZ. More...
 
void SetMass (double m)
 Set the mass. More...
 
void SetMOI (const math::Matrix3 &_moi)
 Sets Moments of Inertia (MOI) from a Matrix3. More...
 
void UpdateParameters (sdf::ElementPtr _sdf)
 update the parameters using new sdf values. More...
 

Friends

std::ostream & operator<< (std::ostream &_out, const gazebo::physics::Inertial &_inertial)
 Output operator. More...
 

Detailed Description

A class for inertial information about a link.

Constructor & Destructor Documentation

§ Inertial() [1/3]

Inertial ( )

Default Constructor.

§ Inertial() [2/3]

Inertial ( double  _mass)
explicit

Constructor.

Parameters
[in]_massMass value in kg if using metric.

§ Inertial() [3/3]

Inertial ( const Inertial _inertial)

Copy constructor.

Parameters
[in]_inertialInertial element to copy

§ ~Inertial()

virtual ~Inertial ( )
virtual

Destructor.

Member Function Documentation

§ GetCoG()

const math::Vector3& GetCoG ( ) const
inline

Get the center of gravity.

Returns
The center of gravity.

References Pose::pos.

§ GetInertial()

Inertial GetInertial ( const math::Pose _frameOffset) const

Get equivalent Inertia values with the Link frame offset, while holding the Pose of CoG constant in the world frame.

Parameters
[in]_frameOffsetamount to offset the Link frame by, this is a transform defined in the Link frame.
Returns
Inertial parameters with the shifted frame.

Referenced by Inertial::GetPose().

§ GetIXX()

double GetIXX ( ) const

Get IXX.

Returns
IXX value

Referenced by Inertial::GetPose().

§ GetIXY()

double GetIXY ( ) const

Get IXY.

Returns
IXY value

Referenced by Inertial::GetPose().

§ GetIXZ()

double GetIXZ ( ) const

Get IXZ.

Returns
IXZ value

Referenced by Inertial::GetPose().

§ GetIYY()

double GetIYY ( ) const

Get IYY.

Returns
IYY value

Referenced by Inertial::GetPose().

§ GetIYZ()

double GetIYZ ( ) const

Get IXZ.

Returns
IYZ value

Referenced by Inertial::GetPose().

§ GetIZZ()

double GetIZZ ( ) const

Get IZZ.

Returns
IZZ value

Referenced by Inertial::GetPose().

§ GetMass()

double GetMass ( ) const

Get the mass.

§ GetMOI() [1/2]

math::Matrix3 GetMOI ( const math::Pose _pose) const

Get the equivalent inertia from a point in local Link frame If you specify GetMOI(this->GetPose()), you should get back the Moment of Inertia (MOI) exactly as specified in the SDF.

If _pose is different from pose of the Inertial block, then the MOI is rotated accordingly, and contributions from changes in MOI location location due to point mass is added to the final MOI.

Parameters
[in]_poselocation in Link local frame
Returns
equivalent inertia at _pose

§ GetMOI() [2/2]

math::Matrix3 GetMOI ( ) const

returns Moments of Inertia as a Matrix3

Returns
Moments of Inertia as a Matrix3

Referenced by Inertial::GetPose().

§ GetPose()

§ GetPrincipalMoments()

math::Vector3 GetPrincipalMoments ( ) const

Get the principal moments of inertia (Ixx, Iyy, Izz).

Returns
The principal moments.

Referenced by Inertial::GetPose().

§ GetProductsofInertia()

math::Vector3 GetProductsofInertia ( ) const

Get the products of inertia (Ixy, Ixz, Iyz).

Returns
The products of inertia.

Referenced by Inertial::GetPose().

§ Load()

void Load ( sdf::ElementPtr  _sdf)

Load from SDF values.

Parameters
[in]_sdfSDF value to load from.

§ operator+()

Inertial operator+ ( const Inertial _inertial) const

Addition operator.

Assuming both CG and Moment of Inertia (MOI) are defined in the same reference Link frame. New CG is computed from masses and perspective offsets, and both MOI contributions relocated to the new cog.

Parameters
[in]_inertialInertial to add.
Returns
The result of the addition.

Referenced by Inertial::GetPose().

§ operator+=()

const Inertial& operator+= ( const Inertial _inertial)

Addition equal operator.

Parameters
[in]_inertialInertial to add.
Returns
Reference to this object.

Referenced by Inertial::GetPose().

§ operator=()

Inertial& operator= ( const Inertial _inertial)

Equal operator.

Parameters
[in]_inertialInertial to copy.
Returns
Reference to this object.

Referenced by Inertial::GetPose().

§ ProcessMsg()

void ProcessMsg ( const msgs::Inertial &  _msg)

Update parameters from a message.

Parameters
[in]_msgMessage to read

Referenced by Inertial::GetPose().

§ Reset()

void Reset ( )

Reset all the mass properties.

§ Rotate()

void Rotate ( const math::Quaternion _rot)

Rotate this mass.

Parameters
[in]_rotRotation amount.

Referenced by Inertial::GetPose().

§ SetCoG() [1/4]

void SetCoG ( double  _cx,
double  _cy,
double  _cz 
)

Set the center of gravity.

Parameters
[in]_cxX position.
[in]_cyY position.
[in]_czZ position.

§ SetCoG() [2/4]

void SetCoG ( const math::Vector3 _center)

Set the center of gravity.

Parameters
[in]_centerCenter of the gravity.

§ SetCoG() [3/4]

void SetCoG ( double  _cx,
double  _cy,
double  _cz,
double  _rx,
double  _ry,
double  _rz 
)

Set the center of gravity and rotation offset of inertial coordinate frame relative to Link frame.

Parameters
[in]_cxCenter offset in x-direction in Link frame
[in]_cyCenter offset in y-direction in Link frame
[in]_czCenter offset in z-direction in Link frame
[in]_rxRoll angle offset of inertial coordinate frame.
[in]_ryPitch angle offset of inertial coordinate frame.
[in]_rzYaw angle offset of inertial coordinate frame.

§ SetCoG() [4/4]

void SetCoG ( const math::Pose _c)

Set the center of gravity.

Parameters
[in]_cTransform to center of gravity.

§ SetInertiaMatrix()

void SetInertiaMatrix ( double  _ixx,
double  _iyy,
double  _izz,
double  _ixy,
double  _ixz,
double  iyz 
)

Set the mass matrix.

Parameters
[in]_ixxX second moment of inertia (MOI) about x axis.
[in]_iyyY second moment of inertia about y axis.
[in]_izzZ second moment of inertia about z axis.
[in]_ixyXY inertia.
[in]_ixzXZ inertia.
[in]_iyzYZ inertia.

§ SetIXX()

void SetIXX ( double  _v)

Set IXX.

Parameters
[in]_vIXX value

Referenced by Inertial::GetPose().

§ SetIXY()

void SetIXY ( double  _v)

Set IXY.

Parameters
[in]_vIXY value

Referenced by Inertial::GetPose().

§ SetIXZ()

void SetIXZ ( double  _v)

Set IXZ.

Parameters
[in]_vIXZ value

Referenced by Inertial::GetPose().

§ SetIYY()

void SetIYY ( double  _v)

Set IYY.

Parameters
[in]_vIYY value

Referenced by Inertial::GetPose().

§ SetIYZ()

void SetIYZ ( double  _v)

Set IYZ.

Parameters
[in]_vIXX value

Referenced by Inertial::GetPose().

§ SetIZZ()

void SetIZZ ( double  _v)

Set IZZ.

Parameters
[in]_vIZZ value

Referenced by Inertial::GetPose().

§ SetMass()

void SetMass ( double  m)

Set the mass.

§ SetMOI()

void SetMOI ( const math::Matrix3 _moi)

Sets Moments of Inertia (MOI) from a Matrix3.

Parameters
[in]Momentsof Inertia as a Matrix3

§ UpdateParameters()

void UpdateParameters ( sdf::ElementPtr  _sdf)

update the parameters using new sdf values.

Parameters
[in]_sdfUpdate values from.

Friends And Related Function Documentation

§ operator<<

std::ostream& operator<< ( std::ostream &  _out,
const gazebo::physics::Inertial _inertial 
)
friend

Output operator.

Parameters
[in]_outOutput stream.
[in]_inertialInertial object to output.

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