Refactor Rx code and better support 25Hz links (#13435)
[betaflight.git] / src / main / fc / rc_controls.h
blobe0bc36e64e39d2dac3821998cb0dec810757cf55
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 <stdbool.h>
25 #include "common/filter.h"
26 #include "pg/pg.h"
28 typedef enum rc_alias {
29 ROLL = 0,
30 PITCH,
31 YAW,
32 THROTTLE,
33 AUX1,
34 AUX2,
35 AUX3,
36 AUX4,
37 AUX5,
38 AUX6,
39 AUX7,
40 AUX8,
41 AUX9,
42 AUX10,
43 AUX11,
44 AUX12
45 } rc_alias_e;
47 #define PRIMARY_CHANNEL_COUNT (THROTTLE + 1)
49 typedef enum {
50 THROTTLE_LOW = 0,
51 THROTTLE_HIGH
52 } throttleStatus_e;
54 #define AIRMODEDEADBAND 12
56 typedef enum {
57 NOT_CENTERED = 0,
58 CENTERED
59 } rollPitchStatus_e;
61 #define ROL_LO (1 << (2 * ROLL))
62 #define ROL_CE (3 << (2 * ROLL))
63 #define ROL_HI (2 << (2 * ROLL))
64 #define PIT_LO (1 << (2 * PITCH))
65 #define PIT_CE (3 << (2 * PITCH))
66 #define PIT_HI (2 << (2 * PITCH))
67 #define YAW_LO (1 << (2 * YAW))
68 #define YAW_CE (3 << (2 * YAW))
69 #define YAW_HI (2 << (2 * YAW))
70 #define THR_LO (1 << (2 * THROTTLE))
71 #define THR_CE (3 << (2 * THROTTLE))
72 #define THR_HI (2 << (2 * THROTTLE))
73 #define THR_MASK (3 << (2 * THROTTLE))
75 #define CONTROL_RATE_CONFIG_RC_EXPO_MAX 100
77 #define CONTROL_RATE_CONFIG_RC_RATES_MAX 255
79 #define CONTROL_RATE_CONFIG_RATE_LIMIT_MIN 200
80 #define CONTROL_RATE_CONFIG_RATE_LIMIT_MAX 1998
82 // (Super) rates are constrained to [0, 100] for Betaflight rates, so values higher than 100 won't make a difference. Range extended for RaceFlight rates.
83 #define CONTROL_RATE_CONFIG_RATE_MAX 255
85 extern float rcCommand[4];
87 typedef struct rcSmoothingFilter_s {
88 bool filterInitialized;
89 pt3Filter_t filterSetpoint[4];
90 pt3Filter_t filterRcDeflection[2];
91 pt3Filter_t filterFeedforward[3];
93 uint8_t setpointCutoffSetting;
94 uint8_t throttleCutoffSetting;
95 uint8_t feedforwardCutoffSetting;
97 uint16_t setpointCutoffFrequency;
98 uint16_t throttleCutoffFrequency;
99 uint16_t feedforwardCutoffFrequency;
101 float smoothedRxRateHz;
102 uint8_t sampleCount;
103 uint8_t debugAxis;
105 float autoSmoothnessFactorSetpoint;
106 float autoSmoothnessFactorFeedforward;
107 float autoSmoothnessFactorThrottle;
108 } rcSmoothingFilter_t;
110 typedef struct rcControlsConfig_s {
111 uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
112 uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
113 uint8_t alt_hold_deadband; // defines the neutral zone of throttle stick during altitude hold, default setting is +/-40
114 uint8_t alt_hold_fast_change; // when disabled, turn off the althold when throttle stick is out of deadband defined with alt_hold_deadband; when enabled, altitude changes slowly proportional to stick movement
115 bool yaw_control_reversed; // invert control direction of yaw
116 } rcControlsConfig_t;
118 PG_DECLARE(rcControlsConfig_t, rcControlsConfig);
120 typedef struct flight3DConfig_s {
121 uint16_t deadband3d_low; // min 3d value
122 uint16_t deadband3d_high; // max 3d value
123 uint16_t neutral3d; // center 3d value
124 uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
125 uint16_t limit3d_low; // pwm output value for max negative thrust
126 uint16_t limit3d_high; // pwm output value for max positive thrust
127 uint8_t switched_mode3d; // enable '3D Switched Mode'
128 } flight3DConfig_t;
130 PG_DECLARE(flight3DConfig_t, flight3DConfig);
132 typedef struct armingConfig_s {
133 uint8_t gyro_cal_on_first_arm; // calibrate the gyro right before the first arm
134 uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
135 } armingConfig_t;
137 PG_DECLARE(armingConfig_t, armingConfig);
139 bool areUsingSticksToArm(void);
141 throttleStatus_e calculateThrottleStatus(void);
142 void processRcStickPositions();
144 bool isUsingSticksForArming(void);
146 void rcControlsInit(void);