IMUROSPlugin
class gazebo::IMUROSPlugin
¶
class gazebo::IMUROSPlugin : public gazebo::ROSBaseModelPlugin
Summary¶
Members | Descriptions |
---|---|
public IMUROSPlugin () |
Class constructor. |
public virtual ~IMUROSPlugin () |
Class destructor. |
public virtual void Load (physics::ModelPtr _model,sdf::ElementPtr _sdf) |
Load the plugin. |
protected ignition::math::Vector3d measLinearAcc |
Last measurement of linear acceleration.. |
protected ignition::math::Vector3d measAngularVel |
Last measurement of angular velocity. |
protected ignition::math::Quaterniond measOrientation |
(Simulation) time when the last sensor measurement was generated. |
protected ignition::math::Vector3d gravityWorld |
Gravity vector wrt. reference frame. |
protected ignition::math::Vector3d gyroscopeBias |
Current (drifting) gyroscope bias. |
protected ignition::math::Vector3d accelerometerBias |
Current (drifting) accelerometer bias. |
protected ignition::math::Vector3d gyroscopeTurnOnBias |
Constant turn-on gyroscope bias. |
protected ignition::math::Vector3d accelerometerTurnOnBias |
Constant turn-on accelerometer bias. |
protected IMUParameters
imuParameters |
IMU model parameters. |
protected sensor_msgs::Imu imuROSMessage |
ROS IMU message. |
protected virtual bool OnUpdate (const common::UpdateInfo & _info) |
Update sensor measurement. |
protected void AddNoise (ignition::math::Vector3d & _linAcc,ignition::math::Vector3d & _angVel,ignition::math::Quaterniond & _orientation,double _dt) |
Apply and add nosie model to ideal measurements. |
Members¶
public
IMUROSPlugin
()
¶
Class constructor.
public virtual
~IMUROSPlugin
()
¶
Class destructor.
public virtual void
Load
(physics::ModelPtr _model,sdf::ElementPtr _sdf)
¶
Load the plugin.
protected ignition::math::Vector3d
measLinearAcc
¶
Last measurement of linear acceleration..
protected ignition::math::Vector3d
measAngularVel
¶
Last measurement of angular velocity.
protected ignition::math::Quaterniond
measOrientation
¶
(Simulation) time when the last sensor measurement was generated.
protected ignition::math::Vector3d
gravityWorld
¶
Gravity vector wrt. reference frame.
protected ignition::math::Vector3d
gyroscopeBias
¶
Current (drifting) gyroscope bias.
protected ignition::math::Vector3d
accelerometerBias
¶
Current (drifting) accelerometer bias.
protected ignition::math::Vector3d
gyroscopeTurnOnBias
¶
Constant turn-on gyroscope bias.
protected ignition::math::Vector3d
accelerometerTurnOnBias
¶
Constant turn-on accelerometer bias.
protected
IMUParameters
imuParameters
¶
IMU model parameters.
protected sensor_msgs::Imu
imuROSMessage
¶
ROS IMU message.
protected virtual bool
OnUpdate
(const common::UpdateInfo & _info)
¶
Update sensor measurement.
protected void
AddNoise
(ignition::math::Vector3d & _linAcc,ignition::math::Vector3d & _angVel,ignition::math::Quaterniond & _orientation,double _dt)
¶
Apply and add nosie model to ideal measurements.