#include <gazebo_magnetometer_plugin.h>
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. |
Definition at line 41 of file gazebo_magnetometer_plugin.h.
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.
Definition at line 26 of file gazebo_magnetometer_plugin.cpp.
Definition at line 33 of file gazebo_magnetometer_plugin.cpp.
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.
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.
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.
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.
std::random_device gazebo::GazeboMagnetometerPlugin::random_device_ [private] |
Definition at line 93 of file gazebo_magnetometer_plugin.h.
std::mt19937 gazebo::GazeboMagnetometerPlugin::random_generator_ [private] |
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.