Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboMagnetometerPlugin Class Reference

#include <gazebo_magnetometer_plugin.h>

Inheritance diagram for gazebo::GazeboMagnetometerPlugin:
Inheritance graph
[legend]

Public Types

typedef std::normal_distribution NormalDistribution
 
typedef std::uniform_real_distribution UniformDistribution
 

Public Member Functions

 GazeboMagnetometerPlugin ()
 
virtual ~GazeboMagnetometerPlugin ()
 

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
void OnUpdate (const common::UpdateInfo &)
 

Private Member Functions

void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
 

Private Attributes

std::string frame_id_
 
physics::LinkPtr link_
 Pointer to the link. More...
 
gz_sensor_msgs::MagneticField mag_message_
 Magnetic field message. More...
 
ignition::math::Vector3d mag_W_
 
gazebo::transport::PublisherPtr magnetometer_pub_
 
std::string magnetometer_topic_
 
physics::ModelPtr model_
 Pointer to the model. More...
 
std::string namespace_
 
gazebo::transport::NodePtr node_handle_
 
NormalDistribution noise_n_ [3]
 
bool pubs_and_subs_created_
 Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate(). More...
 
std::random_device random_device_
 
std::mt19937 random_generator_
 
event::ConnectionPtr updateConnection_
 
physics::WorldPtr world_
 Pointer to the world. More...
 

Detailed Description

Definition at line 41 of file gazebo_magnetometer_plugin.h.

Member Typedef Documentation

◆ NormalDistribution

typedef std::normal_distribution gazebo::GazeboMagnetometerPlugin::NormalDistribution

Definition at line 44 of file gazebo_magnetometer_plugin.h.

◆ UniformDistribution

typedef std::uniform_real_distribution gazebo::GazeboMagnetometerPlugin::UniformDistribution

Definition at line 45 of file gazebo_magnetometer_plugin.h.

Constructor & Destructor Documentation

◆ GazeboMagnetometerPlugin()

gazebo::GazeboMagnetometerPlugin::GazeboMagnetometerPlugin ( )

Definition at line 26 of file gazebo_magnetometer_plugin.cpp.

◆ ~GazeboMagnetometerPlugin()

gazebo::GazeboMagnetometerPlugin::~GazeboMagnetometerPlugin ( )
virtual

Definition at line 33 of file gazebo_magnetometer_plugin.cpp.

Member Function Documentation

◆ CreatePubsAndSubs()

void gazebo::GazeboMagnetometerPlugin::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 178 of file gazebo_magnetometer_plugin.cpp.

◆ Load()

void gazebo::GazeboMagnetometerPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protected

Definition at line 36 of file gazebo_magnetometer_plugin.cpp.

◆ OnUpdate()

void gazebo::GazeboMagnetometerPlugin::OnUpdate ( const common::UpdateInfo &  _info)
protected

Definition at line 145 of file gazebo_magnetometer_plugin.cpp.

Member Data Documentation

◆ frame_id_

std::string gazebo::GazeboMagnetometerPlugin::frame_id_
private

Definition at line 70 of file gazebo_magnetometer_plugin.h.

◆ link_

physics::LinkPtr gazebo::GazeboMagnetometerPlugin::link_
private

Pointer to the link.

Definition at line 79 of file gazebo_magnetometer_plugin.h.

◆ mag_message_

gz_sensor_msgs::MagneticField gazebo::GazeboMagnetometerPlugin::mag_message_
private

Magnetic field message.

Reused message object which is defined here to reduce memory allocation.

Definition at line 89 of file gazebo_magnetometer_plugin.h.

◆ mag_W_

ignition::math::Vector3d gazebo::GazeboMagnetometerPlugin::mag_W_
private

Definition at line 84 of file gazebo_magnetometer_plugin.h.

◆ magnetometer_pub_

gazebo::transport::PublisherPtr gazebo::GazeboMagnetometerPlugin::magnetometer_pub_
private

Definition at line 69 of file gazebo_magnetometer_plugin.h.

◆ magnetometer_topic_

std::string gazebo::GazeboMagnetometerPlugin::magnetometer_topic_
private

Definition at line 67 of file gazebo_magnetometer_plugin.h.

◆ model_

physics::ModelPtr gazebo::GazeboMagnetometerPlugin::model_
private

Pointer to the model.

Definition at line 76 of file gazebo_magnetometer_plugin.h.

◆ namespace_

std::string gazebo::GazeboMagnetometerPlugin::namespace_
private

Definition at line 66 of file gazebo_magnetometer_plugin.h.

◆ node_handle_

gazebo::transport::NodePtr gazebo::GazeboMagnetometerPlugin::node_handle_
private

Definition at line 68 of file gazebo_magnetometer_plugin.h.

◆ noise_n_

NormalDistribution gazebo::GazeboMagnetometerPlugin::noise_n_[3]
private

Definition at line 91 of file gazebo_magnetometer_plugin.h.

◆ pubs_and_subs_created_

bool gazebo::GazeboMagnetometerPlugin::pubs_and_subs_created_
private

Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().

Definition at line 58 of file gazebo_magnetometer_plugin.h.

◆ random_device_

std::random_device gazebo::GazeboMagnetometerPlugin::random_device_
private

Definition at line 93 of file gazebo_magnetometer_plugin.h.

◆ random_generator_

std::mt19937 gazebo::GazeboMagnetometerPlugin::random_generator_
private

Definition at line 94 of file gazebo_magnetometer_plugin.h.

◆ updateConnection_

event::ConnectionPtr gazebo::GazeboMagnetometerPlugin::updateConnection_
private

Definition at line 82 of file gazebo_magnetometer_plugin.h.

◆ world_

physics::WorldPtr gazebo::GazeboMagnetometerPlugin::world_
private

Pointer to the world.

Definition at line 73 of file gazebo_magnetometer_plugin.h.


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