src
scenarios.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (c) 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 "
scenarios.hpp
"
20
21
void
ScenarioManager::init
() {
22
_scenarioSub
=
_node
.
subscribe
(
"/uav/scenario"
, 1, &
ScenarioManager::scenarioCallback
,
this
);
23
}
24
25
void
ScenarioManager::scenarioCallback
(std_msgs::UInt8 msg){
26
Scenario
scenarioType =
static_cast<
Scenario
>
(msg.data);
27
28
switch
(scenarioType) {
29
case
Scenario::BARO_DISABLE
:
30
_sensors
.
pressureSensor
.
disable
();
31
break
;
32
case
Scenario::BARO_ENABLE
:
33
_sensors
.
pressureSensor
.
enable
();
34
break
;
35
36
case
Scenario::DIFFERENTIAL_PRESSURE_DISABLE
:
37
_sensors
.
diffPressureSensor
.
disable
();
38
break
;
39
case
Scenario::DIFFERENTIAL_PRESSURE_ENABLE
:
40
_sensors
.
diffPressureSensor
.
enable
();
41
break
;
42
43
case
Scenario::ICE_STOP_STALL_EMULATION
:
44
_actuators
.
_scenarioType
= msg.data;
45
_sensors
.
iceStatusSensor
.
stop_stall_emulation
();
46
break
;
47
case
Scenario::ICE_START_STALL_EMULATION
:
48
_actuators
.
_scenarioType
= msg.data;
49
_sensors
.
iceStatusSensor
.
start_stall_emulation
();
50
break
;
51
52
case
Scenario::GNSS_DISABLE
:
53
_sensors
.
gpsSensor
.
disable
();
54
break
;
55
case
Scenario::GNSS_ENABLE
:
56
_sensors
.
gpsSensor
.
enable
();
57
break
;
58
59
case
Scenario::MAG_DISABLE
:
60
_sensors
.
magSensor
.
disable
();
61
break
;
62
case
Scenario::MAG_ENABLE
:
63
_sensors
.
magSensor
.
enable
();
64
break
;
65
66
default
:
67
break
;
68
}
69
}
Sensors::magSensor
MagSensor magSensor
Definition:
sensors.hpp:49
BaseSensor::enable
void enable()
Definition:
sensor_base.hpp:30
Sensors::gpsSensor
GpsSensor gpsSensor
Definition:
sensors.hpp:48
Scenario::BARO_DISABLE
IceStatusSensor::start_stall_emulation
void start_stall_emulation()
Definition:
ice.cpp:93
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Scenario::DIFFERENTIAL_PRESSURE_DISABLE
Scenario::MAG_DISABLE
Sensors::iceStatusSensor
IceStatusSensor iceStatusSensor
Definition:
sensors.hpp:45
ScenarioManager::init
void init()
Definition:
scenarios.cpp:21
BaseSensor::disable
void disable()
Definition:
sensor_base.hpp:31
Scenario::GNSS_DISABLE
ScenarioManager::scenarioCallback
void scenarioCallback(std_msgs::UInt8 msg)
Definition:
scenarios.cpp:25
Scenario::BARO_ENABLE
Scenario::ICE_START_STALL_EMULATION
ScenarioManager::_scenarioSub
ros::Subscriber _scenarioSub
Definition:
scenarios.hpp:49
Scenario::ICE_STOP_STALL_EMULATION
Scenario::GNSS_ENABLE
ScenarioManager::_actuators
Actuators & _actuators
Definition:
scenarios.hpp:51
Sensors::diffPressureSensor
DiffPressureSensor diffPressureSensor
Definition:
sensors.hpp:44
scenarios.hpp
Scenario::MAG_ENABLE
Sensors::pressureSensor
PressureSensor pressureSensor
Definition:
sensors.hpp:42
Actuators::_scenarioType
uint8_t _scenarioType
Definition:
actuators.hpp:41
Scenario::DIFFERENTIAL_PRESSURE_ENABLE
IceStatusSensor::stop_stall_emulation
void stop_stall_emulation()
Definition:
ice.cpp:97
ScenarioManager::_sensors
Sensors & _sensors
Definition:
scenarios.hpp:52
Scenario
Scenario
Definition:
scenarios.hpp:27
ScenarioManager::_node
ros::NodeHandle & _node
Definition:
scenarios.hpp:50
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Sat Jul 1 2023 02:13:44