Merge pull request #9335 from iNavFlight/MrD_Add-odometer-to-OSD
[inav.git] / src / main / flight / mixer.h
blob9ee6a20654e76f468a17a7495cd56855e0744acd
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight 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, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include "config/parameter_group.h"
22 #include "drivers/timer.h"
24 #if defined(TARGET_MOTOR_COUNT)
25 #define MAX_SUPPORTED_MOTORS TARGET_MOTOR_COUNT
26 #else
27 #define MAX_SUPPORTED_MOTORS 12
28 #endif
30 // Digital protocol has fixed values
31 #define DSHOT_DISARM_COMMAND 0
32 #define DSHOT_MIN_THROTTLE 48
33 #define DSHOT_MAX_THROTTLE 2047
34 #define DSHOT_3D_DEADBAND_LOW 1047
35 #define DSHOT_3D_DEADBAND_HIGH 1048
37 typedef enum {
38 PLATFORM_MULTIROTOR = 0,
39 PLATFORM_AIRPLANE = 1,
40 PLATFORM_HELICOPTER = 2,
41 PLATFORM_TRICOPTER = 3,
42 PLATFORM_ROVER = 4,
43 PLATFORM_BOAT = 5,
44 PLATFORM_OTHER = 6
45 } flyingPlatformType_e;
48 typedef enum {
49 OUTPUT_MODE_AUTO = 0,
50 OUTPUT_MODE_MOTORS,
51 OUTPUT_MODE_SERVOS
52 } outputMode_e;
54 typedef struct motorAxisCorrectionLimits_s {
55 int16_t min;
56 int16_t max;
57 } motorAxisCorrectionLimits_t;
59 // Custom mixer data per motor
60 typedef struct motorMixer_s {
61 float throttle;
62 float roll;
63 float pitch;
64 float yaw;
65 } motorMixer_t;
68 typedef struct timerOverride_s {
69 uint8_t outputMode;
70 } timerOverride_t;
72 PG_DECLARE_ARRAY(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides);
74 typedef struct reversibleMotorsConfig_s {
75 uint16_t deadband_low; // min 3d value
76 uint16_t deadband_high; // max 3d value
77 uint16_t neutral; // center 3d value
78 } reversibleMotorsConfig_t;
80 PG_DECLARE(reversibleMotorsConfig_t, reversibleMotorsConfig);
82 typedef struct motorConfig_s {
83 // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
84 uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
85 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
86 uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
87 uint8_t motorPwmProtocol;
88 uint16_t digitalIdleOffsetValue;
89 uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry
90 } motorConfig_t;
92 PG_DECLARE(motorConfig_t, motorConfig);
94 typedef enum {
95 MOTOR_STOPPED_USER,
96 MOTOR_STOPPED_AUTO,
97 MOTOR_RUNNING
98 } motorStatus_e;
100 typedef enum {
101 MOTOR_DIRECTION_FORWARD,
102 MOTOR_DIRECTION_BACKWARD,
103 MOTOR_DIRECTION_DEADBAND
104 } reversibleMotorsThrottleState_e;
106 extern int16_t motor[MAX_SUPPORTED_MOTORS];
107 extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
108 extern int mixerThrottleCommand;
110 bool ifMotorstopFeatureEnabled(void);
111 int getThrottleIdleValue(void);
112 int16_t getThrottlePercent(bool);
113 uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop);
114 uint8_t getMotorCount(void);
115 float getMotorMixRange(void);
116 bool mixerIsOutputSaturated(void);
117 motorStatus_e getMotorStatus(void);
119 void writeAllMotors(int16_t mc);
120 void mixerInit(void);
121 void mixerUpdateStateFlags(void);
122 void mixerResetDisarmedMotors(void);
123 void mixTable(void);
124 void writeMotors(void);
125 void processServoAutotrim(const float dT);
126 void processServoAutotrimMode(void);
127 void processContinuousServoAutotrim(const float dT);
128 void stopMotors(void);
129 void stopMotorsNoDelay(void);
130 void stopPwmAllMotors(void);
132 void loadPrimaryMotorMixer(void);
133 bool areMotorsRunning(void);