sensors.hpp
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 #ifndef SRC_SENSORS_SENSORS_HPP_
20 #define SRC_SENSORS_SENSORS_HPP_
21 
22 #include "attitude.hpp"
23 #include "barometer.hpp"
24 #include "battery.hpp"
26 #include "esc_status.hpp"
27 #include "fuel_tank.hpp"
28 #include "gnss.hpp"
29 #include "ice.hpp"
30 #include "imu.hpp"
31 #include "mag.hpp"
32 #include "velocity.hpp"
33 
34 #include "uavDynamicsSimBase.hpp"
36 
37 struct Sensors {
38  explicit Sensors(ros::NodeHandle* nh);
39  int8_t init(const std::shared_ptr<UavDynamicsSimBase>& uavDynamicsSim);
40  void publishStateToCommunicator(uint8_t dynamicsNotation);
41 
51 
55 
56 private:
58  std::shared_ptr<UavDynamicsSimBase> _uavDynamicsSim;
59 };
60 
61 #endif // SRC_SENSORS_SENSORS_HPP_
FuelTankSensor
Definition: fuel_tank.hpp:24
differential_pressure.hpp
Sensors::temperatureSensor
TemperatureSensor temperatureSensor
Definition: sensors.hpp:44
TemperatureSensor
Definition: barometer.hpp:30
battery.hpp
DiffPressureSensor
Definition: differential_pressure.hpp:24
Sensors::escStatusSensor
EscStatusSensor escStatusSensor
Definition: sensors.hpp:52
Sensors::publishStateToCommunicator
void publishStateToCommunicator(uint8_t dynamicsNotation)
Definition: sensors.cpp:95
IceStatusSensor
Definition: ice.hpp:24
mag.hpp
Sensors::magSensor
MagSensor magSensor
Definition: sensors.hpp:50
barometer.hpp
uavDynamicsSimBase.hpp
Sensors::geodeticConverter
CoordinateConverter geodeticConverter
Definition: sensors.hpp:57
geodetic.hpp
VelocitySensor
Definition: velocity.hpp:25
Sensors::attitudeSensor
AttitudeSensor attitudeSensor
Definition: sensors.hpp:42
Sensors::iceStatusSensor
IceStatusSensor iceStatusSensor
Definition: sensors.hpp:46
AttitudeSensor
Definition: attitude.hpp:25
Sensors::gpsSensor
GpsSensor gpsSensor
Definition: sensors.hpp:49
Sensors
Definition: sensors.hpp:37
imu.hpp
Sensors::batteryInfoSensor
BatteryInfoSensor batteryInfoSensor
Definition: sensors.hpp:54
Sensors::diffPressureSensor
DiffPressureSensor diffPressureSensor
Definition: sensors.hpp:45
esc_status.hpp
CoordinateConverter
Definition: geodetic.hpp:20
ice.hpp
velocity.hpp
Sensors::velocitySensor_
VelocitySensor velocitySensor_
Definition: sensors.hpp:48
attitude.hpp
Sensors::fuelTankSensor
FuelTankSensor fuelTankSensor
Definition: sensors.hpp:53
EscStatusSensor
Definition: esc_status.hpp:24
MagSensor
Definition: mag.hpp:25
Sensors::imuSensor
ImuSensor imuSensor
Definition: sensors.hpp:47
PressureSensor
Definition: barometer.hpp:24
ImuSensor
Definition: imu.hpp:25
gnss.hpp
fuel_tank.hpp
Sensors::pressureSensor
PressureSensor pressureSensor
Definition: sensors.hpp:43
Sensors::Sensors
Sensors(ros::NodeHandle *nh)
Definition: sensors.cpp:26
GpsSensor
Definition: gnss.hpp:25
Sensors::_uavDynamicsSim
std::shared_ptr< UavDynamicsSimBase > _uavDynamicsSim
Definition: sensors.hpp:58
BatteryInfoSensor
Definition: battery.hpp:24
ros::NodeHandle
Sensors::init
int8_t init(const std::shared_ptr< UavDynamicsSimBase > &uavDynamicsSim)
Definition: sensors.cpp:42


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35