src
sensors
fuel_tank.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 "
fuel_tank.hpp
"
20
#include <std_msgs/UInt8.h>
21
22
FuelTankSensor::FuelTankSensor
(
ros::NodeHandle
* nh,
const
char
* topic,
double
period) :
BaseSensor
(nh, period){
23
publisher_
=
node_handler_
->
advertise
<std_msgs::UInt8>(topic, 5);
24
}
25
bool
FuelTankSensor::publish
(
double
fuelLevelPercentage) {
26
auto
crntTimeSec =
ros::Time::now
().
toSec
();
27
if
(
_isEnabled
&& (
nextPubTimeSec_
< crntTimeSec)){
28
std_msgs::UInt8 fuelTankMsg;
29
fuelTankMsg.data =
static_cast<
uint8_t
>
(fuelLevelPercentage);
30
publisher_
.
publish
(fuelTankMsg);
31
nextPubTimeSec_
= crntTimeSec +
PERIOD
;
32
}
33
return
true
;
34
}
BaseSensor::_isEnabled
bool _isEnabled
Definition:
sensor_base.hpp:33
TimeBase< Time, Duration >::toSec
double toSec() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
BaseSensor::publisher_
ros::Publisher publisher_
Definition:
sensor_base.hpp:35
FuelTankSensor::publish
bool publish(double rpm)
Definition:
fuel_tank.cpp:25
FuelTankSensor::FuelTankSensor
FuelTankSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition:
fuel_tank.cpp:22
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition:
sensor_base.hpp:36
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
fuel_tank.hpp
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