Removed excess trailing spaces before new lines on licenses.
[betaflight.git] / src / main / flight / mixer.h
blobb028a1b403290b9eb4f8c21176713dcc9bcbd6ab
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #pragma once
23 #include "platform.h"
25 #include "common/time.h"
26 #include "pg/pg.h"
27 #include "drivers/pwm_output_counts.h"
28 #include "drivers/io_types.h"
29 #include "drivers/pwm_output.h"
31 #define QUAD_MOTOR_COUNT 4
32 #define BRUSHED_MOTORS_PWM_RATE 16000
33 #define BRUSHLESS_MOTORS_PWM_RATE 480
35 // Digital protocol has fixed values
36 #define DSHOT_DISARM_COMMAND 0
37 #define DSHOT_MIN_THROTTLE 48
38 #define DSHOT_MAX_THROTTLE 2047
39 #define DSHOT_3D_DEADBAND_LOW 1047
40 #define DSHOT_3D_DEADBAND_HIGH 1048
42 // Note: this is called MultiType/MULTITYPE_* in baseflight.
43 typedef enum mixerMode
45 MIXER_TRI = 1,
46 MIXER_QUADP = 2,
47 MIXER_QUADX = 3,
48 MIXER_BICOPTER = 4,
49 MIXER_GIMBAL = 5,
50 MIXER_Y6 = 6,
51 MIXER_HEX6 = 7,
52 MIXER_FLYING_WING = 8,
53 MIXER_Y4 = 9,
54 MIXER_HEX6X = 10,
55 MIXER_OCTOX8 = 11,
56 MIXER_OCTOFLATP = 12,
57 MIXER_OCTOFLATX = 13,
58 MIXER_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported)
59 MIXER_HELI_120_CCPM = 15,
60 MIXER_HELI_90_DEG = 16,
61 MIXER_VTAIL4 = 17,
62 MIXER_HEX6H = 18,
63 MIXER_PPM_TO_SERVO = 19, // PPM -> servo relay
64 MIXER_DUALCOPTER = 20,
65 MIXER_SINGLECOPTER = 21,
66 MIXER_ATAIL4 = 22,
67 MIXER_CUSTOM = 23,
68 MIXER_CUSTOM_AIRPLANE = 24,
69 MIXER_CUSTOM_TRI = 25,
70 MIXER_QUADX_1234 = 26
71 } mixerMode_e;
73 // Custom mixer data per motor
74 typedef struct motorMixer_s {
75 float throttle;
76 float roll;
77 float pitch;
78 float yaw;
79 } motorMixer_t;
81 PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer);
83 // Custom mixer configuration
84 typedef struct mixer_s {
85 uint8_t motorCount;
86 uint8_t useServo;
87 const motorMixer_t *motor;
88 } mixer_t;
90 typedef struct mixerConfig_s {
91 uint8_t mixerMode;
92 bool yaw_motors_reversed;
93 uint8_t crashflip_motor_percent;
94 } mixerConfig_t;
96 PG_DECLARE(mixerConfig_t, mixerConfig);
98 typedef struct motorConfig_s {
99 motorDevConfig_t dev;
100 uint16_t digitalIdleOffsetValue; // Idle value for DShot protocol, full motor output = 10000
101 uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
102 uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
103 uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
104 } motorConfig_t;
106 PG_DECLARE(motorConfig_t, motorConfig);
108 #define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF
110 extern const mixer_t mixers[];
111 extern float motor[MAX_SUPPORTED_MOTORS];
112 extern float motor_disarmed[MAX_SUPPORTED_MOTORS];
113 extern float motorOutputHigh, motorOutputLow;
114 struct rxConfig_s;
116 uint8_t getMotorCount(void);
117 float getMotorMixRange(void);
118 bool areMotorsRunning(void);
119 bool mixerIsOutputSaturated(int axis, float errorRate);
121 void mixerLoadMix(int index, motorMixer_t *customMixers);
122 void mixerInit(mixerMode_e mixerMode);
124 void mixerConfigureOutput(void);
126 void mixerResetDisarmedMotors(void);
127 void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensation);
128 void syncMotors(bool enabled);
129 void writeMotors(void);
130 void stopMotors(void);
131 void stopPwmAllMotors(void);
133 float convertExternalToMotor(uint16_t externalValue);
134 uint16_t convertMotorToExternal(float motorValue);
135 bool mixerIsTricopter(void);