Go to the documentation of this file.
17 #ifndef GZ_SENSORS_IMUSENSOR_HH_
18 #define GZ_SENSORS_IMUSENSOR_HH_
24 #include <gz/common/SuppressWarning.hh>
25 #include <gz/common/Time.hh>
26 #include <gz/math/Pose3.hh>
28 #include <gz/sensors/config.hh>
29 #include <gz/sensors/imu/Export.hh>
38 inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
41 class ImuSensorPrivate;
58 public:
virtual bool Load(
const sdf::Sensor &_sdf)
override;
63 public:
virtual bool Load(sdf::ElementPtr _sdf)
override;
67 public:
virtual bool Init()
override;
72 public:
virtual bool Update(
const common::Time &_now)
override;
77 public:
void SetAngularVelocity(
const math::Vector3d &_angularVel);
82 public: math::Vector3d AngularVelocity()
const;
87 public:
void SetLinearAcceleration(
const math::Vector3d &_linearAcc);
92 public: math::Vector3d LinearAcceleration()
const;
96 public:
void SetWorldPose(
const math::Pose3d _pose);
100 public: math::Pose3d WorldPose()
const;
106 public:
void SetOrientationReference(
107 const math::Quaterniond &_orient);
111 public: math::Quaterniond OrientationReference()
const;
115 public: math::Quaterniond Orientation()
const;
119 public:
void SetGravity(
const math::Vector3d &_gravity);
123 public: math::Vector3d Gravity()
const;
125 IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
129 IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
Definition: gz/sensors/AirPressureSensor.hh:32
Imu Sensor Class.
Definition: gz/sensors/ImuSensor.hh:47
a base sensor class
Definition: gz/sensors/Sensor.hh:60