#include <gazebo_magnetometer_plugin.h>
|
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
| |
| void | OnUpdate (const common::UpdateInfo &) |
| |
|
| void | CreatePubsAndSubs () |
| | Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
|
| |
◆ NormalDistribution
◆ UniformDistribution
◆ GazeboMagnetometerPlugin()
| gazebo::GazeboMagnetometerPlugin::GazeboMagnetometerPlugin |
( |
| ) |
|
◆ ~GazeboMagnetometerPlugin()
| gazebo::GazeboMagnetometerPlugin::~GazeboMagnetometerPlugin |
( |
| ) |
|
|
virtual |
◆ 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 |
◆ OnUpdate()
| void gazebo::GazeboMagnetometerPlugin::OnUpdate |
( |
const common::UpdateInfo & |
_info | ) |
|
|
protected |
◆ frame_id_
| std::string gazebo::GazeboMagnetometerPlugin::frame_id_ |
|
private |
◆ link_
| physics::LinkPtr gazebo::GazeboMagnetometerPlugin::link_ |
|
private |
◆ 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 |
◆ magnetometer_pub_
| gazebo::transport::PublisherPtr gazebo::GazeboMagnetometerPlugin::magnetometer_pub_ |
|
private |
◆ magnetometer_topic_
| std::string gazebo::GazeboMagnetometerPlugin::magnetometer_topic_ |
|
private |
◆ model_
| physics::ModelPtr gazebo::GazeboMagnetometerPlugin::model_ |
|
private |
◆ namespace_
| std::string gazebo::GazeboMagnetometerPlugin::namespace_ |
|
private |
◆ node_handle_
| gazebo::transport::NodePtr gazebo::GazeboMagnetometerPlugin::node_handle_ |
|
private |
◆ noise_n_
◆ pubs_and_subs_created_
| bool gazebo::GazeboMagnetometerPlugin::pubs_and_subs_created_ |
|
private |
◆ random_device_
| std::random_device gazebo::GazeboMagnetometerPlugin::random_device_ |
|
private |
◆ random_generator_
| std::mt19937 gazebo::GazeboMagnetometerPlugin::random_generator_ |
|
private |
◆ updateConnection_
◆ world_
| physics::WorldPtr gazebo::GazeboMagnetometerPlugin::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