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::Vector3 & | GetCoG () 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 Inertial & | operator+= (const Inertial &_inertial) |
Addition equal operator. More... | |
Inertial & | operator= (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... | |
A class for inertial information about a link.
Inertial | ( | ) |
Default Constructor.
|
explicit |
Constructor.
[in] | _mass | Mass value in kg if using metric. |
Copy constructor.
[in] | _inertial | Inertial element to copy |
|
virtual |
Destructor.
|
inline |
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.
[in] | _frameOffset | amount to offset the Link frame by, this is a transform defined in the Link frame. |
Referenced by Inertial::GetPose().
double GetIXX | ( | ) | const |
double GetIXY | ( | ) | const |
double GetIXZ | ( | ) | const |
double GetIYY | ( | ) | const |
double GetIYZ | ( | ) | const |
double GetIZZ | ( | ) | const |
double GetMass | ( | ) | const |
Get the mass.
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.
[in] | _pose | location in Link local frame |
math::Matrix3 GetMOI | ( | ) | const |
returns Moments of Inertia as a Matrix3
Referenced by Inertial::GetPose().
|
inline |
Get the pose about which the mass and inertia matrix is specified in the Link frame.
References Inertial::GetInertial(), Inertial::GetIXX(), Inertial::GetIXY(), Inertial::GetIXZ(), Inertial::GetIYY(), Inertial::GetIYZ(), Inertial::GetIZZ(), Inertial::GetMOI(), Inertial::GetPrincipalMoments(), Inertial::GetProductsofInertia(), Inertial::operator+(), Inertial::operator+=(), Inertial::operator=(), Inertial::ProcessMsg(), Inertial::Rotate(), Inertial::SetIXX(), Inertial::SetIXY(), Inertial::SetIXZ(), Inertial::SetIYY(), Inertial::SetIYZ(), and Inertial::SetIZZ().
math::Vector3 GetPrincipalMoments | ( | ) | const |
Get the principal moments of inertia (Ixx, Iyy, Izz).
Referenced by Inertial::GetPose().
math::Vector3 GetProductsofInertia | ( | ) | const |
Get the products of inertia (Ixy, Ixz, Iyz).
Referenced by Inertial::GetPose().
void Load | ( | sdf::ElementPtr | _sdf | ) |
Load from SDF values.
[in] | _sdf | SDF value to load from. |
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.
[in] | _inertial | Inertial to add. |
Referenced by Inertial::GetPose().
Addition equal operator.
[in] | _inertial | Inertial to add. |
Referenced by Inertial::GetPose().
Equal operator.
[in] | _inertial | Inertial to copy. |
Referenced by Inertial::GetPose().
void ProcessMsg | ( | const msgs::Inertial & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to read |
Referenced by Inertial::GetPose().
void Reset | ( | ) |
Reset all the mass properties.
void Rotate | ( | const math::Quaternion & | _rot | ) |
void SetCoG | ( | double | _cx, |
double | _cy, | ||
double | _cz | ||
) |
Set the center of gravity.
[in] | _cx | X position. |
[in] | _cy | Y position. |
[in] | _cz | Z position. |
void SetCoG | ( | const math::Vector3 & | _center | ) |
Set the center of gravity.
[in] | _center | Center of the gravity. |
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.
[in] | _cx | Center offset in x-direction in Link frame |
[in] | _cy | Center offset in y-direction in Link frame |
[in] | _cz | Center offset in z-direction in Link frame |
[in] | _rx | Roll angle offset of inertial coordinate frame. |
[in] | _ry | Pitch angle offset of inertial coordinate frame. |
[in] | _rz | Yaw angle offset of inertial coordinate frame. |
void SetCoG | ( | const math::Pose & | _c | ) |
Set the center of gravity.
[in] | _c | Transform to center of gravity. |
void SetInertiaMatrix | ( | double | _ixx, |
double | _iyy, | ||
double | _izz, | ||
double | _ixy, | ||
double | _ixz, | ||
double | iyz | ||
) |
Set the mass matrix.
[in] | _ixx | X second moment of inertia (MOI) about x axis. |
[in] | _iyy | Y second moment of inertia about y axis. |
[in] | _izz | Z second moment of inertia about z axis. |
[in] | _ixy | XY inertia. |
[in] | _ixz | XZ inertia. |
[in] | _iyz | YZ inertia. |
void SetIXX | ( | double | _v | ) |
void SetIXY | ( | double | _v | ) |
void SetIXZ | ( | double | _v | ) |
void SetIYY | ( | double | _v | ) |
void SetIYZ | ( | double | _v | ) |
void SetIZZ | ( | double | _v | ) |
void SetMass | ( | double | m | ) |
Set the mass.
void SetMOI | ( | const math::Matrix3 & | _moi | ) |
Sets Moments of Inertia (MOI) from a Matrix3.
[in] | Moments | of Inertia as a Matrix3 |
void UpdateParameters | ( | sdf::ElementPtr | _sdf | ) |
update the parameters using new sdf values.
[in] | _sdf | Update values from. |
|
friend |
Output operator.
[in] | _out | Output stream. |
[in] | _inertial | Inertial object to output. |