Inertial Class Reference

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

#include <physics/physics.hh>

Public Member Functions

 Inertial ()
 Default Constructor. More...
 
 Inertial (const double _mass)
 Constructor. More...
 
 Inertial (const ignition::math::Inertiald &_inertial)
 Constructor from ignition::math::Inertial. More...
 
 Inertial (const Inertial &_inertial)
 Copy constructor. More...
 
virtual ~Inertial ()
 Destructor. More...
 
const ignition::math::Vector3d & CoG () const
 Get the center of gravity. More...
 
ignition::math::Inertiald Ign () const
 Return copy of Inertial in ignition format. More...
 
double IXX () const
 Get IXX. More...
 
double IXY () const
 Get IXY. More...
 
double IXZ () const
 Get IXZ. More...
 
double IYY () const
 Get IYY. More...
 
double IYZ () const
 Get IYZ. More...
 
double IZZ () const
 Get IZZ. More...
 
void Load (sdf::ElementPtr _sdf)
 Load from SDF values. More...
 
double Mass () const
 Get the mass. More...
 
ignition::math::Matrix3d MOI (const ignition::math::Pose3d &_pose) const
 Get the equivalent inertia from a point in local Link frame If you specify MOI(this->GetPose()), you should get back the Moment of Inertia (MOI) exactly as specified in the SDF. More...
 
ignition::math::Matrix3d MOI () const
 returns Moments of Inertia as a Matrix3 More...
 
Inertial operator() (const ignition::math::Pose3d &_frameOffset) const
 Get equivalent Inertia values with the Link frame offset, while holding the Pose of CoG constant in the world frame. More...
 
Inertial operator() (const ignition::math::Vector3d &_frameOffset) const
 Get equivalent Inertia values with the Link frame offset, while holding the Pose of CoG constant in the world frame. 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...
 
Inertialoperator= (const ignition::math::Inertiald &_inertial)
 Equal operator. More...
 
ignition::math::Pose3d Pose () const
 Get the pose about which the mass and inertia matrix is specified in the Link frame. More...
 
const ignition::math::Vector3d & PrincipalMoments () const
 Get the principal moments of inertia (Ixx, Iyy, Izz). More...
 
void ProcessMsg (const msgs::Inertial &_msg)
 Update parameters from a message. More...
 
const ignition::math::Vector3d & ProductsOfInertia () const
 Get the products of inertia (Ixy, Ixz, Iyz). More...
 
void Reset ()
 Reset all the mass properties. More...
 
void Rotate (const ignition::math::Quaterniond &_rot)
 Rotate this mass. More...
 
void SetCoG (const double _cx, const double _cy, const double _cz)
 Set the center of gravity. More...
 
void SetCoG (const ignition::math::Vector3d &_center)
 Set the center of gravity. More...
 
void SetCoG (const double _cx, const double _cy, const double _cz, const double _rx, const double _ry, const double _rz)
 Set the center of gravity and rotation offset of inertial coordinate frame relative to Link frame. More...
 
void SetCoG (const ignition::math::Pose3d &_c)
 Set the center of gravity. More...
 
void SetInertiaMatrix (const double _ixx, const double _iyy, const double _izz, const double _ixy, const double _ixz, const double iyz)
 Set the mass matrix. More...
 
void SetIXX (const double _v)
 Set IXX. More...
 
void SetIXY (const double _v)
 Set IXY. More...
 
void SetIXZ (const double _v)
 Set IXZ. More...
 
void SetIYY (const double _v)
 Set IYY. More...
 
void SetIYZ (const double _v)
 Set IYZ. More...
 
void SetIZZ (const double _v)
 Set IZZ. More...
 
void SetMass (const double _m)
 Set the mass. More...
 
