Skip to content

CPCSensor

class uuv_plume_simulator::CPCSensor

Summary
Members Descriptions
publicCPCSensor() Class constructor.
public~CPCSensor() Class destructor.
protected boolupdatingCloud Flag to ensure the cloud and measurement update don't coincide.
protected doublegamma Gamma velocity parameter for the smoothing function.
protected doublegain Sensor gain.
protected doublesmoothingLength Radius of the kernel to identify particles that will be taken into account in the concentration computation.
protected std::stringsalinityUnit Salinity unit to be used. Options are.
protected doublesaturation Sensor saturation.
protected booluseGeoCoordinates Flag that will allow storing the geodetic coordinates with the measurement message.
protected boolpublishSalinity Flag to activate publishing the simulated salinity.
protected doublereferenceSalinityValue Default salinity value for the fluid e.g. sea water.
protected doubleplumeSalinityValue Default salinity value for the plume.
protected boolupdateMeasurement Set to true to avoid particle update.
protected doubleupdateRate Output topic's update rate.
protected std::stringsensorFrameID Name of the sensor frame.
protected boolareParticlesInit Flag set to true after the first set of plume particles is received.
protected booluseOdom Flag set if the sensor position update must be read from the vehicle's odometry input topic.
protected booluseGPS Flag set if the sensor position update must be read from the vehicle's GPS topic.
protected booluseTFUpdate Flag set if the TF update wrt the sensor frame ID.
protected geometry_msgs::Vector3cartPos Measured Cartesian position.
protected geographic_msgs::GeoPointgeoPos Measured geodetic position.
protected ros::SubscriberparticlesSub Subscriber for the plume particle point cloud.
protected ros::SubscriberodometrySub Subscriber for odometry topic.
protected ros::SubscribergpsSub Subscriber to the GPS update topic.
protected ros::PublisherconcentrationPub Output topic for particle concentration.
protected ros::PublishersalinityPub Output topic for salinity.
protected std::shared_ptr< ros::NodeHandle >nodeHandle ROS node handle.
protected tf2_ros::BuffertfBuffer TF buffer instance.
protected std::shared_ptr< tf2_ros::TransformListener >tfListener TF listener pointer.
protected GeographicLib::LocalCartesianprojection Local Cartesian projection.
protected uuv_plume_msgs::ParticleConcentrationconcentrationMsg Plume concentration message.
protected uuv_plume_msgs::SalinitysalinityMsg Salinity message.
protected ros::TimerupdateTimer Sensor update timer.
protected std::default_random_enginerndGen Pseudo random number generator.
protected std::normal_distribution< double >noiseModel Normal distribution describing the noise model.
protected doublenoiseAmp Noise amplitude.
protected doublenoiseSigma Noise standard deviation.
protected voidOnSensorUpdate(const ros::TimerEvent &) Update the output concentration and salinity topics.
protected voidOnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr & _msg) Update callback from the plume particles.
protected voidOnOdometryUpdate(const nav_msgs::Odometry::ConstPtr & _msg) Update the odometry callback.
protected voidOnGPSUpdate(const sensor_msgs::NavSatFix::ConstPtr & _msg) Update the GPS update callback.
Members
publicCPCSensor()

Class constructor.

public~CPCSensor()

Class destructor.

protected boolupdatingCloud

Flag to ensure the cloud and measurement update don't coincide.

protected doublegamma

Gamma velocity parameter for the smoothing function.

protected doublegain

Sensor gain.

protected doublesmoothingLength

Radius of the kernel to identify particles that will be taken into account in the concentration computation.

protected std::stringsalinityUnit

Salinity unit to be used. Options are.

  • ppt (parts per thousand)

  • ppm (parts per million)

  • psu (practical salinity unit)

protected doublesaturation

Sensor saturation.

protected booluseGeoCoordinates

Flag that will allow storing the geodetic coordinates with the measurement message.

protected boolpublishSalinity

Flag to activate publishing the simulated salinity.

protected doublereferenceSalinityValue

Default salinity value for the fluid e.g. sea water.

protected doubleplumeSalinityValue

Default salinity value for the plume.

protected boolupdateMeasurement

Set to true to avoid particle update.

protected doubleupdateRate

Output topic's update rate.

protected std::stringsensorFrameID

Name of the sensor frame.

protected boolareParticlesInit

Flag set to true after the first set of plume particles is received.

protected booluseOdom

Flag set if the sensor position update must be read from the vehicle's odometry input topic.

protected booluseGPS

Flag set if the sensor position update must be read from the vehicle's GPS topic.

protected booluseTFUpdate

Flag set if the TF update wrt the sensor frame ID.

protected geometry_msgs::Vector3cartPos

Measured Cartesian position.

protected geographic_msgs::GeoPointgeoPos

Measured geodetic position.

protected ros::SubscriberparticlesSub

Subscriber for the plume particle point cloud.

protected ros::SubscriberodometrySub

Subscriber for odometry topic.

protected ros::SubscribergpsSub

Subscriber to the GPS update topic.

protected ros::PublisherconcentrationPub

Output topic for particle concentration.

protected ros::PublishersalinityPub

Output topic for salinity.

protected std::shared_ptr< ros::NodeHandle >nodeHandle

ROS node handle.

protected tf2_ros::BuffertfBuffer

TF buffer instance.

protected std::shared_ptr< tf2_ros::TransformListener >tfListener

TF listener pointer.

protected GeographicLib::LocalCartesianprojection

Local Cartesian projection.

protected uuv_plume_msgs::ParticleConcentrationconcentrationMsg

Plume concentration message.

protected uuv_plume_msgs::SalinitysalinityMsg

Salinity message.

protected ros::TimerupdateTimer

Sensor update timer.

protected std::default_random_enginerndGen

Pseudo random number generator.

protected std::normal_distribution< double >noiseModel

Normal distribution describing the noise model.

protected doublenoiseAmp

Noise amplitude.

protected doublenoiseSigma

Noise standard deviation.

protected voidOnSensorUpdate(const ros::TimerEvent &)

Update the output concentration and salinity topics.

protected voidOnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr & _msg)

Update callback from the plume particles.

protected voidOnOdometryUpdate(const nav_msgs::Odometry::ConstPtr & _msg)

Update the odometry callback.

protected voidOnGPSUpdate(const sensor_msgs::NavSatFix::ConstPtr & _msg)

Update the GPS update callback.