Go to the documentation of this file.
19 #ifndef SRC_MIXERS_BASE_MIXER_HPP
20 #define SRC_MIXERS_BASE_MIXER_HPP
23 #include <sensor_msgs/Joy.h>
24 #include <std_msgs/Bool.h>
54 virtual int8_t
init();
63 inline static constexpr
char MOTORS_TOPIC[] =
"/uav/actuators_raw";
67 float clamp_float(
float value,
float min,
float max);
70 #endif // SRC_MIXERS_BASE_MIXER_HPP
@ VTOL_OP_ELEVATORS
[-1.0; +1.0]
@ VTOL_MOTOR_0_FRONT_RIGHT
[ 0.0; +1.0]
@ VTOL_AILERONS
[-1.0; +1.0]
@ MC_MOTOR_1_REAR_LEFT
[ 0.0; +1.0]
ros::Subscriber motorsSub
@ VTOL_MOTOR_2_FRONT_LEFT
[ 0.0; +1.0]
@ VTOL_THROTLE
[ 0.0; +1.0]
VtolOctoplaneDynamicsMapping
float rawcommand_to_servo(float value)
@ MC_MOTOR_3_REAR_RIGHT
[ 0.0; +1.0]
@ VTOL_ELEVATORS
[-1.0; +1.0]
@ MC_MOTOR_2_FRONT_LEFT
[ 0.0; +1.0]
@ VTOL_OP_AILERONS
[-1.0; +1.0]
virtual ~BaseReverseMixer()=default
sensor_msgs::Joy sp_to_dynamics
ros::Publisher actuatorsPub
virtual void motorsCallback(sensor_msgs::Joy msg)=0
@ VTOL_MOTOR_3_REAR_RIGHT
[ 0.0; +1.0]
static constexpr char MOTORS_TOPIC[]
@ VTOL_OP_RUDDERS
[-1.0; +1.0]
@ VTOL_MOTOR_1_REAR_LEFT
[ 0.0; +1.0]
@ VTOL_RUDDERS
[-1.0; +1.0]
static constexpr char MAPPED_ACTUATOR_TOPIC[]
float clamp_float(float value, float min, float max)
static constexpr char SERVOS_TOPIC[]
@ MC_MOTOR_0_FRONT_RIGHT
[ 0.0; +1.0]
BaseReverseMixer(const ros::NodeHandle &nh)
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35