19 #include <boost/bind.hpp> 20 #include <GeographicLib/Geocentric.hpp> 21 #include <GeographicLib/LocalCartesian.hpp> 23 #include <geometry_msgs/TransformStamped.h> 24 #include <geometry_msgs/Vector3.h> 25 #include <geographic_msgs/GeoPoint.h> 26 #include <std_msgs/Float64.h> 27 #include <sensor_msgs/PointCloud.h> 28 #include <sensor_msgs/NavSatFix.h> 29 #include <nav_msgs/Odometry.h> 30 #include <uuv_plume_msgs/ParticleConcentration.h> 31 #include <uuv_plume_msgs/Salinity.h> 40 #define CONCENTRATION_UNIT_PPT "ppt" 41 #define CONCENTRATION_UNIT_PPM "ppm" 42 #define CONCENTRATION_UNIT_PSU "psu" 57 const sensor_msgs::PointCloud::ConstPtr &_msg);
61 const nav_msgs::Odometry::ConstPtr &_msg);
65 const sensor_msgs::NavSatFix::ConstPtr &_msg);
130 protected: geographic_msgs::GeoPoint
geoPos;
154 protected: std::shared_ptr<tf2_ros::TransformListener>
tfListener;
169 protected: std::default_random_engine
rndGen;
ros::Subscriber odometrySub
Subscriber for odometry topic.
ros::Subscriber particlesSub
Subscriber for the plume particle point cloud.
double updateRate
Output topic's update rate.
uuv_plume_msgs::ParticleConcentration concentrationMsg
Plume concentration message.
bool useTFUpdate
Flag set if the TF update wrt the sensor frame ID.
bool publishSalinity
Flag to activate publishing the simulated salinity.
~CPCSensor()
Class destructor.
bool areParticlesInit
Flag set to true after the first set of plume particles is received.
std::normal_distribution< double > noiseModel
Normal distribution describing the noise model.
geographic_msgs::GeoPoint geoPos
Measured geodetic position.
ros::Subscriber gpsSub
Subscriber to the GPS update topic.
double gamma
Gamma velocity parameter for the smoothing function.
bool useGPS
Flag set if the sensor position update must be read from the vehicle's GPS topic. ...
void OnSensorUpdate(const ros::TimerEvent &)
Update the output concentration and salinity topics.
ros::Timer updateTimer
Sensor update timer.
double smoothingLength
Radius of the kernel to identify particles that will be taken into account in the concentration compu...
double noiseSigma
Noise standard deviation.
ros::Publisher concentrationPub
Output topic for particle concentration.
double referenceSalinityValue
Default salinity value for the fluid e.g. sea water.
double saturation
Sensor saturation.
ros::Publisher salinityPub
Output topic for salinity.
std::default_random_engine rndGen
Pseudo random number generator.
GeographicLib::LocalCartesian projection
Local Cartesian projection.
uuv_plume_msgs::Salinity salinityMsg
Salinity message.
bool useGeoCoordinates
Flag that will allow storing the geodetic coordinates with the measurement message.
std::shared_ptr< ros::NodeHandle > nodeHandle
ROS node handle.
std::string sensorFrameID
Name of the sensor frame.
double plumeSalinityValue
Default salinity value for the plume.
void OnGPSUpdate(const sensor_msgs::NavSatFix::ConstPtr &_msg)
Update the GPS update callback.
bool updateMeasurement
Set to true to avoid particle update.
tf2_ros::Buffer tfBuffer
TF buffer instance.
std::string salinityUnit
Salinity unit to be used. Options are.
void OnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr &_msg)
Update callback from the plume particles.
std::shared_ptr< tf2_ros::TransformListener > tfListener
TF listener pointer.
void OnOdometryUpdate(const nav_msgs::Odometry::ConstPtr &_msg)
Update the odometry callback.
bool updatingCloud
Flag to ensure the cloud and measurement update don't coincide.
geometry_msgs::Vector3 cartPos
Measured Cartesian position.
bool useOdom
Flag set if the sensor position update must be read from the vehicle's odometry input topic...
CPCSensor()
Class constructor.
double noiseAmp
Noise amplitude.