17 #ifndef GAZEBO_PHYSICS_INERTIAL_HH_ 18 #define GAZEBO_PHYSICS_INERTIAL_HH_ 29 #include <ignition/math/Inertial.hh> 31 #include <ignition/math/Vector3.hh> 32 #include <ignition/math/Quaternion.hh> 33 #include <ignition/math/Matrix3.hh> 44 class InertialPrivate;
58 public:
explicit Inertial(
const double _mass);
63 public:
Inertial(
const ignition::math::Inertiald &_inertial);
74 public:
void Load(sdf::ElementPtr _sdf);
78 public:
void UpdateParameters(sdf::ElementPtr _sdf);
84 public: ignition::math::Inertiald Ign()
const;
88 public:
void SetMass(
const double _m);
92 public:
double Mass()
const;
101 public:
void SetInertiaMatrix(
102 const double _ixx,
const double _iyy,
const double _izz,
103 const double _ixy,
const double _ixz,
const double iyz);
109 public:
void SetCoG(
const double _cx,
const double _cy,
const double _cz);
113 public:
void SetCoG(
const ignition::math::Vector3d &_center);
123 public:
void SetCoG(
const double _cx,
const double _cy,
const double _cz,
124 const double _rx,
const double _ry,
const double _rz);
128 public:
void SetCoG(
const ignition::math::Pose3d &_c);
132 public:
const ignition::math::Vector3d &CoG()
const;
137 public: ignition::math::Pose3d Pose()
const;
141 public:
const ignition::math::Vector3d &PrincipalMoments()
const;
145 public:
const ignition::math::Vector3d &ProductsOfInertia()
const;
149 public:
double IXX()
const;
153 public:
double IYY()
const;
157 public:
double IZZ()
const;
161 public:
double IXY()
const;
165 public:
double IXZ()
const;
169 public:
double IYZ()
const;
173 public:
void SetIXX(
const double _v);
177 public:
void SetIYY(
const double _v);
181 public:
void SetIZZ(
const double _v);
185 public:
void SetIXY(
const double _v);
189 public:
void SetIXZ(
const double _v);
193 public:
void SetIYZ(
const double _v);
197 public:
void Rotate(
const ignition::math::Quaterniond &_rot);
207 public:
Inertial &operator=(
const ignition::math::Inertiald &_inertial);
225 public:
void ProcessMsg(
const msgs::Inertial &_msg);
235 public: ignition::math::Matrix3d MOI(
236 const ignition::math::Pose3d &_pose)
const;
244 const ignition::math::Pose3d &_frameOffset)
const;
252 const ignition::math::Vector3d &_frameOffset)
const;
260 _out <<
"Mass[" << _inertial.
Mass() <<
"] CoG[" 261 << _inertial.
CoG() <<
"]\n";
273 public: ignition::math::Matrix3d MOI()
const;
277 public:
void SetMOI(
const ignition::math::Matrix3d &_moi);
281 private: std::unique_ptr<InertialPrivate> dataPtr;
const ignition::math::Vector3d & PrincipalMoments() const
Get the principal moments of inertia (Ixx, Iyy, Izz).
Forward declarations for the common classes.
Definition: Animation.hh:26
const ignition::math::Vector3d & ProductsOfInertia() const
Get the products of inertia (Ixy, Ixz, Iyz).
const ignition::math::Vector3d & CoG() const
Get the center of gravity.
double Mass() const
Get the mass.
A class for inertial information about a link.
Definition: Inertial.hh:51
friend std::ostream & operator<<(std::ostream &_out, const gazebo::physics::Inertial &_inertial)
Output operator.
Definition: Inertial.hh:257