17 #ifndef _GAZEBO_IMUSENSOR_HH_
18 #define _GAZEBO_IMUSENSOR_HH_
22 #include <ignition/math/Pose3.hh>
23 #include <ignition/math/Quaternion.hh>
24 #include <ignition/math/Vector3.hh>
48 protected:
void Load(
const std::string &_worldName, sdf::ElementPtr _sdf);
51 protected:
virtual void Load(
const std::string &_worldName);
54 public:
virtual void Init();
57 protected:
virtual bool UpdateImpl(
bool _force);
60 protected:
virtual void Fini();
64 public: msgs::IMU GetImuMessage()
const;
90 public: ignition::math::Vector3d AngularVelocity(
91 const bool _noiseFree =
false)
const;
97 public: ignition::math::Vector3d LinearAcceleration(
98 const bool _noiseFree =
false)
const;
103 public: ignition::math::Quaterniond Orientation()
const;
106 public:
void SetReferencePose();
109 public:
virtual bool IsActive();
113 private:
void OnLinkData(ConstLinkDataPtr &_msg);
116 private: ignition::math::Pose3d referencePose;
119 private: ignition::math::Vector3d lastLinearVel;
122 private: ignition::math::Vector3d linearAcc;
125 private: ignition::math::Vector3d gravity;
137 private: msgs::IMU imuMsg;
140 private:
mutable boost::mutex mutex;
143 private: boost::shared_ptr<msgs::LinkData const> incomingLinkData[2];
146 private:
unsigned int dataIndex;
149 private:
bool dataDirty;
152 private: ignition::math::Vector3d angularVel;
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:47
default namespace for gazebo
A quaternion class.
Definition: Quaternion.hh:42
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
An IMU sensor.
Definition: ImuSensor.hh:39
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
Base class for sensors.
Definition: Sensor.hh:69
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:66
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92