16 #ifndef __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__ 17 #define __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__ 19 #include <gazebo/gazebo.hh> 22 #include "SensorPressure.pb.h" 23 #include <sensor_msgs/FluidPressure.h> 36 public:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
39 protected:
virtual bool OnUpdate(
const common::UpdateInfo& _info);
56 #endif // __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__ double kPaPerM
Factor of kPa per meter.
~SubseaPressureROSPlugin()
Class destructor.
virtual bool OnUpdate(const common::UpdateInfo &_info)
Update sensor measurement.
SubseaPressureROSPlugin()
Class constructor.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the plugin.
double saturation
Sensor saturation (max. value for output pressure in Pa)
bool estimateDepth
If flag is set to true, estimate depth according to pressure measurement.
double standardPressure
Standard pressure.