#include <gazebo_pressure_plugin.h>
| Public Types | |
| typedef std::normal_distribution | NormalDistribution | 
| Public Member Functions | |
| GazeboPressurePlugin () | |
| Constructor. | |
| virtual | ~GazeboPressurePlugin () | 
| Destructor. | |
| Protected Member Functions | |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| Called when the plugin is first created, and after the world has been loaded. This function should not be blocking. | |
| void | OnUpdate (const common::UpdateInfo &) | 
| This gets called by the world update start event. | |
| 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_ | 
| Frame ID for pressure messages. | |
| physics::LinkPtr | link_ | 
| Pointer to the link. | |
| physics::ModelPtr | model_ | 
| Pointer to the model. | |
| std::string | namespace_ | 
| Transport namespace. | |
| gazebo::transport::NodePtr | node_handle_ | 
| Handle for the Gazebo node. | |
| gz_sensor_msgs::FluidPressure | pressure_message_ | 
| Fluid pressure message. | |
| NormalDistribution | pressure_n_ [1] | 
| Normal distribution for pressure noise. | |
| gazebo::transport::PublisherPtr | pressure_pub_ | 
| Pressure message publisher. | |
| std::string | pressure_topic_ | 
| Topic name for pressure messages. | |
| double | pressure_var_ | 
| Pressure measurement variance (Pa^2). | |
| 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::mt19937 | random_generator_ | 
| double | ref_alt_ | 
| Reference altitude (meters). | |
| event::ConnectionPtr | updateConnection_ | 
| Pointer to the update event connection. | |
| physics::WorldPtr | world_ | 
| Pointer to the world. | |
Definition at line 51 of file gazebo_pressure_plugin.h.
| typedef std::normal_distribution gazebo::GazeboPressurePlugin::NormalDistribution | 
Definition at line 59 of file gazebo_pressure_plugin.h.
Constructor.
Definition at line 25 of file gazebo_pressure_plugin.cpp.
| gazebo::GazeboPressurePlugin::~GazeboPressurePlugin | ( | ) |  [virtual] | 
Destructor.
Definition at line 31 of file gazebo_pressure_plugin.cpp.
| void gazebo::GazeboPressurePlugin::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 140 of file gazebo_pressure_plugin.cpp.
| void gazebo::GazeboPressurePlugin::Load | ( | physics::ModelPtr | _model, | 
| sdf::ElementPtr | _sdf | ||
| ) |  [protected] | 
Called when the plugin is first created, and after the world has been loaded. This function should not be blocking.
Definition at line 34 of file gazebo_pressure_plugin.cpp.
| void gazebo::GazeboPressurePlugin::OnUpdate | ( | const common::UpdateInfo & | _info | ) |  [protected] | 
This gets called by the world update start event.
Definition at line 96 of file gazebo_pressure_plugin.cpp.
Frame ID for pressure messages.
Definition at line 93 of file gazebo_pressure_plugin.h.
| physics::LinkPtr gazebo::GazeboPressurePlugin::link_  [private] | 
Pointer to the link.
Definition at line 102 of file gazebo_pressure_plugin.h.
| physics::ModelPtr gazebo::GazeboPressurePlugin::model_  [private] | 
Pointer to the model.
Definition at line 99 of file gazebo_pressure_plugin.h.
Transport namespace.
Definition at line 87 of file gazebo_pressure_plugin.h.
| gazebo::transport::NodePtr gazebo::GazeboPressurePlugin::node_handle_  [private] | 
Handle for the Gazebo node.
Definition at line 81 of file gazebo_pressure_plugin.h.
| gz_sensor_msgs::FluidPressure gazebo::GazeboPressurePlugin::pressure_message_  [private] | 
Fluid pressure message.
This is modified everytime OnUpdate() is called,
Definition at line 119 of file gazebo_pressure_plugin.h.
Normal distribution for pressure noise.
Definition at line 114 of file gazebo_pressure_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboPressurePlugin::pressure_pub_  [private] | 
Pressure message publisher.
Definition at line 84 of file gazebo_pressure_plugin.h.
Topic name for pressure messages.
Definition at line 90 of file gazebo_pressure_plugin.h.
| double gazebo::GazeboPressurePlugin::pressure_var_  [private] | 
Pressure measurement variance (Pa^2).
Definition at line 111 of file gazebo_pressure_plugin.h.
| bool gazebo::GazeboPressurePlugin::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 72 of file gazebo_pressure_plugin.h.
| std::mt19937 gazebo::GazeboPressurePlugin::random_generator_  [private] | 
Definition at line 121 of file gazebo_pressure_plugin.h.
| double gazebo::GazeboPressurePlugin::ref_alt_  [private] | 
Reference altitude (meters).
Definition at line 108 of file gazebo_pressure_plugin.h.
Pointer to the update event connection.
Definition at line 105 of file gazebo_pressure_plugin.h.
| physics::WorldPtr gazebo::GazeboPressurePlugin::world_  [private] | 
Pointer to the world.
Definition at line 96 of file gazebo_pressure_plugin.h.