void SetMOI (const ignition::math::Matrix3d &_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 ( )

Default Constructor.

Inertial ( const double  _mass)
explicit

Constructor.

Parameters
[in]_massMass value in kg if using metric.
Inertial ( const ignition::math::Inertiald &  _inertial)

Constructor from ignition::math::Inertial.

Parameters
[in]_inertialIgnition inertial object to copy.
Inertial ( const Inertial _inertial)

Copy constructor.

Parameters
[in]_inertialInertial element to copy
virtual ~Inertial ( )
virtual

Destructor.

Member Function Documentation

const ignition::math::Vector3d& CoG ( ) const

Get the center of gravity.

Returns
The center of gravity.
ignition::math::Inertiald Ign ( ) const

Return copy of Inertial in ignition format.

double IXX ( ) const

Get IXX.

Returns
IXX value
double IXY ( ) const

Get IXY.

Returns
IXY value
double IXZ ( ) const

Get IXZ.

Returns
IXZ value
double IYY ( ) const

Get IYY.

Returns
IYY value
double IYZ ( ) const

Get IYZ.

Returns
IYZ value
double IZZ ( ) const

Get IZZ.

Returns
IZZ value
void Load ( sdf::ElementPtr  _sdf)

Load from SDF values.

Parameters
[in]_sdfSDF value to load from.
double Mass ( ) const

Get the mass.

Returns
The mass in kilograms
ignition::math::Matrix3d MOI ( const ignition::math::Pose3d &  _pose) const

Get the equivalent inertia from a point in local Link frame If you specify MOI(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 due to point mass is added to the final MOI.

Parameters
[in]_poselocation in Link local frame
Returns
equivalent inertia at _pose
ignition::math::Matrix3d MOI ( ) const

returns Moments of Inertia as a Matrix3

Returns
Moments of Inertia as a Matrix3
Inertial operator() ( const ignition::math::Pose3d &  _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.
Inertial operator() ( const ignition::math::Vector3d &  _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.
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.
const Inertial& operator+= ( const Inertial _inertial)

Addition equal operator.

Parameters
[in]_inertialInertial to add.
Returns
Reference to this object.
Inertial& operator= ( const Inertial _inertial)

Equal operator.

Parameters
[in]_inertialInertial to copy.
Returns
Reference to this object.
Inertial& operator= ( const ignition::math::Inertiald &  _inertial)

Equal operator.

Parameters
[in]_inertialIgnition inertial to copy.
Returns
Reference to this object.
ignition::math::Pose3d Pose ( ) const

Get the pose about which the mass and inertia matrix is specified in the Link frame.

Returns
The inertial pose.
const ignition::math::Vector3d& PrincipalMoments ( ) const

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

Returns
The principal moments.
void ProcessMsg ( const msgs::Inertial &  _msg)

Update parameters from a message.

Parameters
[in]_msgMessage to read
const ignition::math::Vector3d& ProductsOfInertia ( ) const

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

Returns
The products of inertia.
void Reset ( )

Reset all the mass properties.

void Rotate ( const ignition::math::Quaterniond &  _rot)

Rotate this mass.

Parameters
[in]_rotRotation amount.
void SetCoG ( const double  _cx,
const double  _cy,
const double  _cz 
)

Set the center of gravity.

Parameters
[in]_cxX position.
[in]_cyY position.
[in]_czZ position.
void SetCoG ( const ignition::math::Vector3d &  _center)

Set the center of gravity.

Parameters
[in]_centerCenter of the gravity.
void SetCoG ( const double  _cx,
const double  _cy,
const double  _cz,
const double  _rx,
const double  _ry,
const 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.
void SetCoG ( const ignition::math::Pose3d &  _c)

Set the center of gravity.

Parameters
[in]_cTransform to center of gravity.
void SetInertiaMatrix ( const double  _ixx,
const double  _iyy,
const double  _izz,
const double  _ixy,
const double  _ixz,
const 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.
void SetIXX ( const double  _v)

Set IXX.

Parameters
[in]_vIXX value
void SetIXY ( const double  _v)

Set IXY.

Parameters
[in]_vIXY value
void SetIXZ ( const double  _v)

Set IXZ.

Parameters
[in]_vIXZ value
void SetIYY ( const double  _v)

Set IYY.

Parameters
[in]_vIYY value
void SetIYZ ( const double  _v)

Set IYZ.

Parameters
[in]_vIYZ value
void SetIZZ ( const double  _v)

Set IZZ.

Parameters
[in]_vIZZ value
void SetMass ( const double  _m)

Set the mass.

Parameters
[in]_mMass value in kilograms.
void SetMOI ( const ignition::math::Matrix3d &  _moi)

Sets Moments of Inertia (MOI) from a Matrix3.

Parameters
[in]_moiMoments of Inertia as a Matrix3
void UpdateParameters ( sdf::ElementPtr  _sdf)

update the parameters using new sdf values.

Parameters
[in]_sdfUpdate values from.

Friends And Related Function Documentation

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: