17 #ifndef GAZEBO_SENSORS_IMUSENSOR_HH_
18 #define GAZEBO_SENSORS_IMUSENSOR_HH_
22 #include <ignition/math/Quaternion.hh>
23 #include <ignition/math/Vector3.hh>
33 class ImuSensorPrivate;
49 protected:
void Load(
const std::string &_worldName, sdf::ElementPtr _sdf);
52 protected:
virtual void Load(
const std::string &_worldName);
55 public:
virtual void Init();
58 protected:
virtual bool UpdateImpl(
const bool _force);
61 protected:
virtual void Fini();
65 public: msgs::IMU ImuMessage()
const;
71 public: ignition::math::Vector3d AngularVelocity(
72 const bool _noiseFree =
false)
const;
79 public: ignition::math::Vector3d LinearAcceleration(
80 const bool _noiseFree =
false)
const;
89 public: ignition::math::Quaterniond Orientation()
const;
95 public:
void SetReferencePose();
98 public:
virtual bool IsActive()
const;
108 public:
void SetWorldToReferenceOrientation(
109 const ignition::math::Quaterniond &_orientation);
113 private:
void OnLinkData(ConstLinkDataPtr &_msg);
117 private: std::unique_ptr<ImuSensorPrivate> dataPtr;
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
An IMU sensor.
Definition: ImuSensor.hh:40
Base class for sensors.
Definition: Sensor.hh:51