src
mixers
mixer_babyshark.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_babyshark.hpp
"
20
21
enum
BABY_SHARK_OUTPUTS
{
22
BABY_SHARK_AILERONS
= 0,
23
BABY_SHARK_A_TAIL_LEFT
,
24
BABY_SHARK_PUSHER_MOTOR
,
25
BABY_SHARK_A_TAIL_RIGHT
,
26
BABY_SHARK_MOTOR_0
,
27
BABY_SHARK_MOTOR_1
,
28
BABY_SHARK_MOTOR_2
,
29
BABY_SHARK_MOTOR_3
,
30
};
31
32
enum
ACTUATORS_OUTPUT
{
33
MC_MOTOR_0
= 0,
34
MC_MOTOR_1
,
35
MC_MOTOR_2
,
36
MC_MOTOR_3
,
37
VTOL_ROLL
,
38
VTOL_PITCH
,
39
VTOL_YAW
,
40
VTOL_THROTTLE
,
41
};
42
43
BabysharkReverseMixer::BabysharkReverseMixer
(
const
ros::NodeHandle
& nh) :
BaseReverseMixer
(nh) {
44
for
(
size_t
channel = 0; channel < 8; channel++) {
45
sp_to_dynamics
.axes.push_back(0);
46
}
47
}
48
49
void
BabysharkReverseMixer::motorsCallback
(sensor_msgs::Joy msg) {
50
if
(msg.axes.size() == 8) {
51
sp_to_dynamics
.header = msg.header;
52
53
sp_to_dynamics
.axes[
MC_MOTOR_0
] = msg.axes[
BABY_SHARK_MOTOR_0
];
54
sp_to_dynamics
.axes[
MC_MOTOR_1
] = msg.axes[
BABY_SHARK_MOTOR_1
];
55
sp_to_dynamics
.axes[
MC_MOTOR_2
] = msg.axes[
BABY_SHARK_MOTOR_2
];
56
sp_to_dynamics
.axes[
MC_MOTOR_3
] = msg.axes[
BABY_SHARK_MOTOR_3
];
57
58
float
roll = msg.axes[
BABY_SHARK_AILERONS
];
59
roll = (roll < 0) ? 0.5 : 1 - roll;
60
sp_to_dynamics
.axes[
VTOL_ROLL
] = roll;
61
62
float
pitch = -msg.axes[
BABY_SHARK_A_TAIL_LEFT
] + msg.axes[
BABY_SHARK_A_TAIL_RIGHT
];
63
pitch = (pitch < 0) ? 0.0
f
: pitch / 0.8
f
;
64
sp_to_dynamics
.axes[
VTOL_PITCH
] = pitch;
65
66
float
yaw = msg.axes[
BABY_SHARK_A_TAIL_LEFT
] + msg.axes[
BABY_SHARK_A_TAIL_RIGHT
];
67
yaw = (yaw < 0) ? 0.0
f
: (1.0
f
- yaw) / 0.7f;
68
sp_to_dynamics
.axes[
VTOL_YAW
] = yaw;
69
70
sp_to_dynamics
.axes[
VTOL_THROTTLE
] = msg.axes[
BABY_SHARK_PUSHER_MOTOR
];
71
actuatorsPub
.
publish
(
sp_to_dynamics
);
72
}
73
}
BaseReverseMixer
Definition:
base_mixer.hpp:50
VTOL_YAW
@ VTOL_YAW
Definition:
mixer_babyshark.cpp:39
VTOL_PITCH
@ VTOL_PITCH
Definition:
mixer_babyshark.cpp:38
BABY_SHARK_PUSHER_MOTOR
@ BABY_SHARK_PUSHER_MOTOR
Definition:
mixer_babyshark.cpp:24
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
BABY_SHARK_AILERONS
@ BABY_SHARK_AILERONS
Definition:
mixer_babyshark.cpp:22
BABY_SHARK_MOTOR_2
@ BABY_SHARK_MOTOR_2
Definition:
mixer_babyshark.cpp:28
mixer_babyshark.hpp
BabysharkReverseMixer::motorsCallback
void motorsCallback(sensor_msgs::Joy msg) override
Definition:
mixer_babyshark.cpp:49
MC_MOTOR_1
@ MC_MOTOR_1
Definition:
mixer_babyshark.cpp:34
BABY_SHARK_MOTOR_0
@ BABY_SHARK_MOTOR_0
Definition:
mixer_babyshark.cpp:26
BaseReverseMixer::sp_to_dynamics
sensor_msgs::Joy sp_to_dynamics
Definition:
base_mixer.hpp:58
BABY_SHARK_MOTOR_3
@ BABY_SHARK_MOTOR_3
Definition:
mixer_babyshark.cpp:29
BaseReverseMixer::actuatorsPub
ros::Publisher actuatorsPub
Definition:
base_mixer.hpp:57
VTOL_ROLL
@ VTOL_ROLL
Definition:
mixer_babyshark.cpp:37
MC_MOTOR_3
@ MC_MOTOR_3
Definition:
mixer_babyshark.cpp:36
BABY_SHARK_A_TAIL_LEFT
@ BABY_SHARK_A_TAIL_LEFT
Definition:
mixer_babyshark.cpp:23
MC_MOTOR_2
@ MC_MOTOR_2
Definition:
mixer_babyshark.cpp:35
BABY_SHARK_MOTOR_1
@ BABY_SHARK_MOTOR_1
Definition:
mixer_babyshark.cpp:27
BabysharkReverseMixer::BabysharkReverseMixer
BabysharkReverseMixer(const ros::NodeHandle &nh)
Definition:
mixer_babyshark.cpp:43
MC_MOTOR_0
@ MC_MOTOR_0
Definition:
mixer_babyshark.cpp:33
BABY_SHARK_A_TAIL_RIGHT
@ BABY_SHARK_A_TAIL_RIGHT
Definition:
mixer_babyshark.cpp:25
BABY_SHARK_OUTPUTS
BABY_SHARK_OUTPUTS
Definition:
mixer_babyshark.cpp:21
f
static const double f
Definition:
geodetic.cpp:22
ACTUATORS_OUTPUT
ACTUATORS_OUTPUT
Definition:
mixer_babyshark.cpp:32
ros::NodeHandle
VTOL_THROTTLE
@ VTOL_THROTTLE
Definition:
mixer_babyshark.cpp:40
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35