barometer.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 "barometer.hpp"
20 #include <std_msgs/Float32.h>
21 
22 static const float STATIC_PRESSURE_NOISE = 0.1f;
23 static const float TEMPERATURE_NOISE = 0.1f;
24 
25 PressureSensor::PressureSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
26  publisher_ = node_handler_->advertise<std_msgs::Float32>(topic, 5);
27 }
28 bool PressureSensor::publish(float staticPressureHpa) {
29  auto crntTimeSec = ros::Time::now().toSec();
30  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
31  return false;
32  }
33 
34  std_msgs::Float32 msg;
35  msg.data = staticPressureHpa * 100;
36  msg.data += STATIC_PRESSURE_NOISE * static_cast<float>(normalDistribution_(randomGenerator_));
37  publisher_.publish(msg);
38 
39  nextPubTimeSec_ = crntTimeSec + PERIOD;
40  return true;
41 }
42 
43 TemperatureSensor::TemperatureSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
44  publisher_ = node_handler_->advertise<std_msgs::Float32>(topic, 5);
45 }
46 bool TemperatureSensor::publish(float staticTemperature) {
47  auto crntTimeSec = ros::Time::now().toSec();
48  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
49  return false;
50  }
51 
52  std_msgs::Float32 msg;
53  msg.data = staticTemperature + 5;
54  msg.data += TEMPERATURE_NOISE * static_cast<float>(normalDistribution_(randomGenerator_));
55  publisher_.publish(msg);
56 
57  nextPubTimeSec_ = crntTimeSec + PERIOD;
58  return true;
59 }
BaseSensor::normalDistribution_
std::normal_distribution< double > normalDistribution_
Definition: sensor_base.hpp:39
PressureSensor::publish
bool publish(float staticPressureHpa)
Definition: barometer.cpp:28
TemperatureSensor::publish
bool publish(float staticTemperature)
Definition: barometer.cpp:46
PressureSensor::PressureSensor
PressureSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: barometer.cpp:25
BaseSensor::_isEnabled
bool _isEnabled
Definition: sensor_base.hpp:33
TimeBase< Time, Duration >::toSec
double toSec() const
STATIC_PRESSURE_NOISE
static const float STATIC_PRESSURE_NOISE
Definition: barometer.cpp:22
TemperatureSensor::TemperatureSensor
TemperatureSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: barometer.cpp:43
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
barometer.hpp
BaseSensor::publisher_
ros::Publisher publisher_
Definition: sensor_base.hpp:35
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition: sensor_base.hpp:36
TEMPERATURE_NOISE
static const float TEMPERATURE_NOISE
Definition: barometer.cpp:23
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