src
mixers
base_mixer.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 "
base_mixer.hpp
"
20
21
int8_t
BaseReverseMixer::init
() {
22
actuatorsPub
=
_node
.
advertise
<sensor_msgs::Joy>(
MAPPED_ACTUATOR_TOPIC
, 5);
23
motorsSub
=
_node
.
subscribe
(
MOTORS_TOPIC
, 2, &
BaseReverseMixer::motorsCallback
,
this
);
24
return
0;
25
}
26
27
float
clamp_float
(
float
value,
float
min,
float
max) {
28
if
(value < min) {
29
value = min;
30
}
else
if
(value > max) {
31
value = max;
32
}
33
return
value;
34
}
35
36
float
rawcommand_to_servo
(
float
value) {
37
return
2.0 *
clamp_float
(value, 0.0, 1.0) - 1.0;
38
}
BaseReverseMixer::_node
ros::NodeHandle _node
Definition:
base_mixer.hpp:59
BaseReverseMixer::motorsSub
ros::Subscriber motorsSub
Definition:
base_mixer.hpp:60
base_mixer.hpp
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
clamp_float
float clamp_float(float value, float min, float max)
Definition:
base_mixer.cpp:27
BaseReverseMixer::init
virtual int8_t init()
Definition:
base_mixer.cpp:21
rawcommand_to_servo
float rawcommand_to_servo(float value)
Definition:
base_mixer.cpp:36
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
BaseReverseMixer::actuatorsPub
ros::Publisher actuatorsPub
Definition:
base_mixer.hpp:57
BaseReverseMixer::motorsCallback
virtual void motorsCallback(sensor_msgs::Joy msg)=0
BaseReverseMixer::MOTORS_TOPIC
static constexpr char MOTORS_TOPIC[]
Definition:
base_mixer.hpp:63
BaseReverseMixer::MAPPED_ACTUATOR_TOPIC
static constexpr char MAPPED_ACTUATOR_TOPIC[]
Definition:
base_mixer.hpp:62
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35