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 |
double GetIXX | ( | ) | const |
Get IXX.
double GetIXY | ( | ) | const |
Get IXY.
double GetIXZ | ( | ) | const |
Get IXZ.
double GetIYY | ( | ) | const |
Get IYY.
double GetIYZ | ( | ) | const |
Get IXZ.
double GetIZZ | ( | ) | const |
Get IZZ.
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
|
inline |
Get the pose about which the mass and inertia matrix is specified in the Link frame.
math::Vector3 GetPrincipalMoments | ( | ) | const |
Get the principal moments of inertia (Ixx, Iyy, Izz).
math::Vector3 GetProductsofInertia | ( | ) | const |
Get the products of inertia (Ixy, Ixz, Iyz).
void Load | ( | sdf::ElementPtr | _sdf | ) |
Load from SDF values.
[in] | _sdf | SDF value to load from. |
void ProcessMsg | ( | const msgs::Inertial & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to read |
void Reset | ( | ) |
Reset all the mass properties.
void Rotate | ( | const math::Quaternion & | _rot | ) |
Rotate this mass.
[in] | _rot | Rotation amount. |
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 | ) |
Set IXX.
[in] | _v | IXX value |
void SetIXY | ( | double | _v | ) |
Set IXY.
[in] | _v | IXY value |
void SetIXZ | ( | double | _v | ) |
Set IXZ.
[in] | _v | IXZ value |
void SetIYY | ( | double | _v | ) |
Set IYY.
[in] | _v | IYY value |
void SetIYZ | ( | double | _v | ) |
Set IYZ.
[in] | _v | IXX value |
void SetIZZ | ( | double | _v | ) |
Set IZZ.
[in] | _v | IZZ value |
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. |