Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboMagnetometerPlugin Class Reference

#include <gazebo_magnetometer_plugin.h>

List of all members.

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.

Private Attributes

std::string frame_id_
physics::LinkPtr link_
 Pointer to the link.
gz_sensor_msgs::MagneticField mag_message_
 Magnetic field message.
ignition::math::Vector3d mag_W_
gazebo::transport::PublisherPtr magnetometer_pub_
std::string magnetometer_topic_
physics::ModelPtr model_
 Pointer to the model.
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().
std::random_device random_device_
std::mt19937 random_generator_
event::ConnectionPtr updateConnection_
physics::WorldPtr world_
 Pointer to the world.

Detailed Description

Definition at line 41 of file gazebo_magnetometer_plugin.h.


Member Typedef Documentation

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

Definition at line 44 of file gazebo_magnetometer_plugin.h.

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

Definition at line 45 of file gazebo_magnetometer_plugin.h.


Constructor & Destructor Documentation

Definition at line 26 of file gazebo_magnetometer_plugin.cpp.

Definition at line 33 of file gazebo_magnetometer_plugin.cpp.


Member Function Documentation

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.

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

Definition at line 36 of file gazebo_magnetometer_plugin.cpp.

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

Definition at line 145 of file gazebo_magnetometer_plugin.cpp.


Member Data Documentation

Definition at line 70 of file gazebo_magnetometer_plugin.h.

physics::LinkPtr gazebo::GazeboMagnetometerPlugin::link_ [private]

Pointer to the link.

Definition at line 79 of file gazebo_magnetometer_plugin.h.

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.

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

Definition at line 84 of file gazebo_magnetometer_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboMagnetometerPlugin::magnetometer_pub_ [private]

Definition at line 69 of file gazebo_magnetometer_plugin.h.

Definition at line 67 of file gazebo_magnetometer_plugin.h.

physics::ModelPtr gazebo::GazeboMagnetometerPlugin::model_ [private]

Pointer to the model.

Definition at line 76 of file gazebo_magnetometer_plugin.h.

Definition at line 66 of file gazebo_magnetometer_plugin.h.

gazebo::transport::NodePtr gazebo::GazeboMagnetometerPlugin::node_handle_ [private]

Definition at line 68 of file gazebo_magnetometer_plugin.h.

Definition at line 91 of file gazebo_magnetometer_plugin.h.

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.

Definition at line 93 of file gazebo_magnetometer_plugin.h.

Definition at line 94 of file gazebo_magnetometer_plugin.h.

Definition at line 82 of file gazebo_magnetometer_plugin.h.

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 Thu Apr 18 2019 02:43:43