Imu contains information about an imu sensor. More...
#include <Imu.hh>
Public Member Functions | |
Imu () | |
Default constructor. More... | |
Imu (const Imu &_imu) | |
Copy constructor. More... | |
Imu (Imu &&_imu) noexcept | |
Move constructor. More... | |
~Imu () | |
Destructor. More... | |
const Noise & | AngularVelocityXNoise () const |
Get the noise values related to the body-frame angular velocity on the X-axis. More... | |
const Noise & | AngularVelocityYNoise () const |
Get the noise values related to the body-frame angular velocity around the Y-axis. More... | |
const Noise & | AngularVelocityZNoise () const |
Get the noise values related to the body-frame angular velocity around the Z-axis. More... | |
const gz::math::Vector3d & | CustomRpy () const |
This field and CustomRpyParentFrame are used when Localization is set to CUSTOM. More... | |
const std::string & | CustomRpyParentFrame () const |
Get the name of parent frame which the custom_rpy transform is defined relative to. More... | |
sdf::ElementPtr | Element () const |
Get a pointer to the SDF element that was used during load. More... | |
gz::math::Vector3d & | GravityDirX () const |
Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector into a plane that is orthogonal to the gravity vector defines the direction of the IMU reference frame's X-axis. More... | |
const std::string & | GravityDirXParentFrame () const |
Get the name of parent frame which the GravityDirX vector is defined relative to. More... | |
const Noise & | LinearAccelerationXNoise () const |
Get the noise values related to the body-frame linear acceleration on the X-axis. More... | |
const Noise & | LinearAccelerationYNoise () const |
Get the noise values related to the body-frame linear acceleration on the Y-axis. More... | |
const Noise & | LinearAccelerationZNoise () const |
Get the noise values related to the body-frame linear acceleration on the Z-axis. More... | |
Errors | Load (ElementPtr _sdf) |
Load the IMU based on an element pointer. More... | |
const std::string & | Localization () const |
This string represents special hardcoded use cases that are commonly seen with typical robot IMU's: More... | |
bool | operator!= (const Imu &_imu) const |
Return true this Imu object does not contain the same values as the passed in parameter. More... | |
Imu & | operator= (const Imu &_imu) |
Assignment operator. More... | |
Imu & | operator= (Imu &&_imu) noexcept |
Move assignment operator. More... | |
bool | operator== (const Imu &_imu) const |
Return true if both Imu objects contain the same values. More... | |
void | SetAngularVelocityXNoise (const Noise &_noise) |
Set the noise values related to the body-frame angular velocity around the X-axis. More... | |
void | SetAngularVelocityYNoise (const Noise &_noise) |
Set the noise values related to the body-frame angular velocity around the Y-axis. More... | |
void | SetAngularVelocityZNoise (const Noise &_noise) |
Set the noise values related to the body-frame angular velocity around the Z-axis. More... | |
void | SetCustomRpy (const gz::math::Vector3d &_rpy) const |
See CustomRpy() const. More... | |
void | SetCustomRpyParentFrame (const std::string &_frame) const |
Set the name of parent frame which the custom_rpy transform is defined relative to. More... | |
void | SetGravityDirX (const gz::math::Vector3d &_grav) const |
Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector into a plane that is orthogonal to the gravity vector defines the direction of the IMU reference frame's X-axis. More... | |
void | SetGravityDirXParentFrame (const std::string &_frame) const |
Set the name of parent frame which the GravityDirX vector is defined relative to. More... | |
void | SetLinearAccelerationXNoise (const Noise &_noise) |
Set the noise values related to the body-frame linear acceleration on the X-axis. More... | |
void | SetLinearAccelerationYNoise (const Noise &_noise) |
Set the noise values related to the body-frame linear acceleration on the Y-axis. More... | |
void | SetLinearAccelerationZNoise (const Noise &_noise) |
Set the noise values related to the body-frame linear acceleration on the Z-axis. More... | |
void | SetLocalization (const std::string &_localization) |
See Localization(const std::string &). More... | |
Imu contains information about an imu sensor.
This sensor can be attached to a link.
sdf::v9::Imu::Imu | ( | ) |
Default constructor.
sdf::v9::Imu::~Imu | ( | ) |
Destructor.
const Noise& sdf::v9::Imu::AngularVelocityXNoise | ( | ) | const |
Get the noise values related to the body-frame angular velocity on the X-axis.
const Noise& sdf::v9::Imu::AngularVelocityYNoise | ( | ) | const |
Get the noise values related to the body-frame angular velocity around the Y-axis.
const Noise& sdf::v9::Imu::AngularVelocityZNoise | ( | ) | const |
Get the noise values related to the body-frame angular velocity around the Z-axis.
const gz::math::Vector3d& sdf::v9::Imu::CustomRpy | ( | ) | const |
This field and CustomRpyParentFrame are used when Localization is set to CUSTOM.
Orientation (fixed axis roll, pitch yaw) transform from ParentFrame to this IMU's reference frame.
Some common examples are:
const std::string& sdf::v9::Imu::CustomRpyParentFrame | ( | ) | const |
Get the name of parent frame which the custom_rpy transform is defined relative to.
It can be any valid fully scoped link name or the special reserved "world" frame. If left empty, use the sensor's own local frame.
sdf::ElementPtr sdf::v9::Imu::Element | ( | ) | const |
gz::math::Vector3d& sdf::v9::Imu::GravityDirX | ( | ) | const |
Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector into a plane that is orthogonal to the gravity vector defines the direction of the IMU reference frame's X-axis.
grav_dir_x is defined in the coordinate frame as defined by the parent_frame element.
const std::string& sdf::v9::Imu::GravityDirXParentFrame | ( | ) | const |
Get the name of parent frame which the GravityDirX vector is defined relative to.
It can be any valid fully scoped link name or the special reserved "world" frame. If left empty, use the sensor's own local frame.
const Noise& sdf::v9::Imu::LinearAccelerationXNoise | ( | ) | const |
Get the noise values related to the body-frame linear acceleration on the X-axis.
const Noise& sdf::v9::Imu::LinearAccelerationYNoise | ( | ) | const |
Get the noise values related to the body-frame linear acceleration on the Y-axis.
const Noise& sdf::v9::Imu::LinearAccelerationZNoise | ( | ) | const |
Get the noise values related to the body-frame linear acceleration on the Z-axis.
Errors sdf::v9::Imu::Load | ( | ElementPtr | _sdf | ) |
const std::string& sdf::v9::Imu::Localization | ( | ) | const |
This string represents special hardcoded use cases that are commonly seen with typical robot IMU's:
GRAV_DOWN: where direction of gravity maps to IMU reference frame Z-axis with Z-axis pointing in the direction of gravity. IMU reference frame X-axis direction is defined by GravityDirX(). Note if GravityDirX() is parallel to gravity direction, this configuration fails. Otherwise, IMU reference frame X-axis is defined by projection of GravityDirX() onto a plane normal to the gravity vector. IMU reference frame Y-axis is a vector orthogonal to both X and Z axis following the right hand rule.
bool sdf::v9::Imu::operator!= | ( | const Imu & | _imu | ) | const |
Assignment operator.
[in] | _imu | The IMU to set values from. |
Move assignment operator.
[in] | _imu | The IMU to set values from. |
bool sdf::v9::Imu::operator== | ( | const Imu & | _imu | ) | const |
void sdf::v9::Imu::SetAngularVelocityXNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame angular velocity around the X-axis.
[in] | _noise | Noise values for the X-axis angular velocity. |
void sdf::v9::Imu::SetAngularVelocityYNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame angular velocity around the Y-axis.
[in] | _noise | Noise values for the Y-axis angular velocity. |
void sdf::v9::Imu::SetAngularVelocityZNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame angular velocity around the Z-axis.
[in] | _noise | Noise values for the Z-axis angular velocity. |
void sdf::v9::Imu::SetCustomRpy | ( | const gz::math::Vector3d & | _rpy | ) | const |
See CustomRpy() const.
[in] | Custom | RPY vectory |
void sdf::v9::Imu::SetCustomRpyParentFrame | ( | const std::string & | _frame | ) | const |
Set the name of parent frame which the custom_rpy transform is defined relative to.
It can be any valid fully scoped link name or the special reserved "world" frame. If left empty, use the sensor's own local frame.
[in] | _frame | The name of the parent frame. |
void sdf::v9::Imu::SetGravityDirX | ( | const gz::math::Vector3d & | _grav | ) | const |
Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector into a plane that is orthogonal to the gravity vector defines the direction of the IMU reference frame's X-axis.
grav_dir_x is defined in the coordinate frame as defined by the parent_frame element.
[in] | _grav | The gravity direction. |
void sdf::v9::Imu::SetGravityDirXParentFrame | ( | const std::string & | _frame | ) | const |
Set the name of parent frame which the GravityDirX vector is defined relative to.
It can be any valid fully scoped link name or the special reserved "world" frame. If left empty, use the sensor's own local frame.
void sdf::v9::Imu::SetLinearAccelerationXNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame linear acceleration on the X-axis.
[in] | _noise | Noise values for the X-axis linear acceleration. |
void sdf::v9::Imu::SetLinearAccelerationYNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame linear acceleration on the Y-axis.
[in] | _noise | Noise values for the Y-axis linear acceleration. |
void sdf::v9::Imu::SetLinearAccelerationZNoise | ( | const Noise & | _noise | ) |
Set the noise values related to the body-frame linear acceleration on the Z-axis.
[in] | _noise | Noise values for the Z-axis linear acceleration. |
void sdf::v9::Imu::SetLocalization | ( | const std::string & | _localization | ) |
See Localization(const std::string &).
[in] | _localization | Localization frame name |