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... | |
math::Vector3 | GetCoG () const GAZEBO_DEPRECATED(8.0) |
Get the center of gravity. More... | |
Inertial | GetInertial (const math::Pose &_frameOffset) const GAZEBO_DEPRECATED(8.0) |
Get equivalent Inertia values with the Link frame offset, while holding the Pose of CoG constant in the world frame. More... | |
double | GetIXX () const GAZEBO_DEPRECATED(8.0) |
Get IXX. More... | |
double | GetIXY () const GAZEBO_DEPRECATED(8.0) |
Get IXY. More... | |
double | GetIXZ () const GAZEBO_DEPRECATED(8.0) |
Get IXZ. More... | |
double | GetIYY () const GAZEBO_DEPRECATED(8.0) |
Get IYY. More... | |
double | GetIYZ () const GAZEBO_DEPRECATED(8.0) |
Get IYZ. More... | |
double | GetIZZ () const GAZEBO_DEPRECATED(8.0) |
Get IZZ. More... | |
double | GetMass () const GAZEBO_DEPRECATED(8.0) |
Get the mass. More... | |
math::Matrix3 | GetMOI (const math::Pose &_pose) const GAZEBO_DEPRECATED(8.0) |
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 GAZEBO_DEPRECATED(8.0) |
returns Moments of Inertia as a Matrix3 More... | |
const math::Pose | GetPose () const GAZEBO_DEPRECATED(8.0) |
Get the pose about which the mass and inertia matrix is specified in the Link frame. More... | |
math::Vector3 | GetPrincipalMoments () const GAZEBO_DEPRECATED(8.0) |
Get the principal moments of inertia (Ixx, Iyy, Izz). More... | |
math::Vector3 | GetProductsofInertia () const GAZEBO_DEPRECATED(8.0) |
Get the products of inertia (Ixy, Ixz, Iyz). 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 Inertial & | operator+= (const Inertial &_inertial) |
Addition equal operator. More... | |
Inertial & | operator= (const Inertial &_inertial) |
Equal operator. More... | |
Inertial & | operator= (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 math::Quaternion &_rot) GAZEBO_DEPRECATED(8.0) |
Rotate this mass. 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 math::Vector3 &_center) GAZEBO_DEPRECATED(8.0) |
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 math::Pose &_c) GAZEBO_DEPRECATED(8.0) |
Set the center of gravity. 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 math::Matrix3 &_moi) GAZEBO_DEPRECATED(8.0) |
Sets Moments of Inertia (MOI) from a Matrix3. 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... | |
A class for inertial information about a link.
Inertial | ( | ) |
Default Constructor.
|
explicit |
Constructor.
[in] | _mass | Mass value in kg if using metric. |
Inertial | ( | const ignition::math::Inertiald & | _inertial | ) |
Constructor from ignition::math::Inertial.
[in] | _inertial | Ignition inertial object to copy. |
Copy constructor.
[in] | _inertial | Inertial element to copy |
|
virtual |
Destructor.
const ignition::math::Vector3d& CoG | ( | ) | const |
Get the center of gravity.
math::Vector3 GetCoG | ( | ) | const |
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. |
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 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
const math::Pose GetPose | ( | ) | const |
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).
ignition::math::Inertiald Ign | ( | ) | const |
Return copy of Inertial in ignition format.
double IXX | ( | ) | const |
Get IXX.
double IXY | ( | ) | const |
Get IXY.
double IXZ | ( | ) | const |
Get IXZ.
double IYY | ( | ) | const |
Get IYY.
double IYZ | ( | ) | const |
Get IYZ.
double IZZ | ( | ) | const |
Get IZZ.
void Load | ( | sdf::ElementPtr | _sdf | ) |
Load from SDF values.
[in] | _sdf | SDF value to load from. |
double Mass | ( | ) | const |
Get the mass.
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.
[in] | _pose | location in Link local frame |
ignition::math::Matrix3d MOI | ( | ) | const |
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.
[in] | _frameOffset | amount to offset the Link frame by, this is a transform defined in the Link 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.
[in] | _frameOffset | amount to offset the Link frame by, this is a transform defined in the Link frame. |
Inertial& operator= | ( | const ignition::math::Inertiald & | _inertial | ) |
Equal operator.
[in] | _inertial | Ignition inertial to copy. |
ignition::math::Pose3d Pose | ( | ) | const |
Get the pose about which the mass and inertia matrix is specified in the Link frame.
const ignition::math::Vector3d& PrincipalMoments | ( | ) | const |
Get the principal moments of inertia (Ixx, Iyy, Izz).
void ProcessMsg | ( | const msgs::Inertial & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to read |
const ignition::math::Vector3d& ProductsOfInertia | ( | ) | const |
Get the products of inertia (Ixy, Ixz, Iyz).
void Reset | ( | ) |
Reset all the mass properties.
void Rotate | ( | const math::Quaternion & | _rot | ) |
Rotate this mass.
[in] | _rot | Rotation amount. |
void Rotate | ( | const ignition::math::Quaterniond & | _rot | ) |
Rotate this mass.
[in] | _rot | Rotation amount. |
void SetCoG | ( | const double | _cx, |
const double | _cy, | ||
const 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 | ( | const ignition::math::Vector3d & | _center | ) |
Set the center of gravity.
[in] | _center | Center 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.
[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 SetCoG | ( | const ignition::math::Pose3d & | _c | ) |
Set the center of gravity.
[in] | _c | Transform 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.
[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 | ( | const double | _v | ) |
Set IXX.
[in] | _v | IXX value |
void SetIXY | ( | const double | _v | ) |
Set IXY.
[in] | _v | IXY value |
void SetIXZ | ( | const double | _v | ) |
Set IXZ.
[in] | _v | IXZ value |
void SetIYY | ( | const double | _v | ) |
Set IYY.
[in] | _v | IYY value |
void SetIYZ | ( | const double | _v | ) |
Set IYZ.
[in] | _v | IYZ value |
void SetIZZ | ( | const double | _v | ) |
Set IZZ.
[in] | _v | IZZ value |
void SetMass | ( | const double | _m | ) |
Set the mass.
[in] | _m | Mass value in kilograms. |
void SetMOI | ( | const math::Matrix3 & | _moi | ) |
Sets Moments of Inertia (MOI) from a Matrix3.
[in] | Moments | of Inertia as a Matrix3 |
void SetMOI | ( | const ignition::math::Matrix3d & | _moi | ) |
Sets Moments of Inertia (MOI) from a Matrix3.
[in] | _moi | 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. |