ImuSensor.hh
Go to the documentation of this file.
1/*
2 * Copyright (C) 2012 Open Source Robotics Foundation
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *
16*/
17#ifndef GAZEBO_SENSORS_IMUSENSOR_HH_
18#define GAZEBO_SENSORS_IMUSENSOR_HH_
19
20#include <memory>
21#include <string>
22#include <ignition/math/Quaternion.hh>
23#include <ignition/math/Vector3.hh>
24
26#include "gazebo/util/system.hh"
27
28namespace gazebo
29{
30 namespace sensors
31 {
32 // Forward declare private data class.
33 class ImuSensorPrivate;
34
37
40 class GZ_SENSORS_VISIBLE ImuSensor: public Sensor
41 {
43 public: ImuSensor();
44
46 public: virtual ~ImuSensor();
47
48 // Documentation inherited.
49 protected: void Load(const std::string &_worldName, sdf::ElementPtr _sdf);
50
51 // Documentation inherited.
52 protected: virtual void Load(const std::string &_worldName);
53
55 public: virtual void Init();
56
57 // Documentation inherited
58 protected: virtual bool UpdateImpl(const bool _force);
59
60 // Documentation inherited
61 protected: virtual void Fini();
62
65 public: msgs::IMU ImuMessage() const;
66
71 public: ignition::math::Vector3d AngularVelocity(
72 const bool _noiseFree = false) const;
73
79 public: ignition::math::Vector3d LinearAcceleration(
80 const bool _noiseFree = false) const;
81
89 public: ignition::math::Quaterniond Orientation() const;
90
95 public: void SetReferencePose();
96
97 // Documentation inherited.
98 public: virtual bool IsActive() const;
99
109 const ignition::math::Quaterniond &_orientation);
110
113 private: void OnLinkData(ConstLinkDataPtr &_msg);
114
117 private: std::unique_ptr<ImuSensorPrivate> dataPtr;
118 };
120 }
121}
122#endif
sensors
Definition SensorManager.hh:35
An IMU sensor.
Definition ImuSensor.hh:41
void Load(const std::string &_worldName, sdf::ElementPtr _sdf)
Load the sensor with SDF parameters.
virtual ~ImuSensor()
Destructor.
void SetReferencePose()
Sets the current IMU pose as the reference NED pose, i.e.
virtual void Fini()
Finalize the sensor.
virtual void Init()
Initialize the IMU.
ignition::math::Quaterniond Orientation() const
get orientation of the IMU relative to a reference pose Initially, the reference pose is the boot up ...
virtual void Load(const std::string &_worldName)
Load the sensor with default parameters.
ignition::math::Vector3d AngularVelocity(const bool _noiseFree=false) const
Returns the angular velocity in the IMU sensor local frame.
virtual bool IsActive() const
Returns true if sensor generation is active.
virtual bool UpdateImpl(const bool _force)
This gets overwritten by derived sensor types.
ignition::math::Vector3d LinearAcceleration(const bool _noiseFree=false) const
Returns the imu linear acceleration in the IMU sensor local frame.
msgs::IMU ImuMessage() const
Returns the imu message.
void SetWorldToReferenceOrientation(const ignition::math::Quaterniond &_orientation)
Sets the rotation transform from world frame to IMU's reference frame.
Base class for sensors.
Definition Sensor.hh:53
Forward declarations for the common classes.
Definition Animation.hh:27