Refactor missing prototypes 2 (#14170)
[betaflight.git] / src / main / fc / rc.c
blob80c284191a79e128d61317bb7aab64dea2cfbbb2
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 #include <stdbool.h>
22 #include <stdint.h>
23 #include <stdlib.h>
24 #include <math.h>
26 #include "platform.h"
28 #include "build/debug.h"
30 #include "common/utils.h"
31 #include "common/vector.h"
33 #include "config/config.h"
34 #include "config/feature.h"
36 #include "fc/controlrate_profile.h"
37 #include "fc/core.h"
38 #include "fc/rc.h"
39 #include "fc/rc_controls.h"
40 #include "fc/rc_modes.h"
41 #include "fc/runtime_config.h"
43 #include "flight/failsafe.h"
44 #include "flight/imu.h"
45 #include "flight/gps_rescue.h"
46 #include "flight/pid.h"
47 #include "flight/pid_init.h"
49 #include "pg/rx.h"
50 #include "rx/rx.h"
52 #include "sensors/battery.h"
53 #include "sensors/gyro.h"
55 #include "rc.h"
57 #define RX_INTERVAL_MIN_US 950 // 0.950ms to fit 1kHz without an issue
58 #define RX_INTERVAL_MAX_US 65500 // 65.5ms or 15.26hz
60 typedef float (applyRatesFn)(const int axis, float rcCommandf, const float rcCommandfAbs);
61 // note that rcCommand[] is an external float
63 static float rawSetpoint[XYZ_AXIS_COUNT];
65 static float setpointRate[3], rcDeflection[3], rcDeflectionAbs[3]; // deflection range -1 to 1
66 static float maxRcDeflectionAbs;
68 static bool reverseMotors = false;
69 static applyRatesFn *applyRates;
71 static uint16_t currentRxIntervalUs; // packet interval in microseconds, constrained to above range
72 static uint16_t previousRxIntervalUs; // previous packet interval in microseconds
73 static float currentRxRateHz; // packet interval in Hz, constrained as above
75 static bool isRxDataNew = false;
76 static bool isRxRateValid = false;
77 static float rcCommandDivider = 500.0f;
78 static float rcCommandYawDivider = 500.0f;
80 enum {
81 ROLL_FLAG = 1 << ROLL,
82 PITCH_FLAG = 1 << PITCH,
83 YAW_FLAG = 1 << YAW,
84 THROTTLE_FLAG = 1 << THROTTLE,
87 #ifdef USE_FEEDFORWARD
88 static float feedforwardSmoothed[3];
89 static float feedforwardRaw[3];
90 static uint16_t feedforwardAveraging;
91 typedef struct laggedMovingAverageCombined_s {
92 laggedMovingAverage_t filter;
93 float buf[4];
94 } laggedMovingAverageCombined_t;
95 laggedMovingAverageCombined_t feedforwardDeltaAvg[XYZ_AXIS_COUNT];
97 static pt1Filter_t feedforwardYawHoldLpf;
99 float getFeedforward(int axis)
101 #ifdef USE_RC_SMOOTHING_FILTER
102 return feedforwardSmoothed[axis];
103 #else
104 return feedforwardRaw[axis];
105 #endif
107 #endif // USE_FEEDFORWARD
109 #ifdef USE_RC_SMOOTHING_FILTER
110 static FAST_DATA_ZERO_INIT rcSmoothingFilter_t rcSmoothingData;
111 static float rcDeflectionSmoothed[3];
112 #endif // USE_RC_SMOOTHING_FILTER
114 float getSetpointRate(int axis)
116 #ifdef USE_RC_SMOOTHING_FILTER
117 return setpointRate[axis];
118 #else
119 return rawSetpoint[axis];
120 #endif
123 static float maxRcRate[3];
124 float getMaxRcRate(int axis)
126 return maxRcRate[axis];
129 float getRcDeflection(int axis)
131 #ifdef USE_RC_SMOOTHING_FILTER
132 return rcDeflectionSmoothed[axis];
133 #else
134 return rcDeflection[axis];
135 #endif
138 float getRcDeflectionRaw(int axis)
140 return rcDeflection[axis];
143 float getRcDeflectionAbs(int axis)
145 return rcDeflectionAbs[axis];
148 float getMaxRcDeflectionAbs(void)
150 return maxRcDeflectionAbs;
153 #define THROTTLE_LOOKUP_LENGTH 12
154 static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
156 static int16_t rcLookupThrottle(int32_t tmp)
158 const int32_t tmp2 = tmp / 100;
159 // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE]
160 return lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100;
163 #define SETPOINT_RATE_LIMIT_MIN -1998.0f
164 #define SETPOINT_RATE_LIMIT_MAX 1998.0f
165 STATIC_ASSERT(CONTROL_RATE_CONFIG_RATE_LIMIT_MAX <= (uint16_t)SETPOINT_RATE_LIMIT_MAX, CONTROL_RATE_CONFIG_RATE_LIMIT_MAX_too_large);
167 #define RC_RATE_INCREMENTAL 14.54f
169 static float applyBetaflightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
171 if (currentControlRateProfile->rcExpo[axis]) {
172 const float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
173 rcCommandf = rcCommandf * power3(rcCommandfAbs) * expof + rcCommandf * (1 - expof);
176 float rcRate = currentControlRateProfile->rcRates[axis] / 100.0f;
177 if (rcRate > 2.0f) {
178 rcRate += RC_RATE_INCREMENTAL * (rcRate - 2.0f);
180 float angleRate = 200.0f * rcRate * rcCommandf;
181 if (currentControlRateProfile->rates[axis]) {
182 const float rcSuperfactor = 1.0f / (constrainf(1.0f - (rcCommandfAbs * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
183 angleRate *= rcSuperfactor;
186 return angleRate;
189 static float applyRaceFlightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
191 // -1.0 to 1.0 ranged and curved
192 rcCommandf = ((1.0f + 0.01f * currentControlRateProfile->rcExpo[axis] * (rcCommandf * rcCommandf - 1.0f)) * rcCommandf);
193 // convert to -2000 to 2000 range using acro+ modifier
194 float angleRate = 10.0f * currentControlRateProfile->rcRates[axis] * rcCommandf;
195 angleRate = angleRate * (1 + rcCommandfAbs * (float)currentControlRateProfile->rates[axis] * 0.01f);
197 return angleRate;
200 static float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs)
202 const float rcCurvef = currentControlRateProfile->rcExpo[axis] / 100.0f;
204 float kissRpyUseRates = 1.0f / (constrainf(1.0f - (rcCommandfAbs * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
205 float kissRcCommandf = (power3(rcCommandf) * rcCurvef + rcCommandf * (1 - rcCurvef)) * (currentControlRateProfile->rcRates[axis] / 1000.0f);
206 float kissAngle = constrainf(((2000.0f * kissRpyUseRates) * kissRcCommandf), SETPOINT_RATE_LIMIT_MIN, SETPOINT_RATE_LIMIT_MAX);
208 return kissAngle;
211 static float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs)
213 float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
214 expof = rcCommandfAbs * (power5(rcCommandf) * expof + rcCommandf * (1 - expof));
216 const float centerSensitivity = currentControlRateProfile->rcRates[axis] * 10.0f;
217 const float stickMovement = MAX(0, currentControlRateProfile->rates[axis] * 10.0f - centerSensitivity);
218 const float angleRate = rcCommandf * centerSensitivity + stickMovement * expof;
220 return angleRate;
223 static float applyQuickRates(const int axis, float rcCommandf, const float rcCommandfAbs)
225 const uint16_t rcRate = currentControlRateProfile->rcRates[axis] * 2;
226 const uint16_t maxDPS = MAX(currentControlRateProfile->rates[axis] * 10, rcRate);
227 const float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
228 const float superFactorConfig = ((float)maxDPS / rcRate - 1) / ((float)maxDPS / rcRate);
230 float curve;
231 float superFactor;
232 float angleRate;
234 if (currentControlRateProfile->quickRatesRcExpo) {
235 curve = power3(rcCommandf) * expof + rcCommandf * (1 - expof);
236 superFactor = 1.0f / (constrainf(1.0f - (rcCommandfAbs * superFactorConfig), 0.01f, 1.00f));
237 angleRate = constrainf(curve * rcRate * superFactor, SETPOINT_RATE_LIMIT_MIN, SETPOINT_RATE_LIMIT_MAX);
238 } else {
239 curve = power3(rcCommandfAbs) * expof + rcCommandfAbs * (1 - expof);
240 superFactor = 1.0f / (constrainf(1.0f - (curve * superFactorConfig), 0.01f, 1.00f));
241 angleRate = constrainf(rcCommandf * rcRate * superFactor, SETPOINT_RATE_LIMIT_MIN, SETPOINT_RATE_LIMIT_MAX);
244 return angleRate;
247 static void scaleRawSetpointToFpvCamAngle(void)
249 //recalculate sin/cos only when rxConfig()->fpvCamAngleDegrees changed
250 static uint8_t lastFpvCamAngleDegrees = 0;
251 static float cosFactor = 1.0;
252 static float sinFactor = 0.0;
254 if (lastFpvCamAngleDegrees != rxConfig()->fpvCamAngleDegrees) {
255 lastFpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees;
256 cosFactor = cos_approx(rxConfig()->fpvCamAngleDegrees * RAD);
257 sinFactor = sin_approx(rxConfig()->fpvCamAngleDegrees * RAD);
260 float roll = rawSetpoint[ROLL];
261 float yaw = rawSetpoint[YAW];
262 rawSetpoint[ROLL] = constrainf(roll * cosFactor - yaw * sinFactor, SETPOINT_RATE_LIMIT_MIN, SETPOINT_RATE_LIMIT_MAX);
263 rawSetpoint[YAW] = constrainf(yaw * cosFactor + roll * sinFactor, SETPOINT_RATE_LIMIT_MIN, SETPOINT_RATE_LIMIT_MAX);
266 void updateRcRefreshRate(timeUs_t currentTimeUs, bool rxReceivingSignal)
268 // this function runs from processRx in core.c
269 // rxReceivingSignal is true:
270 // - every time a new frame is detected,
271 // - if we stop getting data, at the expiry of RXLOSS_TRIGGER_INTERVAL since the last good frame
272 // - if that interval is exceeded and still no data, every RX_FRAME_RECHECK_INTERVAL, until a new frame is detected
273 static timeUs_t lastRxTimeUs = 0;
274 timeDelta_t delta = 0;
276 if (rxReceivingSignal) { // true while receiving data and until RXLOSS_TRIGGER_INTERVAL expires, otherwise false
277 previousRxIntervalUs = currentRxIntervalUs;
278 // use driver rx time if available, current time otherwise
279 const timeUs_t rxTime = rxRuntimeState.lastRcFrameTimeUs ? rxRuntimeState.lastRcFrameTimeUs : currentTimeUs;
281 if (lastRxTimeUs) { // report delta only if previous time is available
282 delta = cmpTimeUs(rxTime, lastRxTimeUs);
284 lastRxTimeUs = rxTime;
285 DEBUG_SET(DEBUG_RX_TIMING, 1, rxTime / 100); // output value in tenths of ms
286 } else {
287 if (lastRxTimeUs) {
288 // no packet received, use current time for delta
289 delta = cmpTimeUs(currentTimeUs, lastRxTimeUs);
293 // temporary debugs
294 DEBUG_SET(DEBUG_RX_TIMING, 4, MIN(delta / 10, INT16_MAX)); // time between frames based on rxFrameCheck
295 #ifdef USE_RX_LINK_QUALITY_INFO
296 DEBUG_SET(DEBUG_RX_TIMING, 6, rxGetLinkQualityPercent()); // raw link quality value
297 #endif
298 DEBUG_SET(DEBUG_RX_TIMING, 7, isRxReceivingSignal()); // flag to initiate RXLOSS signal and Stage 1 values
300 // constrain to a frequency range no lower than about 15Hz and up to about 1000Hz
301 // these intervals and rates will be used for RCSmoothing, Feedforward, etc.
302 currentRxIntervalUs = constrain(delta, RX_INTERVAL_MIN_US, RX_INTERVAL_MAX_US);
303 currentRxRateHz = 1e6f / currentRxIntervalUs;
304 isRxRateValid = delta == currentRxIntervalUs; // delta is not constrained, therefore not outside limits
306 DEBUG_SET(DEBUG_RX_TIMING, 0, MIN(delta / 10, INT16_MAX)); // output value in hundredths of ms
307 DEBUG_SET(DEBUG_RX_TIMING, 2, isRxRateValid);
308 DEBUG_SET(DEBUG_RX_TIMING, 3, MIN(currentRxIntervalUs / 10, INT16_MAX));
311 uint16_t getCurrentRxRateHz(void)
313 return currentRxRateHz;
316 bool getRxRateValid(void)
318 return isRxRateValid;
321 #ifdef USE_RC_SMOOTHING_FILTER
323 // Initialize or update the filters base on either the manually selected cutoff, or
324 // the auto-calculated cutoff frequency based on detected rx frame rate.
325 static FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothingData)
327 // in auto mode, calculate the RC smoothing cutoff from the smoothed Rx link frequency
328 const uint16_t oldSetpointCutoff = smoothingData->setpointCutoffFrequency;
329 const uint16_t oldFeedforwardCutoff = smoothingData->feedforwardCutoffFrequency;
330 const uint16_t minCutoffHz = 15; // don't let any RC smoothing filter cutoff go below 15Hz
331 if (smoothingData->setpointCutoffSetting == 0) {
332 smoothingData->setpointCutoffFrequency = MAX(minCutoffHz, (uint16_t)(smoothingData->smoothedRxRateHz * smoothingData->autoSmoothnessFactorSetpoint));
334 if (smoothingData->throttleCutoffSetting == 0) {
335 smoothingData->throttleCutoffFrequency = MAX(minCutoffHz, (uint16_t)(smoothingData->smoothedRxRateHz * smoothingData->autoSmoothnessFactorThrottle));
338 if (smoothingData->feedforwardCutoffSetting == 0) {
339 smoothingData->feedforwardCutoffFrequency = MAX(minCutoffHz, (uint16_t)(smoothingData->smoothedRxRateHz * smoothingData->autoSmoothnessFactorFeedforward));
342 const float dT = targetPidLooptime * 1e-6f;
343 if ((smoothingData->setpointCutoffFrequency != oldSetpointCutoff) || !smoothingData->filterInitialized) {
344 // note that cutoff frequencies are integers, filter cutoffs won't re-calculate until there is > 1hz variation from previous cutoff
345 // initialize or update the setpoint cutoff based filters
346 const float setpointCutoffFrequency = smoothingData->setpointCutoffFrequency;
347 for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
348 if (i < THROTTLE) {
349 if (!smoothingData->filterInitialized) {
350 pt3FilterInit(&smoothingData->filterSetpoint[i], pt3FilterGain(setpointCutoffFrequency, dT));
351 } else {
352 pt3FilterUpdateCutoff(&smoothingData->filterSetpoint[i], pt3FilterGain(setpointCutoffFrequency, dT));
354 } else {
355 const float throttleCutoffFrequency = smoothingData->throttleCutoffFrequency;
356 if (!smoothingData->filterInitialized) {
357 pt3FilterInit(&smoothingData->filterSetpoint[i], pt3FilterGain(throttleCutoffFrequency, dT));
358 } else {
359 pt3FilterUpdateCutoff(&smoothingData->filterSetpoint[i], pt3FilterGain(throttleCutoffFrequency, dT));
363 // initialize or update the RC Deflection filter
364 for (int i = FD_ROLL; i < FD_YAW; i++) {
365 if (!smoothingData->filterInitialized) {
366 pt3FilterInit(&smoothingData->filterRcDeflection[i], pt3FilterGain(setpointCutoffFrequency, dT));
367 } else {
368 pt3FilterUpdateCutoff(&smoothingData->filterRcDeflection[i], pt3FilterGain(setpointCutoffFrequency, dT));
372 // initialize or update the Feedforward filter
373 if ((smoothingData->feedforwardCutoffFrequency != oldFeedforwardCutoff) || !smoothingData->filterInitialized) {
374 for (int i = FD_ROLL; i <= FD_YAW; i++) {
375 const float feedforwardCutoffFrequency = smoothingData->feedforwardCutoffFrequency;
376 if (!smoothingData->filterInitialized) {
377 pt3FilterInit(&smoothingData->filterFeedforward[i], pt3FilterGain(feedforwardCutoffFrequency, dT));
378 } else {
379 pt3FilterUpdateCutoff(&smoothingData->filterFeedforward[i], pt3FilterGain(feedforwardCutoffFrequency, dT));
384 DEBUG_SET(DEBUG_RC_SMOOTHING, 1, smoothingData->setpointCutoffFrequency);
385 DEBUG_SET(DEBUG_RC_SMOOTHING, 2, smoothingData->feedforwardCutoffFrequency);
388 // Determine if we need to caclulate filter cutoffs. If not then we can avoid
389 // examining the rx frame times completely
390 FAST_CODE_NOINLINE bool rcSmoothingAutoCalculate(void)
392 // if any rc smoothing cutoff is 0 (auto) then we need to calculate cutoffs
393 if ((rcSmoothingData.setpointCutoffSetting == 0) || (rcSmoothingData.feedforwardCutoffSetting == 0) || (rcSmoothingData.throttleCutoffSetting == 0)) {
394 return true;
396 return false;
399 static FAST_CODE void processRcSmoothingFilter(void)
401 static FAST_DATA_ZERO_INIT float rxDataToSmooth[4];
402 static FAST_DATA_ZERO_INIT bool initialized;
403 static FAST_DATA_ZERO_INIT bool calculateCutoffs;
405 // first call initialization
406 if (!initialized) {
407 initialized = true;
408 rcSmoothingData.filterInitialized = false;
409 rcSmoothingData.smoothedRxRateHz = 0.0f;
410 rcSmoothingData.sampleCount = 0;
411 rcSmoothingData.debugAxis = rxConfig()->rc_smoothing_debug_axis;
413 rcSmoothingData.autoSmoothnessFactorSetpoint = 1.5f / (1.0f + (rxConfig()->rc_smoothing_auto_factor_rpy / 10.0f));
414 rcSmoothingData.autoSmoothnessFactorFeedforward = 1.5f / (1.0f + (rxConfig()->rc_smoothing_auto_factor_rpy / 10.0f));
415 rcSmoothingData.autoSmoothnessFactorThrottle = 1.5f / (1.0f + (rxConfig()->rc_smoothing_auto_factor_throttle / 10.0f));
417 rcSmoothingData.setpointCutoffSetting = rxConfig()->rc_smoothing_setpoint_cutoff;
418 rcSmoothingData.throttleCutoffSetting = rxConfig()->rc_smoothing_throttle_cutoff;
419 rcSmoothingData.feedforwardCutoffSetting = rxConfig()->rc_smoothing_feedforward_cutoff;
421 rcSmoothingData.setpointCutoffFrequency = rcSmoothingData.setpointCutoffSetting;
422 rcSmoothingData.feedforwardCutoffFrequency = rcSmoothingData.feedforwardCutoffSetting;
423 rcSmoothingData.throttleCutoffFrequency = rcSmoothingData.throttleCutoffSetting;
425 if (rxConfig()->rc_smoothing_mode) {
426 calculateCutoffs = rcSmoothingAutoCalculate();
427 // if we don't need to calculate cutoffs dynamically then the filters can be initialized now
428 if (!calculateCutoffs) {
429 rcSmoothingSetFilterCutoffs(&rcSmoothingData);
430 rcSmoothingData.filterInitialized = true;
435 if (isRxDataNew) {
436 if (calculateCutoffs) {
437 // for auto calculated filters, calculate the link interval and update the RC smoothing filters at regular intervals
438 // this is more efficient than monitoring for significant changes and making comparisons to decide whether to update the filter
439 const timeMs_t currentTimeMs = millis();
440 int sampleState = 0;
441 const bool ready = (currentTimeMs > 1000) && (targetPidLooptime > 0);
442 if (ready) { // skip during FC initialization
443 // Wait 1000ms after power to let the PID loop stabilize before starting average frame rate calculation
444 if (isRxReceivingSignal() && isRxRateValid) {
446 if (abs(currentRxIntervalUs - previousRxIntervalUs) < (previousRxIntervalUs - (previousRxIntervalUs / 8))) {
447 // exclude large steps, eg after dropouts or telemetry
448 // by using interval here, we catch a dropout/telemetry where the inteval increases by 100%, but accept
449 // the return to normal value, which is only 50% different from the 100% interval of a single drop, and 66% of a return after a double drop.
450 static float prevSmoothedRxRateHz;
451 // smooth the current Rx link frequency estimates
452 const float kF = 0.1f; // first order kind of lowpass smoothing filter coefficient
453 // add one tenth of the new estimate to the smoothed estimate.
454 const float smoothedRxRateHz = prevSmoothedRxRateHz + kF * (currentRxRateHz - prevSmoothedRxRateHz);
455 prevSmoothedRxRateHz = smoothedRxRateHz;
457 // recalculate cutoffs every 3 acceptable samples
458 if (rcSmoothingData.sampleCount) {
459 rcSmoothingData.sampleCount --;
460 sampleState = 1;
461 } else {
462 rcSmoothingData.smoothedRxRateHz = smoothedRxRateHz;
463 rcSmoothingSetFilterCutoffs(&rcSmoothingData);
464 rcSmoothingData.filterInitialized = true;
465 rcSmoothingData.sampleCount = 3;
466 sampleState = 2;
469 } else {
470 // either we stopped receiving rx samples (failsafe?) or the sample interval is unreasonable
471 // require a full re-evaluation period after signal is restored
472 rcSmoothingData.sampleCount = 0;
473 sampleState = 4;
476 DEBUG_SET(DEBUG_RC_SMOOTHING_RATE, 0, currentRxIntervalUs / 10);
477 DEBUG_SET(DEBUG_RC_SMOOTHING_RATE, 1, rcSmoothingData.sampleCount);
478 DEBUG_SET(DEBUG_RC_SMOOTHING_RATE, 2, rcSmoothingData.smoothedRxRateHz); // value used by filters
479 DEBUG_SET(DEBUG_RC_SMOOTHING_RATE, 3, sampleState); // guard time = 1, guard time expired = 2
481 // Get new values to be smoothed
482 for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
483 rxDataToSmooth[i] = i == THROTTLE ? rcCommand[i] : rawSetpoint[i];
484 if (i < THROTTLE) {
485 DEBUG_SET(DEBUG_RC_INTERPOLATION, i, lrintf(rxDataToSmooth[i]));
486 } else {
487 DEBUG_SET(DEBUG_RC_INTERPOLATION, i, ((lrintf(rxDataToSmooth[i])) - 1000));
492 DEBUG_SET(DEBUG_RC_SMOOTHING, 0, rcSmoothingData.smoothedRxRateHz);
493 DEBUG_SET(DEBUG_RC_SMOOTHING, 3, rcSmoothingData.sampleCount);
495 // each pid loop, apply the last received channel value to the filter, if initialised - thanks @klutvott
496 for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
497 float *dst = i == THROTTLE ? &rcCommand[i] : &setpointRate[i];
498 if (rcSmoothingData.filterInitialized) {
499 *dst = pt3FilterApply(&rcSmoothingData.filterSetpoint[i], rxDataToSmooth[i]);
500 } else {
501 // If filter isn't initialized yet, as in smoothing off, use the actual unsmoothed rx channel data
502 *dst = rxDataToSmooth[i];
506 for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
507 // Feedforward smoothing
508 feedforwardSmoothed[axis] = pt3FilterApply(&rcSmoothingData.filterFeedforward[axis], feedforwardRaw[axis]);
509 // Horizon mode smoothing of rcDeflection on pitch and roll to provide a smooth angle element
510 const bool smoothRcDeflection = FLIGHT_MODE(HORIZON_MODE) && rcSmoothingData.filterInitialized;
511 if (smoothRcDeflection && axis < FD_YAW) {
512 rcDeflectionSmoothed[axis] = pt3FilterApply(&rcSmoothingData.filterRcDeflection[axis], rcDeflection[axis]);
513 } else {
514 rcDeflectionSmoothed[axis] = rcDeflection[axis];
518 #endif // USE_RC_SMOOTHING_FILTER
520 #ifdef USE_FEEDFORWARD
521 static FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dynamics_index_t axis)
523 const float rxInterval = currentRxIntervalUs * 1e-6f; // seconds
524 float rxRate = currentRxRateHz; // 1e6f / currentRxIntervalUs;
525 static float prevRcCommand[3]; // for rcCommandDelta test
526 static float prevRcCommandDeltaAbs[3]; // for duplicate interpolation
527 static float prevSetpoint[3]; // equals raw unless extrapolated forward
528 static float prevSetpointSpeed[3]; // for setpointDelta calculation
529 static float prevSetpointSpeedDelta[3]; // for duplicate extrapolation
530 static bool isPrevPacketDuplicate[3]; // to identify multiple identical packets
532 const float rcCommandDelta = rcCommand[axis] - prevRcCommand[axis];
533 prevRcCommand[axis] = rcCommand[axis];
534 float rcCommandDeltaAbs = fabsf(rcCommandDelta);
536 const float setpoint = rawSetpoint[axis];
537 const float setpointDelta = setpoint - prevSetpoint[axis];
538 prevSetpoint[axis] = setpoint;
540 float setpointSpeed = 0.0f;
541 float setpointSpeedDelta = 0.0f;
542 float feedforward = 0.0f;
544 if (pid->feedforwardInterpolate) {
545 static float prevRxInterval;
546 // for Rx links which send frequent duplicate data packets, use a per-axis duplicate test
547 // extrapolate setpointSpeed when a duplicate is detected, to minimise steps in feedforward
548 const bool isDuplicate = rcCommandDeltaAbs == 0;
549 if (!isDuplicate) {
550 // movement!
551 // but, if the packet before this was also a duplicate,
552 // calculate setpointSpeed over the last two intervals
553 if (isPrevPacketDuplicate[axis]) {
554 rxRate = 1.0f / (rxInterval + prevRxInterval);
556 setpointSpeed = setpointDelta * rxRate;
557 isPrevPacketDuplicate[axis] = isDuplicate;
558 } else {
559 // no movement
560 if (!isPrevPacketDuplicate[axis]) {
561 // extrapolate a replacement setpointSpeed value for the first duplicate after normal movement
562 // but not when about to hit max deflection
563 if (fabsf(setpoint) < 0.90f * maxRcRate[axis]) {
564 // this is a single packet duplicate, and we assume that it is of approximately normal duration
565 // hence no multiplication of prevSetpointSpeedDelta by rxInterval / prevRxInterval
566 setpointSpeed = prevSetpointSpeed[axis] + prevSetpointSpeedDelta[axis];
567 // pretend that there was stick movement also, to hold the same jitter value
568 rcCommandDeltaAbs = prevRcCommandDeltaAbs[axis];
570 } else {
571 // for second and all subsequent duplicates...
572 // force setpoint speed to zero
573 setpointSpeed = 0.0f;
574 // zero the acceleration by setting previous speed to zero
575 // feedforward will smoothly decay and be attenuated by the jitter reduction value for zero rcCommandDelta
576 prevSetpointSpeed[axis] = 0.0f; // zero acceleration later on
578 isPrevPacketDuplicate[axis] = isDuplicate;
580 prevRxInterval = rxInterval;
581 } else {
582 // don't interpolate for radio systems that rarely send duplicate packets, eg CRSF/ELRS
583 setpointSpeed = setpointDelta * rxRate;
586 // calculate jitterAttenuation factor
587 // The intent is to attenuate feedforward when absolute rcCommandDelta is small, ie when sticks move very slowly
588 // Greater feedforward_jitter_factor values widen the attenuation range, and increase the suppression at center
589 // Stick input is the average of the previous two absolute rcCommandDelta values
590 // Output is jitterAttenuator, a value 0-1.0 that is a simple multiplier of the final feedforward value
591 // For the CLI user setting of feedforward_jitter_factor:
592 // User setting of 0 returns feedforwardJitterFactorInv = 1.0 (and disables the function)
593 // User setting of 1 returns feedforwardJitterFactorInv = 0.5
594 // User setting of 9 returns feedforwardJitterFactorInv = 0.1
595 // rcCommandDelta has 500 unit values either side of center stick position
596 // For a 250Hz link, a one second stick sweep center->max returns rcCommandDelta around 2.0
597 // For a user jitter reduction setting of 2, the jitterAttenuator value ranges linearly
598 // from 0.33 when rcCommandDelta is close to zero, up to 1.0 for rcCommandDelta of 2.0 or more
599 // For a user jitter reduction setting of 9, the jitterAttenuator value ranges linearly
600 // from 0.1 when rcCommandDelta is close to zero, up to 1.0 for rcCommandDelta is 9.0 or more
601 // note that the jitter reduction multiplies the final smoothed value of feedforward
602 // allowing residual smooth feedforward offsets even if the sticks are not moving
603 // this is an improvement on the previous version which 'chopped' FF to zero when sticks stopped moving
604 float jitterAttenuator = ((rcCommandDeltaAbs + prevRcCommandDeltaAbs[axis]) * 0.5f + 1.0f) * pid->feedforwardJitterFactorInv;
605 jitterAttenuator = MIN(jitterAttenuator, 1.0f);
606 prevRcCommandDeltaAbs[axis] = rcCommandDeltaAbs;
608 // smooth the setpointSpeed value
609 setpointSpeed = prevSetpointSpeed[axis] + pid->feedforwardSmoothFactor * (setpointSpeed - prevSetpointSpeed[axis]);
611 // calculate setpointDelta from smoothed setpoint speed
612 setpointSpeedDelta = setpointSpeed - prevSetpointSpeed[axis];
613 prevSetpointSpeed[axis] = setpointSpeed;
615 // smooth the setpointDelta element (effectively a second order filter since incoming setpoint was already smoothed)
616 setpointSpeedDelta = prevSetpointSpeedDelta[axis] + pid->feedforwardSmoothFactor * (setpointSpeedDelta - prevSetpointSpeedDelta[axis]);
617 prevSetpointSpeedDelta[axis] = setpointSpeedDelta;
619 // apply gain factor to delta and adjust for rxRate
620 const float feedforwardBoost = setpointSpeedDelta * rxRate * pid->feedforwardBoostFactor;
622 feedforward = setpointSpeed;
624 if (axis == FD_ROLL || axis == FD_PITCH) {
625 // for pitch and roll, add feedforwardBoost to deal with motor lag
626 feedforward += feedforwardBoost;
627 // apply jitter reduction multiplier to reduce noise by attenuating when sticks move slowly
628 feedforward *= jitterAttenuator;
629 // pull feedforward back towards zero as sticks approach max if in same direction
630 // to avoid overshooting on the outwards leg of a fast roll or flip
631 if (pid->feedforwardMaxRateLimit && feedforward * setpoint > 0.0f) {
632 const float limit = (maxRcRate[axis] - fabsf(setpoint)) * pid->feedforwardMaxRateLimit;
633 feedforward = (limit > 0.0f) ? constrainf(feedforward, -limit, limit) : 0.0f;
636 } else {
637 // for yaw, apply jitter reduction only to the base feedforward delta element
638 // can't be applied to the 'sustained' element or jitter values will divide it down too much when sticks are still
639 feedforward *= jitterAttenuator;
641 // instead of adding setpoint acceleration, which is too aggressive for yaw,
642 // add a slow-fading high-pass filtered setpoint element
643 // this provides a 'sustained boost' with low noise
644 // it mimics the normal sustained yaw motor drive requirements, reducing P and I and hence reducing bounceback
645 // this doesn't add significant noise to feedforward
646 // too little yaw FF causes iTerm windup and slow bounce back when stopping a hard yaw
647 // too much causes fast bounce back when stopping a hard yaw
649 // calculate lowpass filter gain factor from user specified time constant
650 const float gain = pt1FilterGainFromDelay(pid->feedforwardYawHoldTime, rxInterval);
651 pt1FilterUpdateCutoff(&feedforwardYawHoldLpf, gain);
652 const float setpointLpfYaw = pt1FilterApply(&feedforwardYawHoldLpf, setpoint);
653 // subtract lowpass from input to get highpass of setpoint for sustained yaw 'boost'
654 const float feedforwardYawHold = pid->feedforwardYawHoldGain * (setpoint - setpointLpfYaw);
656 DEBUG_SET(DEBUG_FEEDFORWARD, 6, lrintf(feedforward * 0.01f)); // basic yaw feedforward without hold element
657 DEBUG_SET(DEBUG_FEEDFORWARD, 7, lrintf(feedforwardYawHold * 0.01f)); // yaw feedforward hold element
659 feedforward += feedforwardYawHold;
660 // NB: yaw doesn't need max rate limiting since it rarely overshoots
663 // apply feedforward transition, if configured. Archaic (better to use jitter reduction)
664 const bool useTransition = (pid->feedforwardTransition != 0.0f) && (rcDeflectionAbs[axis] < pid->feedforwardTransition);
665 if (useTransition) {
666 feedforward *= rcDeflectionAbs[axis] * pid->feedforwardTransitionInv;
669 if (axis == gyro.gyroDebugAxis) {
670 DEBUG_SET(DEBUG_FEEDFORWARD, 0, lrintf(setpoint)); // un-smoothed (raw) setpoint value used for FF
671 DEBUG_SET(DEBUG_FEEDFORWARD, 1, lrintf(setpointSpeed * 0.01f)); // smoothed and extrapolated basic feedfoward element
672 DEBUG_SET(DEBUG_FEEDFORWARD, 2, lrintf(feedforwardBoost * 0.01f)); // acceleration (boost) smoothed
673 DEBUG_SET(DEBUG_FEEDFORWARD, 3, lrintf(rcCommandDelta * 10.0f));
674 DEBUG_SET(DEBUG_FEEDFORWARD, 4, lrintf(jitterAttenuator * 100.0f)); // jitter attenuation percent
675 DEBUG_SET(DEBUG_FEEDFORWARD, 5, (int16_t)(isPrevPacketDuplicate[axis])); // previous packet was a duplicate
677 DEBUG_SET(DEBUG_FEEDFORWARD_LIMIT, 0, lrintf(jitterAttenuator * 100.0f)); // jitter attenuation factor in percent
678 DEBUG_SET(DEBUG_FEEDFORWARD_LIMIT, 1, lrintf(maxRcRate[axis])); // max Setpoint rate (badly named)
679 DEBUG_SET(DEBUG_FEEDFORWARD_LIMIT, 2, lrintf(setpoint)); // setpoint used for FF
680 DEBUG_SET(DEBUG_FEEDFORWARD_LIMIT, 3, lrintf(feedforward * 0.01f)); // un-smoothed final feedforward
683 // apply averaging to final values, for additional smoothing if needed; not shown in logs
684 if (feedforwardAveraging) {
685 feedforward = laggedMovingAverageUpdate(&feedforwardDeltaAvg[axis].filter, feedforward);
688 feedforwardRaw[axis] = feedforward;
690 #endif // USE_FEEDFORWARD
692 FAST_CODE void processRcCommand(void)
694 if (isRxDataNew) {
695 maxRcDeflectionAbs = 0.0f;
696 for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
698 float angleRate;
700 #ifdef USE_GPS_RESCUE
701 if ((axis == FD_YAW) && FLIGHT_MODE(GPS_RESCUE_MODE)) {
702 // If GPS Rescue is active then override the setpointRate used in the
703 // pid controller with the value calculated from the desired heading logic.
704 angleRate = gpsRescueGetYawRate();
705 // Treat the stick input as centered to avoid any stick deflection base modifications (like acceleration limit)
706 rcDeflection[axis] = 0;
707 rcDeflectionAbs[axis] = 0;
708 } else
709 #endif
711 // scale rcCommandf to range [-1.0, 1.0]
712 float rcCommandf;
713 if (axis == FD_YAW) {
714 rcCommandf = rcCommand[axis] / rcCommandYawDivider;
715 } else {
716 rcCommandf = rcCommand[axis] / rcCommandDivider;
718 rcDeflection[axis] = rcCommandf;
719 const float rcCommandfAbs = fabsf(rcCommandf);
720 rcDeflectionAbs[axis] = rcCommandfAbs;
721 maxRcDeflectionAbs = fmaxf(maxRcDeflectionAbs, rcCommandfAbs);
723 angleRate = applyRates(axis, rcCommandf, rcCommandfAbs);
726 rawSetpoint[axis] = constrainf(angleRate, -1.0f * currentControlRateProfile->rate_limit[axis], 1.0f * currentControlRateProfile->rate_limit[axis]);
727 DEBUG_SET(DEBUG_ANGLERATE, axis, angleRate);
729 #ifdef USE_FEEDFORWARD
730 calculateFeedforward(&pidRuntime, axis);
731 #endif // USE_FEEDFORWARD
734 // adjust unfiltered setpoint steps to camera angle (mixing Roll and Yaw)
735 if (rxConfig()->fpvCamAngleDegrees && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && !FLIGHT_MODE(HEADFREE_MODE)) {
736 scaleRawSetpointToFpvCamAngle();
740 #ifdef USE_RC_SMOOTHING_FILTER
741 processRcSmoothingFilter();
742 #endif
744 isRxDataNew = false;
747 FAST_CODE_NOINLINE void updateRcCommands(void)
749 isRxDataNew = true;
751 for (int axis = 0; axis < 3; axis++) {
752 float rc = constrainf(rcData[axis] - rxConfig()->midrc, -500.0f, 500.0f); // -500 to 500
753 float rcDeadband = 0;
754 if (axis == ROLL || axis == PITCH) {
755 rcDeadband = rcControlsConfig()->deadband;
756 } else {
757 rcDeadband = rcControlsConfig()->yaw_deadband;
758 rc *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
760 rcCommand[axis] = fapplyDeadband(rc, rcDeadband);
763 int32_t tmp;
764 if (featureIsEnabled(FEATURE_3D)) {
765 tmp = constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX);
766 tmp = (uint32_t)(tmp - PWM_RANGE_MIN);
767 } else {
768 tmp = constrain(rcData[THROTTLE], rxConfig()->mincheck, PWM_RANGE_MAX);
769 tmp = (uint32_t)(tmp - rxConfig()->mincheck) * PWM_RANGE_MIN / (PWM_RANGE_MAX - rxConfig()->mincheck);
772 if (getLowVoltageCutoff()->enabled) {
773 tmp = tmp * getLowVoltageCutoff()->percentage / 100;
776 rcCommand[THROTTLE] = rcLookupThrottle(tmp);
778 if (featureIsEnabled(FEATURE_3D) && !failsafeIsActive()) {
779 if (!flight3DConfig()->switched_mode3d) {
780 if (IS_RC_MODE_ACTIVE(BOX3D)) {
781 fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000);
782 rcCommand[THROTTLE] = rxConfig()->midrc + qMultiply(throttleScaler, PWM_RANGE_MAX - rxConfig()->midrc);
784 } else {
785 if (IS_RC_MODE_ACTIVE(BOX3D)) {
786 reverseMotors = true;
787 fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000);
788 rcCommand[THROTTLE] = rxConfig()->midrc + qMultiply(throttleScaler, PWM_RANGE_MIN - rxConfig()->midrc);
789 } else {
790 reverseMotors = false;
791 fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000);
792 rcCommand[THROTTLE] = rxConfig()->midrc + qMultiply(throttleScaler, PWM_RANGE_MAX - rxConfig()->midrc);
796 if (FLIGHT_MODE(HEADFREE_MODE)) {
797 static vector3_t rcCommandBuff;
799 rcCommandBuff.x = rcCommand[ROLL];
800 rcCommandBuff.y = rcCommand[PITCH];
801 if (!FLIGHT_MODE(ANGLE_MODE | ALT_HOLD_MODE | POS_HOLD_MODE | HORIZON_MODE | GPS_RESCUE_MODE)) {
802 rcCommandBuff.z = rcCommand[YAW];
803 } else {
804 rcCommandBuff.z = 0;
806 imuQuaternionHeadfreeTransformVectorEarthToBody(&rcCommandBuff);
807 rcCommand[ROLL] = rcCommandBuff.x;
808 rcCommand[PITCH] = rcCommandBuff.y;
809 if (!FLIGHT_MODE(ANGLE_MODE | ALT_HOLD_MODE | POS_HOLD_MODE | HORIZON_MODE | GPS_RESCUE_MODE)) {
810 rcCommand[YAW] = rcCommandBuff.z;
815 void resetYawAxis(void)
817 rcCommand[YAW] = 0;
818 setpointRate[YAW] = 0;
821 bool isMotorsReversed(void)
823 return reverseMotors;
826 void initRcProcessing(void)
828 rcCommandDivider = 500.0f - rcControlsConfig()->deadband;
829 rcCommandYawDivider = 500.0f - rcControlsConfig()->yaw_deadband;
831 for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
832 const int16_t tmp = 10 * i - currentControlRateProfile->thrMid8;
833 uint8_t y = 1;
834 if (tmp > 0)
835 y = 100 - currentControlRateProfile->thrMid8;
836 if (tmp < 0)
837 y = currentControlRateProfile->thrMid8;
838 lookupThrottleRC[i] = 10 * currentControlRateProfile->thrMid8 + tmp * (100 - currentControlRateProfile->thrExpo8 + (int32_t) currentControlRateProfile->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
839 lookupThrottleRC[i] = PWM_RANGE_MIN + PWM_RANGE * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
842 switch (currentControlRateProfile->rates_type) {
843 case RATES_TYPE_BETAFLIGHT:
844 default:
845 applyRates = applyBetaflightRates;
846 break;
847 case RATES_TYPE_RACEFLIGHT:
848 applyRates = applyRaceFlightRates;
849 break;
850 case RATES_TYPE_KISS:
851 applyRates = applyKissRates;
852 break;
853 case RATES_TYPE_ACTUAL:
854 applyRates = applyActualRates;
855 break;
856 case RATES_TYPE_QUICK:
857 applyRates = applyQuickRates;
858 break;
861 #ifdef USE_FEEDFORWARD
862 feedforwardAveraging = pidRuntime.feedforwardAveraging;
863 pt1FilterInit(&feedforwardYawHoldLpf, 0.0f);
864 #endif // USE_FEEDFORWARD
866 for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
867 maxRcRate[i] = applyRates(i, 1.0f, 1.0f);
868 #ifdef USE_FEEDFORWARD
869 feedforwardSmoothed[i] = 0.0f;
870 feedforwardRaw[i] = 0.0f;
871 if (feedforwardAveraging) {
872 laggedMovingAverageInit(&feedforwardDeltaAvg[i].filter, feedforwardAveraging + 1, (float *)&feedforwardDeltaAvg[i].buf[0]);
874 #endif // USE_FEEDFORWARD
877 #ifdef USE_YAW_SPIN_RECOVERY
878 const int maxYawRate = (int)maxRcRate[FD_YAW];
879 initYawSpinRecovery(maxYawRate);
880 #endif
883 // send rc smoothing details to blackbox
884 #ifdef USE_RC_SMOOTHING_FILTER
885 rcSmoothingFilter_t *getRcSmoothingData(void)
887 return &rcSmoothingData;
890 bool rcSmoothingInitializationComplete(void)
892 return rcSmoothingData.filterInitialized;
894 #endif // USE_RC_SMOOTHING_FILTER