#include <gazebo_imu_plugin.h>
|
| void | AddNoise (Eigen::Vector3d *linear_acceleration, Eigen::Vector3d *angular_velocity, const double dt) |
| | This method adds noise to acceleration and angular rates for accelerometer and gyroscope measurement simulation. More...
|
| |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
| |
| void | OnUpdate (const common::UpdateInfo &) |
| | This gets called by the world update start event. More...
|
| |
|
| void | CreatePubsAndSubs () |
| | Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
|
| |
Definition at line 97 of file gazebo_imu_plugin.h.
◆ GazeboImuPlugin()
| gazebo::GazeboImuPlugin::GazeboImuPlugin |
( |
| ) |
|
◆ ~GazeboImuPlugin()
| gazebo::GazeboImuPlugin::~GazeboImuPlugin |
( |
| ) |
|
◆ AddNoise()
| void gazebo::GazeboImuPlugin::AddNoise |
( |
Eigen::Vector3d * |
linear_acceleration, |
|
|
Eigen::Vector3d * |
angular_velocity, |
|
|
const double |
dt |
|
) |
| |
|
protected |
This method adds noise to acceleration and angular rates for accelerometer and gyroscope measurement simulation.
Definition at line 213 of file gazebo_imu_plugin.cpp.
◆ CreatePubsAndSubs()
| void gazebo::GazeboImuPlugin::CreatePubsAndSubs |
( |
| ) |
|
|
private |
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.
Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).
Definition at line 340 of file gazebo_imu_plugin.cpp.
◆ InitializeParams()
| void gazebo::GazeboImuPlugin::InitializeParams |
( |
| ) |
|
◆ Load()
| void gazebo::GazeboImuPlugin::Load |
( |
physics::ModelPtr |
_model, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
protected |
◆ OnUpdate()
| void gazebo::GazeboImuPlugin::OnUpdate |
( |
const common::UpdateInfo & |
_info | ) |
|
|
protected |
This gets called by the world update start event.
Calculates IMU parameters and then publishes one IMU message.
- Todo:
- (burrimi): Add orientation estimator.
- Todo:
- (burrimi): add noise.
Definition at line 266 of file gazebo_imu_plugin.cpp.
◆ Publish()
| void gazebo::GazeboImuPlugin::Publish |
( |
| ) |
|
◆ accelerometer_bias_
| Eigen::Vector3d gazebo::GazeboImuPlugin::accelerometer_bias_ |
|
private |
◆ accelerometer_turn_on_bias_
| Eigen::Vector3d gazebo::GazeboImuPlugin::accelerometer_turn_on_bias_ |
|
private |
◆ frame_id_
| std::string gazebo::GazeboImuPlugin::frame_id_ |
|
private |
◆ gravity_W_
| ignition::math::Vector3d gazebo::GazeboImuPlugin::gravity_W_ |
|
private |
◆ gyroscope_bias_
| Eigen::Vector3d gazebo::GazeboImuPlugin::gyroscope_bias_ |
|
private |
◆ gyroscope_turn_on_bias_
| Eigen::Vector3d gazebo::GazeboImuPlugin::gyroscope_turn_on_bias_ |
|
private |
◆ imu_message_
| gz_sensor_msgs::Imu gazebo::GazeboImuPlugin::imu_message_ |
|
private |
◆ imu_parameters_
◆ imu_pub_
| transport::PublisherPtr gazebo::GazeboImuPlugin::imu_pub_ |
|
private |
◆ imu_topic_
| std::string gazebo::GazeboImuPlugin::imu_topic_ |
|
private |
◆ last_time_
| common::Time gazebo::GazeboImuPlugin::last_time_ |
|
private |
◆ link_
| physics::LinkPtr gazebo::GazeboImuPlugin::link_ |
|
private |
◆ link_name_
| std::string gazebo::GazeboImuPlugin::link_name_ |
|
private |
◆ model_
| physics::ModelPtr gazebo::GazeboImuPlugin::model_ |
|
private |
◆ namespace_
| std::string gazebo::GazeboImuPlugin::namespace_ |
|
private |
◆ node_handle_
| transport::NodePtr gazebo::GazeboImuPlugin::node_handle_ |
|
private |
◆ pubs_and_subs_created_
| bool gazebo::GazeboImuPlugin::pubs_and_subs_created_ |
|
private |
◆ random_generator_
| std::default_random_engine gazebo::GazeboImuPlugin::random_generator_ |
|
private |
◆ standard_normal_distribution_
| std::normal_distribution<double> gazebo::GazeboImuPlugin::standard_normal_distribution_ |
|
private |
◆ updateConnection_
◆ velocity_prev_W_
| ignition::math::Vector3d gazebo::GazeboImuPlugin::velocity_prev_W_ |
|
private |
◆ world_
| physics::WorldPtr gazebo::GazeboImuPlugin::world_ |
|
private |
The documentation for this class was generated from the following files:
rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04