Ignition Sensors

API Reference

3.1.0
ImuSensor Class Reference

Imu Sensor Class. More...

#include <ImuSensor.hh>

Public Member Functions

 ImuSensor ()
 constructor More...
 
virtual ~ImuSensor ()
 destructor More...
 
math::Vector3d AngularVelocity () const
 Get the angular velocity of the imu. More...
 
math::Vector3d Gravity () const
 Get the gravity vector. More...
 
virtual bool Init () override
 Initialize values in the sensor. More...
 
math::Vector3d LinearAcceleration () const
 Get the linear acceleration of the imu. More...
 
virtual bool Load (const sdf::Sensor &_sdf) override
 Load the sensor based on data from an sdf::Sensor object. More...
 
virtual bool Load (sdf::ElementPtr _sdf) override
 Load the sensor with SDF parameters. More...
 
math::Quaterniond Orientation () const
 Get the orienation of the imu with respect to reference frame. More...
 
math::Quaterniond OrientationReference () const
 Get the world orienation reference of the imu. More...
 
void SetAngularVelocity (const math::Vector3d &_angularVel)
 Set the angular velocity of the imu. More...
 
void SetGravity (const math::Vector3d &_gravity)
 Set the gravity vector. More...
 
void SetLinearAcceleration (const math::Vector3d &_linearAcc)
 Set the linear acceleration of the imu. More...
 
void SetOrientationReference (const math::Quaterniond &_orient)
 Set the orientation reference, i.e. initial imu orientation. Imu orientation data generated will be relative to this reference frame. More...
 
void SetWorldPose (const math::Pose3d _pose)
 Set the world pose of the imu. More...
 
virtual bool Update (const common::Time &_now) override
 Update the sensor and generate data. More...
 
math::Pose3d WorldPose () const
 Get the world pose of the imu. More...
 
- Public Member Functions inherited from Sensor
virtual ~Sensor ()
 destructor More...
 
void AddSequence (ignition::msgs::Header *_msg, const std::string &_seqKey="default")
 Add a sequence number to an ignition::msgs::Header. This function can be called by a sensor that wants to add a sequence number to a sensor message in order to have improved accountability for generated sensor data. More...
 
SensorId Id () const
 Get the sensor's ID. More...
 
std::string Name () const
 Get name. More...
 
common::Time NextUpdateTime () const
 Return the next time the sensor will generate data. More...
 
std::string Parent () const
 Get parent link of the sensor. More...
 
ignition::math::Pose3d Pose () const
 Get the current pose. More...
 
sdf::ElementPtr SDF () const
 Get the SDF used to load this sensor. More...
 
virtual void SetParent (const std::string &_parent)
 Set the parent of the sensor. More...
 
void SetPose (const ignition::math::Pose3d &_pose)
 Update the pose of the sensor. More...
 
bool SetTopic (const std::string &_topic)
 Set topic where sensor data is published. More...
 
void SetUpdateRate (const double _hz)
 Set the update rate of the sensor. An update rate of zero means that the sensor is updated every cycle. It's zero by default. Negative rates become zero. More...
 
std::string Topic () const
 Get topic where sensor data is published. More...
 
bool Update (const common::Time &_now, const bool _force)
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. More...
 

Additional Inherited Members

- Protected Member Functions inherited from Sensor
 Sensor ()
 constructor More...
 

Detailed Description

Imu Sensor Class.

An imu sensor that reports linear acceleration, angular velocity, and orientation

Constructor & Destructor Documentation

◆ ImuSensor()

ImuSensor ( )

constructor

◆ ~ImuSensor()

virtual ~ImuSensor ( )
virtual

destructor

Member Function Documentation

◆ AngularVelocity()

math::Vector3d AngularVelocity ( ) const

Get the angular velocity of the imu.

Returns
Angular velocity of the imu in body frame, expressed in radians per second.

◆ Gravity()

math::Vector3d Gravity ( ) const

Get the gravity vector.

Returns
Gravity vectory in meters per second squared.

◆ Init()

virtual bool Init ( )
overridevirtual

Initialize values in the sensor.

Returns
True on success

Reimplemented from Sensor.

◆ LinearAcceleration()

math::Vector3d LinearAcceleration ( ) const

Get the linear acceleration of the imu.

Returns
Linear acceleration of the imu in local frame, expressed in meters per second squared.

◆ Load() [1/2]

virtual bool Load ( const sdf::Sensor &  _sdf)
overridevirtual

Load the sensor based on data from an sdf::Sensor object.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

◆ Load() [2/2]

virtual bool Load ( sdf::ElementPtr  _sdf)
overridevirtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

◆ Orientation()

math::Quaterniond Orientation ( ) const

Get the orienation of the imu with respect to reference frame.

Returns
Orientation in reference frame

◆ OrientationReference()

math::Quaterniond OrientationReference ( ) const

Get the world orienation reference of the imu.

Returns
Orientation reference in world frame

◆ SetAngularVelocity()

void SetAngularVelocity ( const math::Vector3d &  _angularVel)

Set the angular velocity of the imu.

Parameters
[in]_angularVelAngular velocity of the imu in body frame expressed in radians per second

◆ SetGravity()

void SetGravity ( const math::Vector3d &  _gravity)

Set the gravity vector.

Parameters
[in]_gravitygravity vector in meters per second squared.

◆ SetLinearAcceleration()

void SetLinearAcceleration ( const math::Vector3d &  _linearAcc)

Set the linear acceleration of the imu.

Parameters
[in]_linearAccLinear accceleration of the imu in body frame expressed in meters per second squared.

◆ SetOrientationReference()

void SetOrientationReference ( const math::Quaterniond &  _orient)

Set the orientation reference, i.e. initial imu orientation. Imu orientation data generated will be relative to this reference frame.

Parameters
[in]_orientationReference orientation

◆ SetWorldPose()

void SetWorldPose ( const math::Pose3d  _pose)

Set the world pose of the imu.

Parameters
[in]_posePose in world frame

◆ Update()

virtual bool Update ( const common::Time &  _now)
overridevirtual

Update the sensor and generate data.

Parameters
[in]_nowThe current time
Returns
true if the update was successfull

Implements Sensor.

◆ WorldPose()

math::Pose3d WorldPose ( ) const

Get the world pose of the imu.

Returns
Pose in world frame.

The documentation for this class was generated from the following file: