16 #ifndef __UUV_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__ 17 #define __UUV_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__ 19 #include <gazebo/gazebo.hh> 22 #include <uuv_sensor_ros_plugins_msgs/ChemicalParticleConcentration.h> 23 #include <uuv_sensor_ros_plugins_msgs/Salinity.h> 24 #include <sensor_msgs/PointCloud.h> 38 public:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
41 protected:
virtual bool OnUpdate(
const common::UpdateInfo& _info);
45 const sensor_msgs::PointCloud::ConstPtr &_msg);
70 protected: uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration
82 #endif // __UUV_CHEMICAL_PARTICLE_CONCENTRATION_ROS_PLUGIN_HH__ bool updatingCloud
Flag to ensure the cloud and measurement update don't coincide.
virtual ~CPCROSPlugin()
Class destructor.
uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration outputMsg
Output measurement topic.
CPCROSPlugin()
Class constructor.
ros::Subscriber particlesSub
Input topic for the plume particle point cloud.
ros::Time lastUpdateTimestamp
Last update from the point cloud callback.
double waterSalinityValue
double plumeSalinityValue
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the plugin.
virtual void OnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr &_msg)
Update callback from simulator.
uuv_sensor_ros_plugins_msgs::Salinity salinityMsg
Output salinity measurement message.
virtual bool OnUpdate(const common::UpdateInfo &_info)
Update sensor measurement.
ros::Publisher salinityPub
Output topic for salinity measurements based on the particle concentration.
double gamma
Gamma velocity parameter for the smoothing function.