CPCROSPlugin
class gazebo::CPCROSPlugin
¶
class gazebo::CPCROSPlugin : public gazebo::ROSBaseModelPlugin
Summary¶
Members | Descriptions |
---|---|
public CPCROSPlugin () |
Class constructor. |
public virtual ~CPCROSPlugin () |
Class destructor. |
public virtual void Load (physics::ModelPtr _model,sdf::ElementPtr _sdf) |
Load the plugin. |
protected ros::Subscriber particlesSub |
Input topic for the plume particle point cloud. |
protected ros::Publisher salinityPub |
Output topic for salinity measurements based on the particle concentration. |
protected bool updatingCloud |
Flag to ensure the cloud and measurement update don't coincide. |
protected double gamma |
Gamma velocity parameter for the smoothing function. |
protected double gain |
Sensor gain. |
protected double smoothingLength |
|
protected ros::Time lastUpdateTimestamp |
Last update from the point cloud callback. |
protected uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration outputMsg |
Output measurement topic. |
protected uuv_sensor_ros_plugins_msgs::Salinity salinityMsg |
Output salinity measurement message. |
protected double waterSalinityValue |
|
protected double plumeSalinityValue |
|
protected virtual bool OnUpdate (const common::UpdateInfo & _info) |
Update sensor measurement. |
protected virtual void OnPlumeParticlesUpdate (const sensor_msgs::PointCloud::ConstPtr & _msg) |
Update callback from simulator. |
Members¶
public
CPCROSPlugin
()
¶
Class constructor.
public virtual
~CPCROSPlugin
()
¶
Class destructor.
public virtual void
Load
(physics::ModelPtr _model,sdf::ElementPtr _sdf)
¶
Load the plugin.
protected ros::Subscriber
particlesSub
¶
Input topic for the plume particle point cloud.
protected ros::Publisher
salinityPub
¶
Output topic for salinity measurements based on the particle concentration.
protected bool
updatingCloud
¶
Flag to ensure the cloud and measurement update don't coincide.
protected double
gamma
¶
Gamma velocity parameter for the smoothing function.
protected double
gain
¶
Sensor gain.
protected double
smoothingLength
¶
protected ros::Time
lastUpdateTimestamp
¶
Last update from the point cloud callback.
protected uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration
outputMsg
¶
Output measurement topic.
protected uuv_sensor_ros_plugins_msgs::Salinity
salinityMsg
¶
Output salinity measurement message.
protected double
waterSalinityValue
¶
protected double
plumeSalinityValue
¶
protected virtual bool
OnUpdate
(const common::UpdateInfo & _info)
¶
Update sensor measurement.
protected virtual void
OnPlumeParticlesUpdate
(const sensor_msgs::PointCloud::ConstPtr & _msg)
¶
Update callback from simulator.