src
actuators.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_ACTUATORS_HPP
20
#define SRC_ACTUATORS_HPP
21
22
#include <
ros/ros.h
>
23
#include <sensor_msgs/Joy.h>
24
#include <std_msgs/Bool.h>
25
26
27
enum class
ArmingStatus
{
28
UNKNOWN
,
// Vehicle without Arming status is assumed to be always armed
29
ARMED
,
30
DISARMED
,
31
};
32
33
struct
Actuators
{
34
Actuators
() :
actuators
(16, 0.0) {}
35
void
init
(
ros::NodeHandle
& node);
36
void
retriveStats
(uint64_t* msg_counter, uint64_t* max_delay_us);
37
ArmingStatus
getArmingStatus
();
38
39
std::vector<double>
actuators
;
40
uint8_t
actuatorsSize
{0};
41
uint8_t
_scenarioType
{0};
42
43
private
:
44
void
_actuatorsCallback
(sensor_msgs::Joy::Ptr msg);
45
void
_armCallback
(std_msgs::Bool msg);
46
47
ros::Subscriber
_actuatorsSub
;
48
ros::Subscriber
_armSub
;
49
uint64_t
_lastActuatorsTimestampUsec
;
50
51
uint64_t
_maxDelayUsec
{0};
52
uint64_t
_msgCounter
{0};
53
54
ArmingStatus
_armingStatus
{
ArmingStatus::DISARMED
};
55
double
_lastArmingStatusTimestampSec
{
ros::Time::now
().
toSec
()};
56
};
57
58
#endif // SRC_ACTUATORS_HPP
Actuators::getArmingStatus
ArmingStatus getArmingStatus()
Definition:
actuators.cpp:34
ArmingStatus::DISARMED
@ DISARMED
Actuators::_armingStatus
ArmingStatus _armingStatus
Definition:
actuators.hpp:54
ros.h
ArmingStatus::ARMED
@ ARMED
Actuators::_armCallback
void _armCallback(std_msgs::Bool msg)
Definition:
actuators.cpp:63
TimeBase< Time, Duration >::toSec
double toSec() const
Actuators::_msgCounter
uint64_t _msgCounter
Definition:
actuators.hpp:52
Actuators
Definition:
actuators.hpp:33
Actuators::_maxDelayUsec
uint64_t _maxDelayUsec
Definition:
actuators.hpp:51
Actuators::init
void init(ros::NodeHandle &node)
Definition:
actuators.cpp:21
Actuators::_scenarioType
uint8_t _scenarioType
Definition:
actuators.hpp:41
ArmingStatus
ArmingStatus
Definition:
actuators.hpp:27
Actuators::retriveStats
void retriveStats(uint64_t *msg_counter, uint64_t *max_delay_us)
Definition:
actuators.cpp:26
Actuators::actuatorsSize
uint8_t actuatorsSize
Definition:
actuators.hpp:40
Actuators::_armSub
ros::Subscriber _armSub
Definition:
actuators.hpp:48
Actuators::_actuatorsCallback
void _actuatorsCallback(sensor_msgs::Joy::Ptr msg)
Definition:
actuators.cpp:43
Actuators::_lastActuatorsTimestampUsec
uint64_t _lastActuatorsTimestampUsec
Definition:
actuators.hpp:49
Actuators::actuators
std::vector< double > actuators
Definition:
actuators.hpp:39
Actuators::_lastArmingStatusTimestampSec
double _lastArmingStatusTimestampSec
Definition:
actuators.hpp:55
ArmingStatus::UNKNOWN
@ UNKNOWN
Actuators::_actuatorsSub
ros::Subscriber _actuatorsSub
Definition:
actuators.hpp:47
Actuators::Actuators
Actuators()
Definition:
actuators.hpp:34
ros::NodeHandle
ros::Subscriber
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