base_mixer.hpp
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 #ifndef SRC_MIXERS_BASE_MIXER_HPP
20 #define SRC_MIXERS_BASE_MIXER_HPP
21 
22 #include <ros/ros.h>
23 #include <sensor_msgs/Joy.h>
24 #include <std_msgs/Bool.h>
25 
31 };
32 
42 };
43 
48 };
49 
51  public:
52  explicit BaseReverseMixer(const ros::NodeHandle& nh): _node(nh) {}
53  virtual ~BaseReverseMixer() = default;
54  virtual int8_t init();
55  virtual void motorsCallback(sensor_msgs::Joy msg) = 0;
56 
58  sensor_msgs::Joy sp_to_dynamics;
61 
62  inline static constexpr char MAPPED_ACTUATOR_TOPIC[] = "/uav/actuators";
63  inline static constexpr char MOTORS_TOPIC[] = "/uav/actuators_raw";
64  inline static constexpr char SERVOS_TOPIC[] = "/uav/servo";
65 };
66 
67 float clamp_float(float value, float min, float max);
68 float rawcommand_to_servo(float value);
69 
70 #endif // SRC_MIXERS_BASE_MIXER_HPP
VTOL_OP_ELEVATORS
@ VTOL_OP_ELEVATORS
[-1.0; +1.0]
Definition: base_mixer.hpp:46
BaseReverseMixer::_node
ros::NodeHandle _node
Definition: base_mixer.hpp:59
VTOL_MOTOR_0_FRONT_RIGHT
@ VTOL_MOTOR_0_FRONT_RIGHT
[ 0.0; +1.0]
Definition: base_mixer.hpp:34
VTOL_AILERONS
@ VTOL_AILERONS
[-1.0; +1.0]
Definition: base_mixer.hpp:39
MC_MOTOR_1_REAR_LEFT
@ MC_MOTOR_1_REAR_LEFT
[ 0.0; +1.0]
Definition: base_mixer.hpp:28
BaseReverseMixer
Definition: base_mixer.hpp:50
ros::Publisher
BaseReverseMixer::motorsSub
ros::Subscriber motorsSub
Definition: base_mixer.hpp:60
ros.h
VTOL_MOTOR_2_FRONT_LEFT
@ VTOL_MOTOR_2_FRONT_LEFT
[ 0.0; +1.0]
Definition: base_mixer.hpp:36
VTOL_THROTLE
@ VTOL_THROTLE
[ 0.0; +1.0]
Definition: base_mixer.hpp:38
VtolOctoplaneDynamicsMapping
VtolOctoplaneDynamicsMapping
Definition: base_mixer.hpp:44
rawcommand_to_servo
float rawcommand_to_servo(float value)
Definition: base_mixer.cpp:36
MC_MOTOR_3_REAR_RIGHT
@ MC_MOTOR_3_REAR_RIGHT
[ 0.0; +1.0]
Definition: base_mixer.hpp:30
VTOL_ELEVATORS
@ VTOL_ELEVATORS
[-1.0; +1.0]
Definition: base_mixer.hpp:40
MC_MOTOR_2_FRONT_LEFT
@ MC_MOTOR_2_FRONT_LEFT
[ 0.0; +1.0]
Definition: base_mixer.hpp:29
VTOL_OP_AILERONS
@ VTOL_OP_AILERONS
[-1.0; +1.0]
Definition: base_mixer.hpp:45
BaseReverseMixer::init
virtual int8_t init()
Definition: base_mixer.cpp:21
MulticopterMapping
MulticopterMapping
Definition: base_mixer.hpp:26
BaseReverseMixer::~BaseReverseMixer
virtual ~BaseReverseMixer()=default
BaseReverseMixer::sp_to_dynamics
sensor_msgs::Joy sp_to_dynamics
Definition: base_mixer.hpp:58
VtolDynamicsMapping
VtolDynamicsMapping
Definition: base_mixer.hpp:33
BaseReverseMixer::actuatorsPub
ros::Publisher actuatorsPub
Definition: base_mixer.hpp:57
BaseReverseMixer::motorsCallback
virtual void motorsCallback(sensor_msgs::Joy msg)=0
VTOL_MOTOR_3_REAR_RIGHT
@ VTOL_MOTOR_3_REAR_RIGHT
[ 0.0; +1.0]
Definition: base_mixer.hpp:37
BaseReverseMixer::MOTORS_TOPIC
static constexpr char MOTORS_TOPIC[]
Definition: base_mixer.hpp:63
VTOL_OP_RUDDERS
@ VTOL_OP_RUDDERS
[-1.0; +1.0]
Definition: base_mixer.hpp:47
VTOL_MOTOR_1_REAR_LEFT
@ VTOL_MOTOR_1_REAR_LEFT
[ 0.0; +1.0]
Definition: base_mixer.hpp:35
VTOL_RUDDERS
@ VTOL_RUDDERS
[-1.0; +1.0]
Definition: base_mixer.hpp:41
BaseReverseMixer::MAPPED_ACTUATOR_TOPIC
static constexpr char MAPPED_ACTUATOR_TOPIC[]
Definition: base_mixer.hpp:62
clamp_float
float clamp_float(float value, float min, float max)
Definition: base_mixer.cpp:27
BaseReverseMixer::SERVOS_TOPIC
static constexpr char SERVOS_TOPIC[]
Definition: base_mixer.hpp:64
MC_MOTOR_0_FRONT_RIGHT
@ MC_MOTOR_0_FRONT_RIGHT
[ 0.0; +1.0]
Definition: base_mixer.hpp:27
BaseReverseMixer::BaseReverseMixer
BaseReverseMixer(const ros::NodeHandle &nh)
Definition: base_mixer.hpp:52
ros::NodeHandle
ros::Subscriber


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35