src
mixers
mixer_direct.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2023 Dmitry Ponomarev <ponomarevda96@gmail.com>
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 "
mixer_direct.hpp
"
20
21
void
DirectMixer::motorsCallback
(sensor_msgs::Joy msg) {
22
if
(msg.axes.size() < 4) {
23
return
;
24
}
25
26
auto
channels_amount = std::min(
MAX_CHANNELS
, (uint8_t)msg.axes.size());
27
for
(uint8_t idx = 0; idx < channels_amount; idx++) {
28
sp_to_dynamics
.axes[idx] = msg.axes[idx];
29
}
30
31
sp_to_dynamics
.header = msg.header;
32
actuatorsPub
.
publish
(
sp_to_dynamics
);
33
}
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
mixer_direct.hpp
BaseReverseMixer::sp_to_dynamics
sensor_msgs::Joy sp_to_dynamics
Definition:
base_mixer.hpp:58
DirectMixer::MAX_CHANNELS
static constexpr uint8_t MAX_CHANNELS
Definition:
mixer_direct.hpp:34
BaseReverseMixer::actuatorsPub
ros::Publisher actuatorsPub
Definition:
base_mixer.hpp:57
DirectMixer::motorsCallback
void motorsCallback(sensor_msgs::Joy msg) override
Definition:
mixer_direct.cpp:21
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35