src
sensors
differential_pressure.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2020-2023 RaccoonLab.
3
*
4
* This program is free software: you can redistribute it and/or modify
5
* it under the terms of the GNU General Public License as published by
6
* the Free Software Foundation, version 3.
7
*
8
* This program is distributed in the hope that it will be useful, but
9
* WITHOUT ANY WARRANTY; without even the implied warranty of
10
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11
* General Public License for more details.
12
*
13
* You should have received a copy of the GNU General Public License
14
* along with this program. If not, see <http://www.gnu.org/licenses/>.
15
*
16
* Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17
*/
18
19
#include "
differential_pressure.hpp
"
20
#include <std_msgs/Float32.h>
21
22
static
const
double
STATIC_PRESSURE_NOISE
= 0.5;
23
24
DiffPressureSensor::DiffPressureSensor
(
ros::NodeHandle
* nh,
const
char
* topic,
double
period) :
BaseSensor
(nh, period){
25
publisher_
=
node_handler_
->
advertise
<std_msgs::Float32>(topic, 5);
26
}
27
bool
DiffPressureSensor::publish
(
float
diffPressureHpa) {
28
auto
crntTimeSec =
ros::Time::now
().
toSec
();
29
if
(!
_isEnabled
|| (
nextPubTimeSec_
> crntTimeSec)){
30
return
false
;
31
}
32
33
std_msgs::Float32 msg;
34
msg.data = diffPressureHpa * 100;
35
msg.data +=
static_cast<
float
>
(
STATIC_PRESSURE_NOISE
*
normalDistribution_
(
randomGenerator_
));
36
publisher_
.
publish
(msg);
37
38
nextPubTimeSec_
= crntTimeSec +
PERIOD
;
39
return
true
;
40
}
BaseSensor::normalDistribution_
std::normal_distribution< double > normalDistribution_
Definition:
sensor_base.hpp:39
differential_pressure.hpp
BaseSensor::_isEnabled
bool _isEnabled
Definition:
sensor_base.hpp:33
TimeBase< Time, Duration >::toSec
double toSec() const
STATIC_PRESSURE_NOISE
static const double STATIC_PRESSURE_NOISE
Definition:
differential_pressure.cpp:22
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
BaseSensor::randomGenerator_
std::default_random_engine randomGenerator_
Definition:
sensor_base.hpp:38
BaseSensor::publisher_
ros::Publisher publisher_
Definition:
sensor_base.hpp:35
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition:
sensor_base.hpp:36
DiffPressureSensor::DiffPressureSensor
DiffPressureSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition:
differential_pressure.cpp:24
DiffPressureSensor::publish
bool publish(float diffPressureHpa)
Definition:
differential_pressure.cpp:27
BaseSensor::PERIOD
const double PERIOD
Definition:
sensor_base.hpp:34
BaseSensor
Definition:
sensor_base.hpp:25
BaseSensor::node_handler_
ros::NodeHandle * node_handler_
Definition:
sensor_base.hpp:32
ros::NodeHandle
ros::Time::now
static Time now()
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35