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)
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/>.
25 #include "common/axis.h"
26 #include "common/filter.h"
29 typedef enum rc_alias
{
48 #define PRIMARY_CHANNEL_COUNT (THROTTLE + 1)
55 #define AIRMODEDEADBAND 12
62 #define ROL_LO (1 << (2 * ROLL))
63 #define ROL_CE (3 << (2 * ROLL))
64 #define ROL_HI (2 << (2 * ROLL))
65 #define PIT_LO (1 << (2 * PITCH))
66 #define PIT_CE (3 << (2 * PITCH))
67 #define PIT_HI (2 << (2 * PITCH))
68 #define YAW_LO (1 << (2 * YAW))
69 #define YAW_CE (3 << (2 * YAW))
70 #define YAW_HI (2 << (2 * YAW))
71 #define THR_LO (1 << (2 * THROTTLE))
72 #define THR_CE (3 << (2 * THROTTLE))
73 #define THR_HI (2 << (2 * THROTTLE))
74 #define THR_MASK (3 << (2 * THROTTLE))
76 #define CONTROL_RATE_CONFIG_RC_EXPO_MAX 100
78 #define CONTROL_RATE_CONFIG_RC_RATES_MAX 255
80 #define CONTROL_RATE_CONFIG_RATE_LIMIT_MIN 200
81 #define CONTROL_RATE_CONFIG_RATE_LIMIT_MAX 1998
83 // (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.
84 #define CONTROL_RATE_CONFIG_RATE_MAX 255
86 extern float rcCommand
[4];
88 typedef struct rcSmoothingFilter_s
{
89 bool filterInitialized
;
90 pt3Filter_t filterSetpoint
[4];
91 pt3Filter_t filterRcDeflection
[RP_AXIS_COUNT
];
92 pt3Filter_t filterFeedforward
[3];
94 uint8_t setpointCutoffSetting
;
95 uint8_t throttleCutoffSetting
;
96 uint8_t feedforwardCutoffSetting
;
98 uint16_t setpointCutoffFrequency
;
99 uint16_t throttleCutoffFrequency
;
100 uint16_t feedforwardCutoffFrequency
;
102 float smoothedRxRateHz
;
106 float autoSmoothnessFactorSetpoint
;
107 float autoSmoothnessFactorFeedforward
;
108 float autoSmoothnessFactorThrottle
;
109 } rcSmoothingFilter_t
;
111 typedef struct rcControlsConfig_s
{
112 uint8_t deadband
; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
113 uint8_t yaw_deadband
; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
114 bool yaw_control_reversed
; // invert control direction of yaw
115 } rcControlsConfig_t
;
117 PG_DECLARE(rcControlsConfig_t
, rcControlsConfig
);
119 typedef struct flight3DConfig_s
{
120 uint16_t deadband3d_low
; // min 3d value
121 uint16_t deadband3d_high
; // max 3d value
122 uint16_t neutral3d
; // center 3d value
123 uint16_t deadband3d_throttle
; // default throttle deadband from MIDRC
124 uint16_t limit3d_low
; // pwm output value for max negative thrust
125 uint16_t limit3d_high
; // pwm output value for max positive thrust
126 uint8_t switched_mode3d
; // enable '3D Switched Mode'
129 PG_DECLARE(flight3DConfig_t
, flight3DConfig
);
131 typedef struct armingConfig_s
{
132 uint8_t gyro_cal_on_first_arm
; // calibrate the gyro right before the first arm
133 uint8_t auto_disarm_delay
; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
134 uint8_t prearm_allow_rearm
;
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);