CPCSensor.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #pragma once
17 
18 #include <ros/ros.h>
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>
32 #include <memory>
33 #include <string>
34 #include <chrono>
35 #include <random>
36 
38 {
39 
40 #define CONCENTRATION_UNIT_PPT "ppt"
41 #define CONCENTRATION_UNIT_PPM "ppm"
42 #define CONCENTRATION_UNIT_PSU "psu"
43 
44 class CPCSensor
45 {
47  public: CPCSensor();
48 
50  public: ~CPCSensor();
51 
53  protected: void OnSensorUpdate(const ros::TimerEvent&);
54 
56  protected: void OnPlumeParticlesUpdate(
57  const sensor_msgs::PointCloud::ConstPtr &_msg);
58 
60  protected: void OnOdometryUpdate(
61  const nav_msgs::Odometry::ConstPtr &_msg);
62 
64  protected: void OnGPSUpdate(
65  const sensor_msgs::NavSatFix::ConstPtr &_msg);
66 
68  protected: bool updatingCloud;
69 
71  protected: double gamma;
72 
74  protected: double gain;
75 
78  protected: double smoothingLength;
79 
84  protected: std::string salinityUnit;
85 
87  protected: double saturation;
88 
91  protected: bool useGeoCoordinates;
92 
94  protected: bool publishSalinity;
95 
97  protected: double referenceSalinityValue;
98 
100  protected: double plumeSalinityValue;
101 
103  protected: bool updateMeasurement;
104 
106  protected: double updateRate;
107 
109  protected: std::string sensorFrameID;
110 
113  protected: bool areParticlesInit;
114 
117  protected: bool useOdom;
118 
121  protected: bool useGPS;
122 
124  protected: bool useTFUpdate;
125 
127  protected: geometry_msgs::Vector3 cartPos;
128 
130  protected: geographic_msgs::GeoPoint geoPos;
131 
134 
137 
140 
143 
146 
148  protected: std::shared_ptr<ros::NodeHandle> nodeHandle;
149 
152 
154  protected: std::shared_ptr<tf2_ros::TransformListener> tfListener;
155 
157  protected: GeographicLib::LocalCartesian projection;
158 
160  protected: uuv_plume_msgs::ParticleConcentration concentrationMsg;
161 
163  protected: uuv_plume_msgs::Salinity salinityMsg;
164 
167 
169  protected: std::default_random_engine rndGen;
170 
172  protected: std::normal_distribution<double> noiseModel;
173 
175  protected: double noiseAmp;
176 
178  protected: double noiseSigma;
179 };
180 }
ros::Subscriber odometrySub
Subscriber for odometry topic.
Definition: CPCSensor.hh:136
ros::Subscriber particlesSub
Subscriber for the plume particle point cloud.
Definition: CPCSensor.hh:133
double updateRate
Output topic&#39;s update rate.
Definition: CPCSensor.hh:106
uuv_plume_msgs::ParticleConcentration concentrationMsg
Plume concentration message.
Definition: CPCSensor.hh:160
bool useTFUpdate
Flag set if the TF update wrt the sensor frame ID.
Definition: CPCSensor.hh:124
bool publishSalinity
Flag to activate publishing the simulated salinity.
Definition: CPCSensor.hh:94
~CPCSensor()
Class destructor.
Definition: CPCSensor.cc:187
bool areParticlesInit
Flag set to true after the first set of plume particles is received.
Definition: CPCSensor.hh:113
std::normal_distribution< double > noiseModel
Normal distribution describing the noise model.
Definition: CPCSensor.hh:172
geographic_msgs::GeoPoint geoPos
Measured geodetic position.
Definition: CPCSensor.hh:130
ros::Subscriber gpsSub
Subscriber to the GPS update topic.
Definition: CPCSensor.hh:139
double gamma
Gamma velocity parameter for the smoothing function.
Definition: CPCSensor.hh:71
double gain
Sensor gain.
Definition: CPCSensor.hh:74
bool useGPS
Flag set if the sensor position update must be read from the vehicle&#39;s GPS topic. ...
Definition: CPCSensor.hh:121
void OnSensorUpdate(const ros::TimerEvent &)
Update the output concentration and salinity topics.
Definition: CPCSensor.cc:348
ros::Timer updateTimer
Sensor update timer.
Definition: CPCSensor.hh:166
double smoothingLength
Radius of the kernel to identify particles that will be taken into account in the concentration compu...
Definition: CPCSensor.hh:78
double noiseSigma
Noise standard deviation.
Definition: CPCSensor.hh:178
ros::Publisher concentrationPub
Output topic for particle concentration.
Definition: CPCSensor.hh:142
double referenceSalinityValue
Default salinity value for the fluid e.g. sea water.
Definition: CPCSensor.hh:97
double saturation
Sensor saturation.
Definition: CPCSensor.hh:87
ros::Publisher salinityPub
Output topic for salinity.
Definition: CPCSensor.hh:145
std::default_random_engine rndGen
Pseudo random number generator.
Definition: CPCSensor.hh:169
GeographicLib::LocalCartesian projection
Local Cartesian projection.
Definition: CPCSensor.hh:157
uuv_plume_msgs::Salinity salinityMsg
Salinity message.
Definition: CPCSensor.hh:163
bool useGeoCoordinates
Flag that will allow storing the geodetic coordinates with the measurement message.
Definition: CPCSensor.hh:91
std::shared_ptr< ros::NodeHandle > nodeHandle
ROS node handle.
Definition: CPCSensor.hh:148
std::string sensorFrameID
Name of the sensor frame.
Definition: CPCSensor.hh:109
double plumeSalinityValue
Default salinity value for the plume.
Definition: CPCSensor.hh:100
void OnGPSUpdate(const sensor_msgs::NavSatFix::ConstPtr &_msg)
Update the GPS update callback.
Definition: CPCSensor.cc:330
bool updateMeasurement
Set to true to avoid particle update.
Definition: CPCSensor.hh:103
tf2_ros::Buffer tfBuffer
TF buffer instance.
Definition: CPCSensor.hh:151
std::string salinityUnit
Salinity unit to be used. Options are.
Definition: CPCSensor.hh:84
void OnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr &_msg)
Update callback from the plume particles.
Definition: CPCSensor.cc:193
std::shared_ptr< tf2_ros::TransformListener > tfListener
TF listener pointer.
Definition: CPCSensor.hh:154
void OnOdometryUpdate(const nav_msgs::Odometry::ConstPtr &_msg)
Update the odometry callback.
Definition: CPCSensor.cc:316
bool updatingCloud
Flag to ensure the cloud and measurement update don&#39;t coincide.
Definition: CPCSensor.hh:68
geometry_msgs::Vector3 cartPos
Measured Cartesian position.
Definition: CPCSensor.hh:127
bool useOdom
Flag set if the sensor position update must be read from the vehicle&#39;s odometry input topic...
Definition: CPCSensor.hh:117
CPCSensor()
Class constructor.
Definition: CPCSensor.cc:21
double noiseAmp
Noise amplitude.
Definition: CPCSensor.hh:175


uuv_cpc_sensor
Author(s): Musa Morena Marcusso Manhaes
autogenerated on Mon Jun 10 2019 15:41:26