CPCROSPlugin.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_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__
17 #define __UUV_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__
18 
19 #include <gazebo/gazebo.hh>
20 #include <ros/ros.h>
22 #include <uuv_sensor_ros_plugins_msgs/ChemicalParticleConcentration.h>
23 #include <uuv_sensor_ros_plugins_msgs/Salinity.h>
24 #include <sensor_msgs/PointCloud.h>
26 
27 namespace gazebo
28 {
30  {
32  public: CPCROSPlugin();
33 
35  public: virtual ~CPCROSPlugin();
36 
38  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
39 
41  protected: virtual bool OnUpdate(const common::UpdateInfo& _info);
42 
44  protected: virtual void OnPlumeParticlesUpdate(
45  const sensor_msgs::PointCloud::ConstPtr &_msg);
46 
49 
52 
54  protected: bool updatingCloud;
55 
57  protected: double gamma;
58 
60  protected: double gain;
61 
62  // \brief Radius of the kernel to identify particles that will be taken into
63  // account in the concentration computation
64  protected: double smoothingLength;
65 
68 
70  protected: uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration
72 
74  protected: uuv_sensor_ros_plugins_msgs::Salinity salinityMsg;
75 
76  protected: double waterSalinityValue;
77 
78  protected: double plumeSalinityValue;
79  };
80 }
81 
82 #endif // __UUV_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__
bool updatingCloud
Flag to ensure the cloud and measurement update don&#39;t coincide.
Definition: CPCROSPlugin.hh:54
virtual ~CPCROSPlugin()
Class destructor.
Definition: CPCROSPlugin.cc:25
uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration outputMsg
Output measurement topic.
Definition: CPCROSPlugin.hh:71
CPCROSPlugin()
Class constructor.
Definition: CPCROSPlugin.cc:21
ros::Subscriber particlesSub
Input topic for the plume particle point cloud.
Definition: CPCROSPlugin.hh:48
ros::Time lastUpdateTimestamp
Last update from the point cloud callback.
Definition: CPCROSPlugin.hh:67
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the plugin.
Definition: CPCROSPlugin.cc:29
virtual void OnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr &_msg)
Update callback from simulator.
uuv_sensor_ros_plugins_msgs::Salinity salinityMsg
Output salinity measurement message.
Definition: CPCROSPlugin.hh:74
virtual bool OnUpdate(const common::UpdateInfo &_info)
Update sensor measurement.
ros::Publisher salinityPub
Output topic for salinity measurements based on the particle concentration.
Definition: CPCROSPlugin.hh:51
double gain
Sensor gain.
Definition: CPCROSPlugin.hh:60
double gamma
Gamma velocity parameter for the smoothing function.
Definition: CPCROSPlugin.hh:57


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:33