SubseaPressureROSPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__
17 #define __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__
18 
19 #include <gazebo/gazebo.hh>
20 #include <ros/ros.h>
22 #include "SensorPressure.pb.h"
23 #include <sensor_msgs/FluidPressure.h>
24 
25 namespace gazebo
26 {
28  {
30  public: SubseaPressureROSPlugin();
31 
33  public: ~SubseaPressureROSPlugin();
34 
36  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
37 
39  protected: virtual bool OnUpdate(const common::UpdateInfo& _info);
40 
42  protected: double saturation;
43 
46  protected: bool estimateDepth;
47 
49  protected: double standardPressure;
50 
52  protected: double kPaPerM;
53  };
54 }
55 
56 #endif // __UUV_SUBSEA_PRESSURE_ROS_PLUGIN_HH__
double kPaPerM
Factor of kPa per meter.
virtual bool OnUpdate(const common::UpdateInfo &_info)
Update sensor measurement.
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.


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:20