#include <CPCSensor.hh>
Public Member Functions | |
CPCSensor () | |
Class constructor. More... | |
~CPCSensor () | |
Class destructor. More... | |
Protected Member Functions | |
void | OnGPSUpdate (const sensor_msgs::NavSatFix::ConstPtr &_msg) |
Update the GPS update callback. More... | |
void | OnOdometryUpdate (const nav_msgs::Odometry::ConstPtr &_msg) |
Update the odometry callback. More... | |
void | OnPlumeParticlesUpdate (const sensor_msgs::PointCloud::ConstPtr &_msg) |
Update callback from the plume particles. More... | |
void | OnSensorUpdate (const ros::TimerEvent &) |
Update the output concentration and salinity topics. More... | |
Protected Attributes | |
bool | areParticlesInit |
Flag set to true after the first set of plume particles is received. More... | |
geometry_msgs::Vector3 | cartPos |
Measured Cartesian position. More... | |
uuv_plume_msgs::ParticleConcentration | concentrationMsg |
Plume concentration message. More... | |
ros::Publisher | concentrationPub |
Output topic for particle concentration. More... | |
double | gain |
Sensor gain. More... | |
double | gamma |
Gamma velocity parameter for the smoothing function. More... | |
geographic_msgs::GeoPoint | geoPos |
Measured geodetic position. More... | |
ros::Subscriber | gpsSub |
Subscriber to the GPS update topic. More... | |
std::shared_ptr< ros::NodeHandle > | nodeHandle |
ROS node handle. More... | |
double | noiseAmp |
Noise amplitude. More... | |
std::normal_distribution< double > | noiseModel |
Normal distribution describing the noise model. More... | |
double | noiseSigma |
Noise standard deviation. More... | |
ros::Subscriber | odometrySub |
Subscriber for odometry topic. More... | |
ros::Subscriber | particlesSub |
Subscriber for the plume particle point cloud. More... | |
double | plumeSalinityValue |
Default salinity value for the plume. More... | |
GeographicLib::LocalCartesian | projection |
Local Cartesian projection. More... | |
bool | publishSalinity |
Flag to activate publishing the simulated salinity. More... | |
double | referenceSalinityValue |
Default salinity value for the fluid e.g. sea water. More... | |
std::default_random_engine | rndGen |
Pseudo random number generator. More... | |
uuv_plume_msgs::Salinity | salinityMsg |
Salinity message. More... | |
ros::Publisher | salinityPub |
Output topic for salinity. More... | |
std::string | salinityUnit |
Salinity unit to be used. Options are. More... | |
double | saturation |
Sensor saturation. More... | |
std::string | sensorFrameID |
Name of the sensor frame. More... | |
double | smoothingLength |
Radius of the kernel to identify particles that will be taken into account in the concentration computation. More... | |
tf2_ros::Buffer | tfBuffer |
TF buffer instance. More... | |
std::shared_ptr< tf2_ros::TransformListener > | tfListener |
TF listener pointer. More... | |
bool | updateMeasurement |
Set to true to avoid particle update. More... | |
double | updateRate |
Output topic's update rate. More... | |
ros::Timer | updateTimer |
Sensor update timer. More... | |
bool | updatingCloud |
Flag to ensure the cloud and measurement update don't coincide. More... | |
bool | useGeoCoordinates |
Flag that will allow storing the geodetic coordinates with the measurement message. More... | |
bool | useGPS |
Flag set if the sensor position update must be read from the vehicle's GPS topic. More... | |
bool | useOdom |
Flag set if the sensor position update must be read from the vehicle's odometry input topic. More... | |
bool | useTFUpdate |
Flag set if the TF update wrt the sensor frame ID. More... | |
Definition at line 44 of file CPCSensor.hh.
CPCSensor::CPCSensor | ( | ) |
Class constructor.
Definition at line 21 of file CPCSensor.cc.
CPCSensor::~CPCSensor | ( | ) |
Class destructor.
Definition at line 187 of file CPCSensor.cc.
|
protected |
Update the GPS update callback.
Definition at line 330 of file CPCSensor.cc.
|
protected |
Update the odometry callback.
Definition at line 316 of file CPCSensor.cc.
|
protected |
Update callback from the plume particles.
Definition at line 193 of file CPCSensor.cc.
|
protected |
Update the output concentration and salinity topics.
Definition at line 348 of file CPCSensor.cc.
|
protected |
Flag set to true after the first set of plume particles is received.
Definition at line 113 of file CPCSensor.hh.
|
protected |
Measured Cartesian position.
Definition at line 127 of file CPCSensor.hh.
|
protected |
Plume concentration message.
Definition at line 160 of file CPCSensor.hh.
|
protected |
Output topic for particle concentration.
Definition at line 142 of file CPCSensor.hh.
|
protected |
Sensor gain.
Definition at line 74 of file CPCSensor.hh.
|
protected |
Gamma velocity parameter for the smoothing function.
Definition at line 71 of file CPCSensor.hh.
|
protected |
Measured geodetic position.
Definition at line 130 of file CPCSensor.hh.
|
protected |
Subscriber to the GPS update topic.
Definition at line 139 of file CPCSensor.hh.
|
protected |
ROS node handle.
Definition at line 148 of file CPCSensor.hh.
|
protected |
Noise amplitude.
Definition at line 175 of file CPCSensor.hh.
|
protected |
Normal distribution describing the noise model.
Definition at line 172 of file CPCSensor.hh.
|
protected |
Noise standard deviation.
Definition at line 178 of file CPCSensor.hh.
|
protected |
Subscriber for odometry topic.
Definition at line 136 of file CPCSensor.hh.
|
protected |
Subscriber for the plume particle point cloud.
Definition at line 133 of file CPCSensor.hh.
|
protected |
Default salinity value for the plume.
Definition at line 100 of file CPCSensor.hh.
|
protected |
Local Cartesian projection.
Definition at line 157 of file CPCSensor.hh.
|
protected |
Flag to activate publishing the simulated salinity.
Definition at line 94 of file CPCSensor.hh.
|
protected |
Default salinity value for the fluid e.g. sea water.
Definition at line 97 of file CPCSensor.hh.
|
protected |
Pseudo random number generator.
Definition at line 169 of file CPCSensor.hh.
|
protected |
Salinity message.
Definition at line 163 of file CPCSensor.hh.
|
protected |
Output topic for salinity.
Definition at line 145 of file CPCSensor.hh.
|
protected |
Salinity unit to be used. Options are.
ppt
(parts per thousand)ppm
(parts per million)psu
(practical salinity unit) Definition at line 84 of file CPCSensor.hh.
|
protected |
Sensor saturation.
Definition at line 87 of file CPCSensor.hh.
|
protected |
Name of the sensor frame.
Definition at line 109 of file CPCSensor.hh.
|
protected |
Radius of the kernel to identify particles that will be taken into account in the concentration computation.
Definition at line 78 of file CPCSensor.hh.
|
protected |
TF buffer instance.
Definition at line 151 of file CPCSensor.hh.
|
protected |
TF listener pointer.
Definition at line 154 of file CPCSensor.hh.
|
protected |
Set to true to avoid particle update.
Definition at line 103 of file CPCSensor.hh.
|
protected |
Output topic's update rate.
Definition at line 106 of file CPCSensor.hh.
|
protected |
Sensor update timer.
Definition at line 166 of file CPCSensor.hh.
|
protected |
Flag to ensure the cloud and measurement update don't coincide.
Definition at line 68 of file CPCSensor.hh.
|
protected |
Flag that will allow storing the geodetic coordinates with the measurement message.
Definition at line 91 of file CPCSensor.hh.
|
protected |
Flag set if the sensor position update must be read from the vehicle's GPS topic.
Definition at line 121 of file CPCSensor.hh.
|
protected |
Flag set if the sensor position update must be read from the vehicle's odometry input topic.
Definition at line 117 of file CPCSensor.hh.
|
protected |
Flag set if the TF update wrt the sensor frame ID.
Definition at line 124 of file CPCSensor.hh.