A class for inertial information about a link. More...
#include <physics/physics.hh>
Public Member Functions | |
Inertial () | |
Default Constructor. | |
Inertial (double _mass) | |
Constructor. | |
Inertial (const Inertial &_inertial) | |
Copy constructor. | |
virtual | ~Inertial () |
Destructor. | |
const math::Vector3 & | GetCoG () const |
Get the center of gravity. | |
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. | |
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. | |
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). | |
void | Load (sdf::ElementPtr _sdf) |
Load from SDF values. | |
Inertial | operator+ (const Inertial &_inertial) const |
Addition operator. | |
const Inertial & | operator+= (const Inertial &_inertial) |
Addition equal operator. | |
Inertial & | operator= (const Inertial &_inertial) |
Equal operator. | |
void | ProcessMsg (const msgs::Inertial &_msg) |
Update parameters from a message. | |
void | Reset () |
Reset all the mass properties. | |
void | Rotate (const math::Quaternion &_rot) |
Rotate this mass. | |
void | SetCoG (double _cx, double _cy, double _cz) |
Set the center of gravity. | |
void | SetCoG (const math::Vector3 &_center) |
Set the center of 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. | |
void | SetCoG (const math::Pose &_c) |
Set the center of gravity. | |
void | SetInertiaMatrix (double _ixx, double _iyy, double _izz, double _ixy, double _ixz, double iyz) |
Set the mass matrix. | |
void | SetIXX (double _v) |
Set IXX. | |
void | SetIXY (double _v) |
Set IXY. | |
void | SetIXZ (double _v) |
Set IXZ. | |
void | SetIYY (double _v) |
Set IYY. | |
void | SetIYZ (double _v) |
Set IYZ. | |
void | SetIZZ (double _v) |
Set IZZ. | |
void | SetMass (double m) |
Set the mass. | |
void | SetMOI (const math::Matrix3 &_moi) |
Sets Moments of Inertia (MOI) from a Matrix3. | |
void | UpdateParameters (sdf::ElementPtr _sdf) |
update the parameters using new sdf values. |
Friends | |
std::ostream & | operator<< (std::ostream &_out, const gazebo::physics::Inertial &_inertial) |
Output operator. |
A class for inertial information about a link.
gazebo::physics::Inertial::Inertial | ( | ) |
Default Constructor.
|
explicit |
Constructor.
[in] | _mass | Mass value in kg if using metric. |
gazebo::physics::Inertial::Inertial | ( | const Inertial & | _inertial | ) |
Copy constructor.
[in] | _inertial | Inertial element to copy |
|
virtual |
Destructor.
|
inline |
Inertial gazebo::physics::Inertial::GetInertial | ( | const math::Pose & | _frameOffset | ) | const |
double gazebo::physics::Inertial::GetIXX | ( | ) | const |
Get IXX.
double gazebo::physics::Inertial::GetIXY | ( | ) | const |
Get IXY.
double gazebo::physics::Inertial::GetIXZ | ( | ) | const |
Get IXZ.
double gazebo::physics::Inertial::GetIYY | ( | ) | const |
Get IYY.
double gazebo::physics::Inertial::GetIYZ | ( | ) | const |
Get IXZ.
double gazebo::physics::Inertial::GetIZZ | ( | ) | const |
Get IZZ.
double gazebo::physics::Inertial::GetMass | ( | ) | const |
Get the mass.
math::Matrix3 gazebo::physics::Inertial::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 gazebo::physics::Inertial::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 gazebo::physics::Inertial::GetPrincipalMoments | ( | ) | const |
Get the principal moments of inertia (Ixx, Iyy, Izz).
math::Vector3 gazebo::physics::Inertial::GetProductsofInertia | ( | ) | const |
Get the products of inertia (Ixy, Ixz, Iyz).
void gazebo::physics::Inertial::Load | ( | sdf::ElementPtr | _sdf | ) |
Load from SDF values.
[in] | _sdf | SDF value to load from. |
void gazebo::physics::Inertial::ProcessMsg | ( | const msgs::Inertial & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to read |
void gazebo::physics::Inertial::Reset | ( | ) |
Reset all the mass properties.
void gazebo::physics::Inertial::Rotate | ( | const math::Quaternion & | _rot | ) |
Rotate this mass.
[in] | _rot | Rotation amount. |
void gazebo::physics::Inertial::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 gazebo::physics::Inertial::SetCoG | ( | const math::Vector3 & | _center | ) |
Set the center of gravity.
[in] | _center | Center of the gravity. |
void gazebo::physics::Inertial::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 gazebo::physics::Inertial::SetCoG | ( | const math::Pose & | _c | ) |
Set the center of gravity.
[in] | _c | Transform to center of gravity. |
void gazebo::physics::Inertial::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 gazebo::physics::Inertial::SetIXX | ( | double | _v | ) |
Set IXX.
[in] | _v | IXX value |
void gazebo::physics::Inertial::SetIXY | ( | double | _v | ) |
Set IXY.
[in] | _v | IXY value |
void gazebo::physics::Inertial::SetIXZ | ( | double | _v | ) |
Set IXZ.
[in] | _v | IXZ value |
void gazebo::physics::Inertial::SetIYY | ( | double | _v | ) |
Set IYY.
[in] | _v | IYY value |
void gazebo::physics::Inertial::SetIYZ | ( | double | _v | ) |
Set IYZ.
[in] | _v | IXX value |
void gazebo::physics::Inertial::SetIZZ | ( | double | _v | ) |
Set IZZ.
[in] | _v | IZZ value |
void gazebo::physics::Inertial::SetMass | ( | double | m | ) |
Set the mass.
void gazebo::physics::Inertial::SetMOI | ( | const math::Matrix3 & | _moi | ) |
Sets Moments of Inertia (MOI) from a Matrix3.
[in] | Moments | of Inertia as a Matrix3 |
void gazebo::physics::Inertial::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. |