An IMU sensor. More...
#include <sensors/sensors.hh>
Inherits Sensor.
Public Member Functions | |
ImuSensor () | |
Constructor. More... | |
virtual | ~ImuSensor () |
Destructor. More... | |
ignition::math::Vector3d | AngularVelocity (const bool _noiseFree=false) const |
Returns the angular velocity in the IMU sensor local frame. More... | |
SensorCategory | Category () const |
Get the category of the sensor. More... | |
event::ConnectionPtr | ConnectUpdated (std::function< void()> _subscriber) |
Connect a signal that is triggered when the sensor is updated. More... | |
void | DisconnectUpdated (event::ConnectionPtr &_c) |
Disconnect from a the updated signal. More... | |
void | FillMsg (msgs::Sensor &_msg) |
fills a msgs::Sensor message. More... | |
SensorCategory | GetCategory () const GAZEBO_DEPRECATED(7.0) |
Get the category of the sensor. More... | |
uint32_t | GetId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's ID. More... | |
msgs::IMU | GetImuMessage () const GAZEBO_DEPRECATED(7.0) |
Returns the imu message. More... | |
common::Time | GetLastMeasurementTime () GAZEBO_DEPRECATED(7.0) |
Return last measurement time. More... | |
common::Time | GetLastUpdateTime () GAZEBO_DEPRECATED(7.0) |
Return last update time. More... | |
std::string | GetName () const GAZEBO_DEPRECATED(7.0) |
Get name. More... | |
NoisePtr | GetNoise (const SensorNoiseType _type) const GAZEBO_DEPRECATED(7.0) |
Get the sensor's noise model for a specified noise type. More... | |
uint32_t | GetParentId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's parent's ID. More... | |
std::string | GetParentName () const GAZEBO_DEPRECATED(7.0) |
Returns the name of the sensor parent. More... | |
std::string | GetScopedName () const GAZEBO_DEPRECATED(7.0) |
Get fully scoped name of the sensor. More... | |
virtual std::string | GetTopic () const GAZEBO_DEPRECATED(7.0) |
Returns the topic name as set in SDF. More... | |
std::string | GetType () const GAZEBO_DEPRECATED(7.0) |
Get sensor type. More... | |
double | GetUpdateRate () GAZEBO_DEPRECATED(7.0) |
Get the update rate of the sensor. More... | |
bool | GetVisualize () const GAZEBO_DEPRECATED(7.0) |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More... | |
std::string | GetWorldName () const GAZEBO_DEPRECATED(7.0) |
Returns the name of the world the sensor is in. More... | |
uint32_t | Id () const |
Get the sensor's ID. More... | |
msgs::IMU | ImuMessage () const |
Returns the imu message. More... | |
virtual void | Init () |
Initialize the IMU. More... | |
virtual bool | IsActive () const |
Returns true if sensor generation is active. More... | |
common::Time | LastMeasurementTime () const |
Return last measurement time. More... | |
common::Time | LastUpdateTime () const |
Return last update time. More... | |
ignition::math::Vector3d | LinearAcceleration (const bool _noiseFree=false) const |
Returns the imu linear acceleration in the IMU sensor local frame. More... | |
std::string | Name () const |
Get name. More... | |
NoisePtr | Noise (const SensorNoiseType _type) const |
Get the sensor's noise model for a specified noise type. More... | |
ignition::math::Quaterniond | Orientation () const |
get orientation of the IMU relative to a reference pose Initially, the reference pose is the boot up pose of the IMU, but user can call either SetReferencePose to define current pose as the reference frame, or call SetWorldToReferencePose to define transform from world frame to reference frame. More... | |
uint32_t | ParentId () const |
Get the sensor's parent's ID. More... | |
std::string | ParentName () const |
Returns the name of the sensor parent. More... | |
virtual ignition::math::Pose3d | Pose () const |
Get the current pose. More... | |
void | ResetLastUpdateTime () |
Reset the lastUpdateTime to zero. More... | |
std::string | ScopedName () const |
Get fully scoped name of the sensor. More... | |
virtual void | SetActive (const bool _value) |
Set whether the sensor is active or not. More... | |
void | SetParent (const std::string &_name, const uint32_t _id) |
Set the sensor's parent. More... | |
virtual void | SetPose (const ignition::math::Pose3d &_pose) |
Set the current pose. More... | |
void | SetReferencePose () |
Sets the current IMU pose as the reference NED pose, i.e. More... | |
void | SetUpdateRate (const double _hz) |
Set the update rate of the sensor. More... | |
void | SetWorldToReferencePose (const ignition::math::Pose3d &_pose=ignition::math::Pose3d()) |
Sets the transform from world frame to IMU's reference frame. More... | |
virtual std::string | Topic () const |
Returns the topic name as set in SDF. More... | |
std::string | Type () const |
Get sensor type. More... | |
void | Update (const bool _force) |
Update the sensor. More... | |
double | UpdateRate () const |
Get the update rate of the sensor. More... | |
bool | Visualize () const |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More... | |
std::string | WorldName () const |
Returns the name of the world the sensor is in. More... | |
Protected Member Functions | |
virtual void | Fini () |
Finalize the sensor. More... | |
void | Load (const std::string &_worldName, sdf::ElementPtr _sdf) |
Load the sensor with SDF parameters. More... | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. More... | |
bool | NeedsUpdate () |
Return true if the sensor needs to be updated. More... | |
virtual bool | UpdateImpl (const bool _force) |
This gets overwritten by derived sensor types. More... | |
Protected Attributes | |
bool | active |
True if sensor generation is active. More... | |
std::vector< event::ConnectionPtr > | connections |
All event connections. More... | |
common::Time | lastMeasurementTime |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl. More... | |
common::Time | lastUpdateTime |
Time of the last update. More... | |
transport::NodePtr | node |
Node for communication. More... | |
std::map< SensorNoiseType, NoisePtr > | noises |
Noise added to sensor data. More... | |
uint32_t | parentId |
The sensor's parent ID. More... | |
std::string | parentName |
Name of the parent. More... | |
std::vector< SensorPluginPtr > | plugins |
All the plugins for the sensor. More... | |
ignition::math::Pose3d | pose |
Pose of the sensor. More... | |
gazebo::rendering::ScenePtr | scene |
Pointer to the Scene. More... | |
sdf::ElementPtr | sdf |
Pointer the the SDF element for the sensor. More... | |
common::Time | updatePeriod |
Desired time between updates, set indirectly by Sensor::SetUpdateRate. More... | |
gazebo::physics::WorldPtr | world |
Pointer to the world. More... | |
An IMU sensor.
ImuSensor | ( | ) |
Constructor.
|
virtual |
Destructor.
ignition::math::Vector3d AngularVelocity | ( | const bool | _noiseFree = false | ) | const |
Returns the angular velocity in the IMU sensor local frame.
[in] | _noiseFree | True if the returned measurement should not use noise. |
|
inherited |
|
inherited |
Connect a signal that is triggered when the sensor is updated.
[in] | _subscriber | Callback that receives the signal. |
|
inherited |
Disconnect from a the updated signal.
[in] | _c | The connection to disconnect |
|
inherited |
fills a msgs::Sensor message.
[out] | _msg | Message to fill. |
|
protectedvirtual |
Finalize the sensor.
Reimplemented from Sensor.
|
inherited |
Get the category of the sensor.
|
inherited |
msgs::IMU GetImuMessage | ( | ) | const |
|
inherited |
Return last measurement time.
|
inherited |
|
inherited |
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
|
inherited |
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Returns the topic name as set in SDF.
Reimplemented in AltimeterSensor, LogicalCameraSensor, and MagnetometerSensor.
|
inherited |
|
inherited |
Get the update rate of the sensor.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
|
inherited |
Get the sensor's ID.
msgs::IMU ImuMessage | ( | ) | const |
Returns the imu message.
|
virtual |
Initialize the IMU.
Reimplemented from Sensor.
|
virtual |
Returns true if sensor generation is active.
Reimplemented from Sensor.
|
inherited |
Return last measurement time.
|
inherited |
Return last update time.
ignition::math::Vector3d LinearAcceleration | ( | const bool | _noiseFree = false | ) | const |
Returns the imu linear acceleration in the IMU sensor local frame.
[in] | _noiseFree | True if the returned measurement should not use noise. |
|
protectedvirtual |
|
protectedvirtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from. |
Reimplemented from Sensor.
|
inherited |
Get name.
|
protectedinherited |
Return true if the sensor needs to be updated.
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
ignition::math::Quaterniond Orientation | ( | ) | const |
get orientation of the IMU relative to a reference pose Initially, the reference pose is the boot up pose of the IMU, but user can call either SetReferencePose to define current pose as the reference frame, or call SetWorldToReferencePose to define transform from world frame to reference frame.
|
inherited |
Get the sensor's parent's ID.
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
|
virtualinherited |
|
inherited |
Reset the lastUpdateTime to zero.
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Set whether the sensor is active or not.
[in] | _value | True if active, false if not. |
Reimplemented in DepthCameraSensor.
|
inherited |
Set the sensor's parent.
[in] | _name | The sensor's parent's name. |
[in] | _id | The sensor's parent's ID. |
|
virtualinherited |
void SetReferencePose | ( | ) |
Sets the current IMU pose as the reference NED pose, i.e.
X axis of the IMU is aligned with North, Y axis of the IMU is aligned with East, Z axis of the IMU is aligned with Downward (gravity) direction.
|
inherited |
Set the update rate of the sensor.
[in] | _hz | update rate of sensor. |
void SetWorldToReferencePose | ( | const ignition::math::Pose3d & | _pose = ignition::math::Pose3d() | ) |
Sets the transform from world frame to IMU's reference frame.
For example, if this IMU works with respect to NED frame, then call this function with the transform that transforms world frame to NED frame. Subsequently, ImuSensor::Orientation will return identity transform if the IMU is aligned with the NED frame. This call replaces SetReferencePose.
_orientation | current IMU orientation in NED |
|
virtualinherited |
Returns the topic name as set in SDF.
Reimplemented in LogicalCameraSensor, GpuRaySensor, RaySensor, CameraSensor, ForceTorqueSensor, MultiCameraSensor, SonarSensor, and WirelessTransceiver.
|
inherited |
Get sensor type.
|
inherited |
Update the sensor.
[in] | _force | True to force update, false otherwise. |
|
protectedvirtual |
This gets overwritten by derived sensor types.
This function is called during Sensor::Update. And in turn, Sensor::Update is called by SensorManager::Update
[in] | _force | True if update is forced, false if not |
Reimplemented from Sensor.
|
inherited |
Get the update rate of the sensor.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
|
protectedinherited |
True if sensor generation is active.
|
protectedinherited |
All event connections.
|
protectedinherited |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
|
protectedinherited |
Time of the last update.
|
protectedinherited |
Node for communication.
|
protectedinherited |
Noise added to sensor data.
|
protectedinherited |
The sensor's parent ID.
|
protectedinherited |
Name of the parent.
|
protectedinherited |
All the plugins for the sensor.
|
protectedinherited |
Pose of the sensor.
|
protectedinherited |
Pointer to the Scene.
|
protectedinherited |
Pointer the the SDF element for the sensor.
|
protectedinherited |
Desired time between updates, set indirectly by Sensor::SetUpdateRate.
|
protectedinherited |
Pointer to the world.