Fix arming when GPS included in build but no active GNSS device attached + revert...
[betaflight.git] / src / main / fc / core.c
blobef1898bf176ec4e705d5e498e55a3566d2e2b6d4
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 <string.h>
25 #include <math.h>
27 #include "platform.h"
29 #include "blackbox/blackbox.h"
30 #include "blackbox/blackbox_fielddefs.h"
32 #include "build/debug.h"
34 #include "cli/cli.h"
36 #include "cms/cms.h"
38 #include "common/axis.h"
39 #include "common/filter.h"
40 #include "common/maths.h"
41 #include "common/utils.h"
43 #include "config/config.h"
44 #include "config/feature.h"
46 #include "drivers/dshot.h"
47 #include "drivers/dshot_command.h"
48 #include "drivers/light_led.h"
49 #include "drivers/motor.h"
50 #include "drivers/sound_beeper.h"
51 #include "drivers/system.h"
52 #include "drivers/time.h"
53 #include "drivers/transponder_ir.h"
55 #include "fc/controlrate_profile.h"
56 #include "fc/rc.h"
57 #include "fc/rc_adjustments.h"
58 #include "fc/rc_controls.h"
59 #include "fc/runtime_config.h"
60 #include "fc/stats.h"
62 #include "flight/failsafe.h"
63 #include "flight/gps_rescue.h"
65 #if defined(USE_DYN_NOTCH_FILTER)
66 #include "flight/dyn_notch_filter.h"
67 #endif
69 #include "flight/imu.h"
70 #include "flight/mixer.h"
71 #include "flight/pid.h"
72 #include "flight/position.h"
73 #include "flight/rpm_filter.h"
74 #include "flight/servos.h"
76 #include "io/beeper.h"
77 #include "io/gps.h"
78 #include "io/pidaudio.h"
79 #include "io/serial.h"
80 #include "io/statusindicator.h"
81 #include "io/transponder_ir.h"
82 #include "io/vtx_control.h"
83 #include "io/vtx_rtc6705.h"
85 #include "msp/msp_serial.h"
87 #include "osd/osd.h"
89 #include "pg/motor.h"
90 #include "pg/pg.h"
91 #include "pg/pg_ids.h"
92 #include "pg/rx.h"
94 #include "rx/rc_stats.h"
95 #include "rx/rx.h"
97 #include "scheduler/scheduler.h"
99 #include "sensors/acceleration.h"
100 #include "sensors/barometer.h"
101 #include "sensors/battery.h"
102 #include "sensors/boardalignment.h"
103 #include "sensors/compass.h"
104 #include "sensors/gyro.h"
106 #include "telemetry/telemetry.h"
108 #include "core.h"
111 enum {
112 ALIGN_GYRO = 0,
113 ALIGN_ACCEL = 1,
114 ALIGN_MAG = 2
117 enum {
118 ARMING_DELAYED_DISARMED = 0,
119 ARMING_DELAYED_NORMAL = 1,
120 ARMING_DELAYED_CRASHFLIP = 2,
121 ARMING_DELAYED_LAUNCH_CONTROL = 3,
124 #define GYRO_WATCHDOG_DELAY 80 // delay for gyro sync
126 #ifdef USE_RUNAWAY_TAKEOFF
127 #define RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD 600 // The pidSum threshold required to trigger - corresponds to a pidSum value of 60% (raw 600) in the blackbox viewer
128 #define RUNAWAY_TAKEOFF_ACTIVATE_DELAY 75000 // (75ms) Time in microseconds where pidSum is above threshold to trigger
129 #define RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT 15 // 15% - minimum stick deflection during deactivation phase
130 #define RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT 100 // 10.0% - pidSum limit during deactivation phase
131 #define RUNAWAY_TAKEOFF_GYRO_LIMIT_RP 15 // Roll/pitch 15 deg/sec threshold to prevent triggering during bench testing without props
132 #define RUNAWAY_TAKEOFF_GYRO_LIMIT_YAW 50 // Yaw 50 deg/sec threshold to prevent triggering during bench testing without props
133 #define RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT 75 // High throttle limit to accelerate deactivation (halves the deactivation delay)
135 #define DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE 0
136 #define DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY 1
137 #define DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY 2
138 #define DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME 3
140 #define DEBUG_RUNAWAY_TAKEOFF_TRUE 1
141 #define DEBUG_RUNAWAY_TAKEOFF_FALSE 0
142 #endif
144 #if defined(USE_GPS) || defined(USE_MAG)
145 int16_t magHold;
146 #endif
148 static FAST_DATA_ZERO_INIT uint8_t pidUpdateCounter;
150 static bool flipOverAfterCrashActive = false;
152 static timeUs_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
154 static int lastArmingDisabledReason = 0;
155 static timeUs_t lastDisarmTimeUs;
156 static int tryingToArm = ARMING_DELAYED_DISARMED;
158 #ifdef USE_RUNAWAY_TAKEOFF
159 static timeUs_t runawayTakeoffDeactivateUs = 0;
160 static timeUs_t runawayTakeoffAccumulatedUs = 0;
161 static bool runawayTakeoffCheckDisabled = false;
162 static timeUs_t runawayTakeoffTriggerUs = 0;
163 static bool runawayTakeoffTemporarilyDisabled = false;
164 #endif
166 #ifdef USE_LAUNCH_CONTROL
167 static launchControlState_e launchControlState = LAUNCH_CONTROL_DISABLED;
169 const char * const osdLaunchControlModeNames[] = {
170 "NORMAL",
171 "PITCHONLY",
172 "FULL"
174 #endif
176 PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0);
178 PG_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig,
179 .throttle_correction_value = 0, // could 10 with althold or 40 for fpv
180 .throttle_correction_angle = 800 // could be 80.0 deg with atlhold or 45.0 for fpv
183 static bool isCalibrating(void)
185 return (sensors(SENSOR_GYRO) && !gyroIsCalibrationComplete())
186 #ifdef USE_ACC
187 || (sensors(SENSOR_ACC) && !accIsCalibrationComplete())
188 #endif
189 #ifdef USE_BARO
190 || (sensors(SENSOR_BARO) && !baroIsCalibrated())
191 #endif
192 #ifdef USE_MAG
193 || (sensors(SENSOR_MAG) && !compassIsCalibrationComplete())
194 #endif
198 #ifdef USE_LAUNCH_CONTROL
199 bool canUseLaunchControl(void)
201 if (!isFixedWing()
202 && !isUsingSticksForArming() // require switch arming for safety
203 && IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL)
204 && (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled()) // can't use when motors are stopped
205 && !featureIsEnabled(FEATURE_3D) // pitch control is not 3D aware
206 && (flightModeFlags == 0)) { // don't want to use unless in acro mode
207 return true;
209 return false;
211 #endif
213 void resetArmingDisabled(void)
215 lastArmingDisabledReason = 0;
218 #ifdef USE_ACC
219 static bool accNeedsCalibration(void)
221 if (sensors(SENSOR_ACC)) {
223 // Check to see if the ACC has already been calibrated
224 if (accHasBeenCalibrated()) {
225 return false;
228 // We've determined that there's a detected ACC that has not
229 // yet been calibrated. Check to see if anything is using the
230 // ACC that would be affected by the lack of calibration.
232 // Check for any configured modes that use the ACC
233 if (isModeActivationConditionPresent(BOXANGLE) ||
234 isModeActivationConditionPresent(BOXHORIZON) ||
235 isModeActivationConditionPresent(BOXGPSRESCUE) ||
236 isModeActivationConditionPresent(BOXCAMSTAB) ||
237 isModeActivationConditionPresent(BOXCALIB) ||
238 isModeActivationConditionPresent(BOXACROTRAINER)) {
240 return true;
243 // Launch Control only requires the ACC if a angle limit is set
244 if (isModeActivationConditionPresent(BOXLAUNCHCONTROL) && currentPidProfile->launchControlAngleLimit) {
245 return true;
248 #ifdef USE_OSD
249 // Check for any enabled OSD elements that need the ACC
250 if (featureIsEnabled(FEATURE_OSD)) {
251 if (osdNeedsAccelerometer()) {
252 return true;
255 #endif
257 #ifdef USE_GPS_RESCUE
258 // Check if failsafe will use GPS Rescue
259 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
260 return true;
262 #endif
265 return false;
267 #endif
269 void updateArmingStatus(void)
271 if (ARMING_FLAG(ARMED)) {
272 LED0_ON;
273 } else {
274 // Check if the power on arming grace time has elapsed
275 if ((getArmingDisableFlags() & ARMING_DISABLED_BOOT_GRACE_TIME) && (millis() >= systemConfig()->powerOnArmingGraceTime * 1000)
276 #ifdef USE_DSHOT
277 // We also need to prevent arming until it's possible to send DSHOT commands.
278 // Otherwise if the initial arming is in crash-flip the motor direction commands
279 // might not be sent.
280 && (!isMotorProtocolDshot() || dshotStreamingCommandsAreEnabled())
281 #endif
283 // If so, unset the grace time arming disable flag
284 unsetArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
287 // Clear the crash flip active status
288 flipOverAfterCrashActive = false;
290 // If switch is used for arming then check it is not defaulting to on when the RX link recovers from a fault
291 if (!isUsingSticksForArming()) {
292 static bool hadRx = false;
293 const bool haveRx = rxIsReceivingSignal();
295 const bool justGotRxBack = !hadRx && haveRx;
297 if (justGotRxBack && IS_RC_MODE_ACTIVE(BOXARM)) {
298 // If the RX has just started to receive a signal again and the arm switch is on, apply arming restriction
299 setArmingDisabled(ARMING_DISABLED_NOT_DISARMED);
300 } else if (haveRx && !IS_RC_MODE_ACTIVE(BOXARM)) {
301 // If RX signal is OK and the arm switch is off, remove arming restriction
302 unsetArmingDisabled(ARMING_DISABLED_NOT_DISARMED);
305 hadRx = haveRx;
308 if (IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
309 setArmingDisabled(ARMING_DISABLED_BOXFAILSAFE);
310 } else {
311 unsetArmingDisabled(ARMING_DISABLED_BOXFAILSAFE);
314 if (calculateThrottleStatus() != THROTTLE_LOW) {
315 setArmingDisabled(ARMING_DISABLED_THROTTLE);
316 } else {
317 unsetArmingDisabled(ARMING_DISABLED_THROTTLE);
320 if (!isUpright() && !IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
321 setArmingDisabled(ARMING_DISABLED_ANGLE);
322 } else {
323 unsetArmingDisabled(ARMING_DISABLED_ANGLE);
326 if (getAverageSystemLoadPercent() > LOAD_PERCENTAGE_ONE) {
327 setArmingDisabled(ARMING_DISABLED_LOAD);
328 } else {
329 unsetArmingDisabled(ARMING_DISABLED_LOAD);
332 if (isCalibrating()) {
333 setArmingDisabled(ARMING_DISABLED_CALIBRATING);
334 } else {
335 unsetArmingDisabled(ARMING_DISABLED_CALIBRATING);
338 if (isModeActivationConditionPresent(BOXPREARM)) {
339 if (IS_RC_MODE_ACTIVE(BOXPREARM) && !ARMING_FLAG(WAS_ARMED_WITH_PREARM)) {
340 unsetArmingDisabled(ARMING_DISABLED_NOPREARM);
341 } else {
342 setArmingDisabled(ARMING_DISABLED_NOPREARM);
346 #ifdef USE_GPS_RESCUE
347 if (gpsRescueIsConfigured()) {
348 if (gpsRescueConfig()->allowArmingWithoutFix || (STATE(GPS_FIX) && (gpsSol.numSat >= gpsRescueConfig()->minSats)) ||
349 ARMING_FLAG(WAS_EVER_ARMED) || IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
350 unsetArmingDisabled(ARMING_DISABLED_GPS);
351 } else {
352 setArmingDisabled(ARMING_DISABLED_GPS);
354 if (IS_RC_MODE_ACTIVE(BOXGPSRESCUE)) {
355 setArmingDisabled(ARMING_DISABLED_RESC);
356 } else {
357 unsetArmingDisabled(ARMING_DISABLED_RESC);
360 #endif
362 #ifdef USE_DSHOT_TELEMETRY
363 // If Dshot Telemetry is enabled and any motor isn't providing telemetry, then disable arming
364 if (motorConfig()->dev.useDshotTelemetry && !isDshotTelemetryActive()) {
365 setArmingDisabled(ARMING_DISABLED_DSHOT_TELEM);
366 } else {
367 unsetArmingDisabled(ARMING_DISABLED_DSHOT_TELEM);
369 #endif
371 #ifdef USE_DSHOT_BITBANG
372 if (isDshotBitbangActive(&motorConfig()->dev) && dshotBitbangGetStatus() != DSHOT_BITBANG_STATUS_OK) {
373 setArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG);
374 } else {
375 unsetArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG);
377 #endif
379 if (IS_RC_MODE_ACTIVE(BOXPARALYZE)) {
380 setArmingDisabled(ARMING_DISABLED_PARALYZE);
383 #ifdef USE_ACC
384 if (accNeedsCalibration()) {
385 setArmingDisabled(ARMING_DISABLED_ACC_CALIBRATION);
386 } else {
387 unsetArmingDisabled(ARMING_DISABLED_ACC_CALIBRATION);
389 #endif
391 if (!isMotorProtocolEnabled()) {
392 setArmingDisabled(ARMING_DISABLED_MOTOR_PROTOCOL);
395 if (!isUsingSticksForArming()) {
396 if (!IS_RC_MODE_ACTIVE(BOXARM)) {
397 #ifdef USE_RUNAWAY_TAKEOFF
398 unsetArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF);
399 #endif
400 unsetArmingDisabled(ARMING_DISABLED_CRASH_DETECTED);
403 /* Ignore ARMING_DISABLED_CALIBRATING if we are going to calibrate gyro on first arm */
404 bool ignoreGyro = armingConfig()->gyro_cal_on_first_arm
405 && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_CALIBRATING));
407 /* Ignore ARMING_DISABLED_THROTTLE (once arm switch is on) if we are in 3D mode */
408 bool ignoreThrottle = featureIsEnabled(FEATURE_3D)
409 && !IS_RC_MODE_ACTIVE(BOX3D)
410 && !flight3DConfig()->switched_mode3d
411 && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_THROTTLE));
413 // If arming is disabled and the ARM switch is on
414 if (isArmingDisabled()
415 && !ignoreGyro
416 && !ignoreThrottle
417 && IS_RC_MODE_ACTIVE(BOXARM)) {
418 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH);
419 } else if (!IS_RC_MODE_ACTIVE(BOXARM)) {
420 unsetArmingDisabled(ARMING_DISABLED_ARM_SWITCH);
424 if (isArmingDisabled()) {
425 warningLedFlash();
426 } else {
427 warningLedDisable();
430 warningLedUpdate();
434 void disarm(flightLogDisarmReason_e reason)
436 if (ARMING_FLAG(ARMED)) {
437 if (!flipOverAfterCrashActive) {
438 ENABLE_ARMING_FLAG(WAS_EVER_ARMED);
440 DISABLE_ARMING_FLAG(ARMED);
441 lastDisarmTimeUs = micros();
443 #ifdef USE_OSD
444 if (IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) || isLaunchControlActive()) {
445 osdSuppressStats(true);
447 #endif
449 #ifdef USE_BLACKBOX
450 flightLogEvent_disarm_t eventData;
451 eventData.reason = reason;
452 blackboxLogEvent(FLIGHT_LOG_EVENT_DISARM, (flightLogEventData_t*)&eventData);
454 if (blackboxConfig()->device && blackboxConfig()->mode != BLACKBOX_MODE_ALWAYS_ON) { // Close the log upon disarm except when logging mode is ALWAYS ON
455 blackboxFinish();
457 #else
458 UNUSED(reason);
459 #endif
460 BEEP_OFF;
461 #ifdef USE_DSHOT
462 if (isMotorProtocolDshot() && flipOverAfterCrashActive && !featureIsEnabled(FEATURE_3D)) {
463 dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, DSHOT_CMD_TYPE_INLINE);
465 #endif
466 #ifdef USE_PERSISTENT_STATS
467 if (!flipOverAfterCrashActive) {
468 statsOnDisarm();
470 #endif
472 flipOverAfterCrashActive = false;
474 // if ARMING_DISABLED_RUNAWAY_TAKEOFF is set then we want to play it's beep pattern instead
475 if (!(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
476 beeper(BEEPER_DISARMING); // emit disarm tone
481 void tryArm(void)
483 if (armingConfig()->gyro_cal_on_first_arm) {
484 gyroStartCalibration(true);
487 updateArmingStatus();
489 if (!isArmingDisabled()) {
490 if (ARMING_FLAG(ARMED)) {
491 return;
494 const timeUs_t currentTimeUs = micros();
496 #ifdef USE_DSHOT
497 if (cmpTimeUs(currentTimeUs, getLastDshotBeaconCommandTimeUs()) < DSHOT_BEACON_GUARD_DELAY_US) {
498 if (tryingToArm == ARMING_DELAYED_DISARMED) {
499 if (IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
500 tryingToArm = ARMING_DELAYED_CRASHFLIP;
501 #ifdef USE_LAUNCH_CONTROL
502 } else if (canUseLaunchControl()) {
503 tryingToArm = ARMING_DELAYED_LAUNCH_CONTROL;
504 #endif
505 } else {
506 tryingToArm = ARMING_DELAYED_NORMAL;
509 return;
512 if (isMotorProtocolDshot()) {
513 #if defined(USE_ESC_SENSOR) && defined(USE_DSHOT_TELEMETRY)
514 // Try to activate extended DSHOT telemetry only if no esc sensor exists and dshot telemetry is active
515 if (!featureIsEnabled(FEATURE_ESC_SENSOR) && motorConfig()->dev.useDshotTelemetry) {
516 dshotCleanTelemetryData();
517 if (motorConfig()->dev.useDshotEdt) {
518 dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE, DSHOT_CMD_TYPE_INLINE);
521 #endif
523 if (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH)) {
524 // Set motor spin direction
525 if (!(IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) || (tryingToArm == ARMING_DELAYED_CRASHFLIP))) {
526 flipOverAfterCrashActive = false;
527 if (!featureIsEnabled(FEATURE_3D)) {
528 dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, DSHOT_CMD_TYPE_INLINE);
530 } else {
531 flipOverAfterCrashActive = true;
532 #ifdef USE_RUNAWAY_TAKEOFF
533 runawayTakeoffCheckDisabled = false;
534 #endif
535 if (!featureIsEnabled(FEATURE_3D)) {
536 dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_REVERSED, DSHOT_CMD_TYPE_INLINE);
541 #endif
543 #ifdef USE_LAUNCH_CONTROL
544 if (!flipOverAfterCrashActive && (canUseLaunchControl() || (tryingToArm == ARMING_DELAYED_LAUNCH_CONTROL))) {
545 if (launchControlState == LAUNCH_CONTROL_DISABLED) { // only activate if it hasn't already been triggered
546 launchControlState = LAUNCH_CONTROL_ACTIVE;
549 #endif
551 #ifdef USE_OSD
552 osdSuppressStats(false);
553 #endif
554 #ifdef USE_RPM_LIMIT
555 mixerResetRpmLimiter();
556 #endif
557 ENABLE_ARMING_FLAG(ARMED);
559 #ifdef USE_RC_STATS
560 NotifyRcStatsArming();
561 #endif
563 resetTryingToArm();
565 #ifdef USE_ACRO_TRAINER
566 pidAcroTrainerInit();
567 #endif // USE_ACRO_TRAINER
569 if (isModeActivationConditionPresent(BOXPREARM)) {
570 ENABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM);
572 imuQuaternionHeadfreeOffsetSet();
574 #if defined(USE_DYN_NOTCH_FILTER)
575 resetMaxFFT();
576 #endif
578 disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1e6; // start disarm timeout, will be extended when throttle is nonzero
580 lastArmingDisabledReason = 0;
582 #ifdef USE_GPS
583 //beep to indicate arming
584 if (featureIsEnabled(FEATURE_GPS)) {
585 GPS_reset_home_position();
587 if (STATE(GPS_FIX) && gpsSol.numSat >= gpsRescueConfig()->minSats) {
588 beeper(BEEPER_ARMING_GPS_FIX);
589 } else {
590 beeper(BEEPER_ARMING_GPS_NO_FIX);
592 } else {
593 beeper(BEEPER_ARMING);
595 #else
596 beeper(BEEPER_ARMING);
597 #endif
599 #ifdef USE_PERSISTENT_STATS
600 statsOnArm();
601 #endif
603 #ifdef USE_RUNAWAY_TAKEOFF
604 runawayTakeoffDeactivateUs = 0;
605 runawayTakeoffAccumulatedUs = 0;
606 runawayTakeoffTriggerUs = 0;
607 #endif
608 } else {
609 resetTryingToArm();
610 if (!isFirstArmingGyroCalibrationRunning()) {
611 int armingDisabledReason = ffs(getArmingDisableFlags());
612 if (lastArmingDisabledReason != armingDisabledReason) {
613 lastArmingDisabledReason = armingDisabledReason;
615 beeperWarningBeeps(armingDisabledReason);
621 // Automatic ACC Offset Calibration
622 bool AccInflightCalibrationArmed = false;
623 bool AccInflightCalibrationMeasurementDone = false;
624 bool AccInflightCalibrationSavetoEEProm = false;
625 bool AccInflightCalibrationActive = false;
626 uint16_t InflightcalibratingA = 0;
628 void handleInflightCalibrationStickPosition(void)
630 if (AccInflightCalibrationMeasurementDone) {
631 // trigger saving into eeprom after landing
632 AccInflightCalibrationMeasurementDone = false;
633 AccInflightCalibrationSavetoEEProm = true;
634 } else {
635 AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
636 if (AccInflightCalibrationArmed) {
637 beeper(BEEPER_ACC_CALIBRATION);
638 } else {
639 beeper(BEEPER_ACC_CALIBRATION_FAIL);
644 static void updateInflightCalibrationState(void)
646 if (AccInflightCalibrationArmed && ARMING_FLAG(ARMED) && rcData[THROTTLE] > rxConfig()->mincheck && !IS_RC_MODE_ACTIVE(BOXARM)) { // Copter is airborne and you are turning it off via boxarm : start measurement
647 InflightcalibratingA = 50;
648 AccInflightCalibrationArmed = false;
650 if (IS_RC_MODE_ACTIVE(BOXCALIB)) { // Use the Calib Option to activate : Calib = TRUE measurement started, Land and Calib = 0 measurement stored
651 if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone)
652 InflightcalibratingA = 50;
653 AccInflightCalibrationActive = true;
654 } else if (AccInflightCalibrationMeasurementDone && !ARMING_FLAG(ARMED)) {
655 AccInflightCalibrationMeasurementDone = false;
656 AccInflightCalibrationSavetoEEProm = true;
660 #if defined(USE_GPS) || defined(USE_MAG)
661 static void updateMagHold(void)
663 if (fabsf(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) {
664 int16_t dif = DECIDEGREES_TO_DEGREES(attitude.values.yaw) - magHold;
665 if (dif <= -180)
666 dif += 360;
667 if (dif >= +180)
668 dif -= 360;
669 dif *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
670 if (isUpright()) {
671 rcCommand[YAW] -= dif * currentPidProfile->pid[PID_MAG].P / 30; // 18 deg
673 } else
674 magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
676 #endif
678 #ifdef USE_VTX_CONTROL
679 static bool canUpdateVTX(void)
681 #ifdef USE_VTX_RTC6705
682 return vtxRTC6705CanUpdate();
683 #endif
684 return true;
686 #endif
688 #if defined(USE_RUNAWAY_TAKEOFF) || defined(USE_GPS_RESCUE)
689 // determine if the R/P/Y stick deflection exceeds the specified limit - integer math is good enough here.
690 bool areSticksActive(uint8_t stickPercentLimit)
692 for (int axis = FD_ROLL; axis <= FD_YAW; axis ++) {
693 if (getRcDeflectionAbs(axis) * 100.f >= stickPercentLimit) {
694 return true;
697 return false;
699 #endif
701 #ifdef USE_RUNAWAY_TAKEOFF
702 // allow temporarily disabling runaway takeoff prevention if we are connected
703 // to the configurator and the ARMING_DISABLED_MSP flag is cleared.
704 void runawayTakeoffTemporaryDisable(uint8_t disableFlag)
706 runawayTakeoffTemporarilyDisabled = disableFlag;
708 #endif
711 // calculate the throttle stick percent - integer math is good enough here.
712 // returns negative values for reversed thrust in 3D mode
713 int8_t calculateThrottlePercent(void)
715 uint8_t ret = 0;
716 int channelData = constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX);
718 if (featureIsEnabled(FEATURE_3D)
719 && !IS_RC_MODE_ACTIVE(BOX3D)
720 && !flight3DConfig()->switched_mode3d) {
722 if (channelData > (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) {
723 ret = ((channelData - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle) * 100) / (PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle);
724 } else if (channelData < (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle)) {
725 ret = -((rxConfig()->midrc - flight3DConfig()->deadband3d_throttle - channelData) * 100) / (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle - PWM_RANGE_MIN);
727 } else {
728 ret = constrain(((channelData - rxConfig()->mincheck) * 100) / (PWM_RANGE_MAX - rxConfig()->mincheck), 0, 100);
729 if (featureIsEnabled(FEATURE_3D)
730 && IS_RC_MODE_ACTIVE(BOX3D)
731 && flight3DConfig()->switched_mode3d) {
733 ret = -ret; // 3D on a switch is active
736 return ret;
739 uint8_t calculateThrottlePercentAbs(void)
741 return abs(calculateThrottlePercent());
744 static bool airmodeIsActivated;
746 bool isAirmodeActivated(void)
748 return airmodeIsActivated;
753 * processRx called from taskUpdateRxMain
755 bool processRx(timeUs_t currentTimeUs)
757 if (!calculateRxChannelsAndUpdateFailsafe(currentTimeUs)) {
758 return false;
761 updateRcRefreshRate(currentTimeUs);
763 // in 3D mode, we need to be able to disarm by switch at any time
764 if (featureIsEnabled(FEATURE_3D)) {
765 if (!IS_RC_MODE_ACTIVE(BOXARM))
766 disarm(DISARM_REASON_SWITCH);
769 updateRSSI(currentTimeUs);
771 if (currentTimeUs > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) {
772 failsafeStartMonitoring();
775 const bool throttleActive = calculateThrottleStatus() != THROTTLE_LOW;
776 const uint8_t throttlePercent = calculateThrottlePercentAbs();
777 const bool launchControlActive = isLaunchControlActive();
779 if (airmodeIsEnabled() && ARMING_FLAG(ARMED) && !launchControlActive) {
780 // once throttle exceeds activate threshold, airmode latches active until disarm
781 if (throttlePercent >= rxConfig()->airModeActivateThreshold) {
782 airmodeIsActivated = true;
784 } else {
785 airmodeIsActivated = false;
788 if (ARMING_FLAG(ARMED) && (airmodeIsActivated || throttleActive || launchControlActive || isFixedWing())) {
789 pidSetItermReset(false);
790 pidStabilisationState(PID_STABILISATION_ON);
791 } else {
792 pidSetItermReset(true);
793 pidStabilisationState(currentPidProfile->pidAtMinThrottle ? PID_STABILISATION_ON : PID_STABILISATION_OFF);
796 #ifdef USE_RUNAWAY_TAKEOFF
797 // If runaway_takeoff_prevention is enabled, accumulate the amount of time that throttle
798 // is above runaway_takeoff_deactivate_throttle with the any of the R/P/Y sticks deflected
799 // to at least runaway_takeoff_stick_percent percent while the pidSum on all axis is kept low.
800 // Once the amount of accumulated time exceeds runaway_takeoff_deactivate_delay then disable
801 // prevention for the remainder of the battery.
803 if (ARMING_FLAG(ARMED)
804 && pidConfig()->runaway_takeoff_prevention
805 && !runawayTakeoffCheckDisabled
806 && !flipOverAfterCrashActive
807 && !runawayTakeoffTemporarilyDisabled
808 && !isFixedWing()) {
810 // Determine if we're in "flight"
811 // - motors running
812 // - throttle over runaway_takeoff_deactivate_throttle_percent
813 // - sticks are active and have deflection greater than runaway_takeoff_deactivate_stick_percent
814 // - pidSum on all axis is less then runaway_takeoff_deactivate_pidlimit
815 bool inStableFlight = false;
816 if (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled() || throttleActive) { // are motors running?
817 const uint8_t lowThrottleLimit = pidConfig()->runaway_takeoff_deactivate_throttle;
818 const uint8_t midThrottleLimit = constrain(lowThrottleLimit * 2, lowThrottleLimit * 2, RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT);
819 if ((((throttlePercent >= lowThrottleLimit) && areSticksActive(RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT)) || (throttlePercent >= midThrottleLimit))
820 && (fabsf(pidData[FD_PITCH].Sum) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT)
821 && (fabsf(pidData[FD_ROLL].Sum) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT)
822 && (fabsf(pidData[FD_YAW].Sum) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT)) {
824 inStableFlight = true;
825 if (runawayTakeoffDeactivateUs == 0) {
826 runawayTakeoffDeactivateUs = currentTimeUs;
831 // If we're in flight, then accumulate the time and deactivate once it exceeds runaway_takeoff_deactivate_delay milliseconds
832 if (inStableFlight) {
833 if (runawayTakeoffDeactivateUs == 0) {
834 runawayTakeoffDeactivateUs = currentTimeUs;
836 uint16_t deactivateDelay = pidConfig()->runaway_takeoff_deactivate_delay;
837 // at high throttle levels reduce deactivation delay by 50%
838 if (throttlePercent >= RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT) {
839 deactivateDelay = deactivateDelay / 2;
841 if ((cmpTimeUs(currentTimeUs, runawayTakeoffDeactivateUs) + runawayTakeoffAccumulatedUs) > deactivateDelay * 1000) {
842 runawayTakeoffCheckDisabled = true;
845 } else {
846 if (runawayTakeoffDeactivateUs != 0) {
847 runawayTakeoffAccumulatedUs += cmpTimeUs(currentTimeUs, runawayTakeoffDeactivateUs);
849 runawayTakeoffDeactivateUs = 0;
851 if (runawayTakeoffDeactivateUs == 0) {
852 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY, DEBUG_RUNAWAY_TAKEOFF_FALSE);
853 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME, runawayTakeoffAccumulatedUs / 1000);
854 } else {
855 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY, DEBUG_RUNAWAY_TAKEOFF_TRUE);
856 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME, (cmpTimeUs(currentTimeUs, runawayTakeoffDeactivateUs) + runawayTakeoffAccumulatedUs) / 1000);
858 } else {
859 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY, DEBUG_RUNAWAY_TAKEOFF_FALSE);
860 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME, DEBUG_RUNAWAY_TAKEOFF_FALSE);
862 #endif
864 #ifdef USE_LAUNCH_CONTROL
865 if (ARMING_FLAG(ARMED)) {
866 if (launchControlActive && (throttlePercent > currentPidProfile->launchControlThrottlePercent)) {
867 // throttle limit trigger reached, launch triggered
868 // reset the iterms as they may be at high values from holding the launch position
869 launchControlState = LAUNCH_CONTROL_TRIGGERED;
870 pidResetIterm();
872 } else {
873 if (launchControlState == LAUNCH_CONTROL_TRIGGERED) {
874 // If trigger mode is MULTIPLE then reset the state when disarmed
875 // and the mode switch is turned off.
876 // For trigger mode SINGLE we never reset the state and only a single
877 // launch is allowed until a reboot.
878 if (currentPidProfile->launchControlAllowTriggerReset && !IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL)) {
879 launchControlState = LAUNCH_CONTROL_DISABLED;
881 } else {
882 launchControlState = LAUNCH_CONTROL_DISABLED;
885 #endif
887 return true;
890 void processRxModes(timeUs_t currentTimeUs)
892 static bool armedBeeperOn = false;
893 #ifdef USE_TELEMETRY
894 static bool sharedPortTelemetryEnabled = false;
895 #endif
896 const throttleStatus_e throttleStatus = calculateThrottleStatus();
898 // When armed and motors aren't spinning, do beeps and then disarm
899 // board after delay so users without buzzer won't lose fingers.
900 // mixTable constrains motor commands, so checking throttleStatus is enough
901 const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6;
902 if (ARMING_FLAG(ARMED)
903 && featureIsEnabled(FEATURE_MOTOR_STOP)
904 && !isFixedWing()
905 && !featureIsEnabled(FEATURE_3D)
906 && !airmodeIsEnabled()
907 && !FLIGHT_MODE(GPS_RESCUE_MODE) // disable auto-disarm when GPS Rescue is active
909 if (isUsingSticksForArming()) {
910 if (throttleStatus == THROTTLE_LOW) {
911 if ((autoDisarmDelayUs > 0) && (currentTimeUs > disarmAt)) {
912 // auto-disarm configured and delay is over
913 disarm(DISARM_REASON_THROTTLE_TIMEOUT);
914 armedBeeperOn = false;
915 } else {
916 // still armed; do warning beeps while armed
917 beeper(BEEPER_ARMED);
918 armedBeeperOn = true;
920 } else {
921 // throttle is not low - extend disarm time
922 disarmAt = currentTimeUs + autoDisarmDelayUs;
924 if (armedBeeperOn) {
925 beeperSilence();
926 armedBeeperOn = false;
929 } else {
930 // arming is via AUX switch; beep while throttle low
931 if (throttleStatus == THROTTLE_LOW) {
932 beeper(BEEPER_ARMED);
933 armedBeeperOn = true;
934 } else if (armedBeeperOn) {
935 beeperSilence();
936 armedBeeperOn = false;
939 } else {
940 disarmAt = currentTimeUs + autoDisarmDelayUs; // extend auto-disarm timer
943 if (!(IS_RC_MODE_ACTIVE(BOXPARALYZE) && !ARMING_FLAG(ARMED))
944 #ifdef USE_CMS
945 && !cmsInMenu
946 #endif
948 processRcStickPositions();
951 if (featureIsEnabled(FEATURE_INFLIGHT_ACC_CAL)) {
952 updateInflightCalibrationState();
955 updateActivatedModes();
957 #ifdef USE_DSHOT
958 /* Enable beep warning when the crash flip mode is active */
959 if (flipOverAfterCrashActive) {
960 beeper(BEEPER_CRASH_FLIP_MODE);
962 #endif
964 if (!cliMode && !(IS_RC_MODE_ACTIVE(BOXPARALYZE) && !ARMING_FLAG(ARMED))) {
965 processRcAdjustments(currentControlRateProfile);
968 bool canUseHorizonMode = true;
969 if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeIsActive()) && (sensors(SENSOR_ACC))) {
970 // bumpless transfer to Level mode
971 canUseHorizonMode = false;
973 if (!FLIGHT_MODE(ANGLE_MODE)) {
974 ENABLE_FLIGHT_MODE(ANGLE_MODE);
976 } else {
977 DISABLE_FLIGHT_MODE(ANGLE_MODE); // failsafe support
980 if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
982 DISABLE_FLIGHT_MODE(ANGLE_MODE);
984 if (!FLIGHT_MODE(HORIZON_MODE)) {
985 ENABLE_FLIGHT_MODE(HORIZON_MODE);
987 } else {
988 DISABLE_FLIGHT_MODE(HORIZON_MODE);
991 #ifdef USE_GPS_RESCUE
992 if (ARMING_FLAG(ARMED) && (IS_RC_MODE_ACTIVE(BOXGPSRESCUE) || (failsafeIsActive() && failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE))) {
993 if (!FLIGHT_MODE(GPS_RESCUE_MODE)) {
994 ENABLE_FLIGHT_MODE(GPS_RESCUE_MODE);
996 } else {
997 DISABLE_FLIGHT_MODE(GPS_RESCUE_MODE);
999 #endif
1001 if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
1002 LED1_ON;
1003 // increase frequency of attitude task to reduce drift when in angle or horizon mode
1004 rescheduleTask(TASK_ATTITUDE, TASK_PERIOD_HZ(acc.sampleRateHz / (float)imuConfig()->imu_process_denom));
1005 } else {
1006 LED1_OFF;
1007 rescheduleTask(TASK_ATTITUDE, TASK_PERIOD_HZ(100));
1010 if (!IS_RC_MODE_ACTIVE(BOXPREARM) && ARMING_FLAG(WAS_ARMED_WITH_PREARM)) {
1011 DISABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM);
1014 #if defined(USE_ACC) || defined(USE_MAG)
1015 if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
1016 #if defined(USE_GPS) || defined(USE_MAG)
1017 if (IS_RC_MODE_ACTIVE(BOXMAG)) {
1018 if (!FLIGHT_MODE(MAG_MODE)) {
1019 ENABLE_FLIGHT_MODE(MAG_MODE);
1020 magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
1022 } else {
1023 DISABLE_FLIGHT_MODE(MAG_MODE);
1025 #endif
1026 if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && !FLIGHT_MODE(GPS_RESCUE_MODE)) {
1027 if (!FLIGHT_MODE(HEADFREE_MODE)) {
1028 ENABLE_FLIGHT_MODE(HEADFREE_MODE);
1030 } else {
1031 DISABLE_FLIGHT_MODE(HEADFREE_MODE);
1033 if (IS_RC_MODE_ACTIVE(BOXHEADADJ) && !FLIGHT_MODE(GPS_RESCUE_MODE)) {
1034 if (imuQuaternionHeadfreeOffsetSet()) {
1035 beeper(BEEPER_RX_SET);
1039 #endif
1041 if (IS_RC_MODE_ACTIVE(BOXPASSTHRU)) {
1042 ENABLE_FLIGHT_MODE(PASSTHRU_MODE);
1043 } else {
1044 DISABLE_FLIGHT_MODE(PASSTHRU_MODE);
1047 if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE) {
1048 DISABLE_FLIGHT_MODE(HEADFREE_MODE);
1051 #ifdef USE_TELEMETRY
1052 if (featureIsEnabled(FEATURE_TELEMETRY)) {
1053 bool enableSharedPortTelemetry = (!isModeActivationConditionPresent(BOXTELEMETRY) && ARMING_FLAG(ARMED)) || (isModeActivationConditionPresent(BOXTELEMETRY) && IS_RC_MODE_ACTIVE(BOXTELEMETRY));
1054 if (enableSharedPortTelemetry && !sharedPortTelemetryEnabled) {
1055 mspSerialReleaseSharedTelemetryPorts();
1056 telemetryCheckState();
1058 sharedPortTelemetryEnabled = true;
1059 } else if (!enableSharedPortTelemetry && sharedPortTelemetryEnabled) {
1060 // the telemetry state must be checked immediately so that shared serial ports are released.
1061 telemetryCheckState();
1062 mspSerialAllocatePorts();
1064 sharedPortTelemetryEnabled = false;
1067 #endif
1069 #ifdef USE_VTX_CONTROL
1070 vtxUpdateActivatedChannel();
1072 if (canUpdateVTX()) {
1073 handleVTXControlButton();
1075 #endif
1077 #ifdef USE_ACRO_TRAINER
1078 pidSetAcroTrainerState(IS_RC_MODE_ACTIVE(BOXACROTRAINER) && sensors(SENSOR_ACC));
1079 #endif // USE_ACRO_TRAINER
1081 #ifdef USE_RC_SMOOTHING_FILTER
1082 if (ARMING_FLAG(ARMED) && !rcSmoothingInitializationComplete() && rxConfig()->rc_smoothing_mode) {
1083 beeper(BEEPER_RC_SMOOTHING_INIT_FAIL);
1085 #endif
1087 pidSetAntiGravityState(IS_RC_MODE_ACTIVE(BOXANTIGRAVITY) || featureIsEnabled(FEATURE_ANTI_GRAVITY));
1090 static FAST_CODE_NOINLINE void subTaskPidController(timeUs_t currentTimeUs)
1092 uint32_t startTime = 0;
1093 if (debugMode == DEBUG_PIDLOOP) {startTime = micros();}
1094 // PID - note this is function pointer set by setPIDController()
1095 pidController(currentPidProfile, currentTimeUs);
1096 DEBUG_SET(DEBUG_PIDLOOP, 1, micros() - startTime);
1098 #ifdef USE_RUNAWAY_TAKEOFF
1099 // Check to see if runaway takeoff detection is active (anti-taz), the pidSum is over the threshold,
1100 // and gyro rate for any axis is above the limit for at least the activate delay period.
1101 // If so, disarm for safety
1102 if (ARMING_FLAG(ARMED)
1103 && !isFixedWing()
1104 && pidConfig()->runaway_takeoff_prevention
1105 && !runawayTakeoffCheckDisabled
1106 && !flipOverAfterCrashActive
1107 && !runawayTakeoffTemporarilyDisabled
1108 && !FLIGHT_MODE(GPS_RESCUE_MODE) // disable Runaway Takeoff triggering if GPS Rescue is active
1109 && (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled() || (calculateThrottleStatus() != THROTTLE_LOW))) {
1111 if (((fabsf(pidData[FD_PITCH].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD)
1112 || (fabsf(pidData[FD_ROLL].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD)
1113 || (fabsf(pidData[FD_YAW].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD))
1114 && ((gyroAbsRateDps(FD_PITCH) > RUNAWAY_TAKEOFF_GYRO_LIMIT_RP)
1115 || (gyroAbsRateDps(FD_ROLL) > RUNAWAY_TAKEOFF_GYRO_LIMIT_RP)
1116 || (gyroAbsRateDps(FD_YAW) > RUNAWAY_TAKEOFF_GYRO_LIMIT_YAW))) {
1118 if (runawayTakeoffTriggerUs == 0) {
1119 runawayTakeoffTriggerUs = currentTimeUs + RUNAWAY_TAKEOFF_ACTIVATE_DELAY;
1120 } else if (currentTimeUs > runawayTakeoffTriggerUs) {
1121 setArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF);
1122 disarm(DISARM_REASON_RUNAWAY_TAKEOFF);
1124 } else {
1125 runawayTakeoffTriggerUs = 0;
1127 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE, DEBUG_RUNAWAY_TAKEOFF_TRUE);
1128 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY, runawayTakeoffTriggerUs == 0 ? DEBUG_RUNAWAY_TAKEOFF_FALSE : DEBUG_RUNAWAY_TAKEOFF_TRUE);
1129 } else {
1130 runawayTakeoffTriggerUs = 0;
1131 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE, DEBUG_RUNAWAY_TAKEOFF_FALSE);
1132 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF, DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY, DEBUG_RUNAWAY_TAKEOFF_FALSE);
1134 #endif
1137 #ifdef USE_PID_AUDIO
1138 if (isModeActivationConditionPresent(BOXPIDAUDIO)) {
1139 pidAudioUpdate();
1141 #endif
1144 static FAST_CODE_NOINLINE void subTaskPidSubprocesses(timeUs_t currentTimeUs)
1146 uint32_t startTime = 0;
1147 if (debugMode == DEBUG_PIDLOOP) {
1148 startTime = micros();
1151 #if defined(USE_GPS) || defined(USE_MAG)
1152 if (sensors(SENSOR_GPS) || sensors(SENSOR_MAG)) {
1153 updateMagHold();
1155 #endif
1157 #ifdef USE_BLACKBOX
1158 if (!cliMode && blackboxConfig()->device) {
1159 blackboxUpdate(currentTimeUs);
1161 #else
1162 UNUSED(currentTimeUs);
1163 #endif
1165 DEBUG_SET(DEBUG_PIDLOOP, 3, micros() - startTime);
1168 #ifdef USE_TELEMETRY
1169 #define GYRO_TEMP_READ_DELAY_US 3e6 // Only read the gyro temp every 3 seconds
1170 void subTaskTelemetryPollSensors(timeUs_t currentTimeUs)
1172 static timeUs_t lastGyroTempTimeUs = 0;
1174 if (cmpTimeUs(currentTimeUs, lastGyroTempTimeUs) >= GYRO_TEMP_READ_DELAY_US) {
1175 // Read out gyro temperature if used for telemmetry
1176 gyroReadTemperature();
1177 lastGyroTempTimeUs = currentTimeUs;
1180 #endif
1182 static FAST_CODE void subTaskMotorUpdate(timeUs_t currentTimeUs)
1184 uint32_t startTime = 0;
1185 if (debugMode == DEBUG_CYCLETIME) {
1186 startTime = micros();
1187 static uint32_t previousMotorUpdateTime;
1188 const uint32_t currentDeltaTime = startTime - previousMotorUpdateTime;
1189 debug[2] = currentDeltaTime;
1190 debug[3] = currentDeltaTime - targetPidLooptime;
1191 previousMotorUpdateTime = startTime;
1192 } else if (debugMode == DEBUG_PIDLOOP) {
1193 startTime = micros();
1196 mixTable(currentTimeUs);
1198 #ifdef USE_SERVOS
1199 // motor outputs are used as sources for servo mixing, so motors must be calculated using mixTable() before servos.
1200 if (isMixerUsingServos()) {
1201 writeServos();
1203 #endif
1205 writeMotors();
1207 #ifdef USE_DSHOT_TELEMETRY_STATS
1208 if (debugMode == DEBUG_DSHOT_RPM_ERRORS && useDshotTelemetry) {
1209 const uint8_t motorCount = MIN(getMotorCount(), 4);
1210 for (uint8_t i = 0; i < motorCount; i++) {
1211 debug[i] = getDshotTelemetryMotorInvalidPercent(i);
1214 #endif
1216 DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime);
1219 static FAST_CODE_NOINLINE void subTaskRcCommand(timeUs_t currentTimeUs)
1221 UNUSED(currentTimeUs);
1223 // If we're armed, at minimum throttle, and we do arming via the
1224 // sticks, do not process yaw input from the rx. We do this so the
1225 // motors do not spin up while we are trying to arm or disarm.
1226 // Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
1227 if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck
1228 #ifndef USE_QUAD_MIXER_ONLY
1229 #ifdef USE_SERVOS
1230 && !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoConfig()->tri_unarmed_servo)
1231 #endif
1232 && mixerConfig()->mixerMode != MIXER_AIRPLANE
1233 && mixerConfig()->mixerMode != MIXER_FLYING_WING
1234 #endif
1236 resetYawAxis();
1239 processRcCommand();
1242 FAST_CODE void taskGyroSample(timeUs_t currentTimeUs)
1244 UNUSED(currentTimeUs);
1245 gyroUpdate();
1246 if (pidUpdateCounter % activePidLoopDenom == 0) {
1247 pidUpdateCounter = 0;
1249 pidUpdateCounter++;
1252 FAST_CODE bool gyroFilterReady(void)
1254 if (pidUpdateCounter % activePidLoopDenom == 0) {
1255 return true;
1256 } else {
1257 return false;
1261 FAST_CODE bool pidLoopReady(void)
1263 if ((pidUpdateCounter % activePidLoopDenom) == (activePidLoopDenom / 2)) {
1264 return true;
1266 return false;
1269 FAST_CODE void taskFiltering(timeUs_t currentTimeUs)
1271 #ifdef USE_DSHOT_TELEMETRY
1272 updateDshotTelemetry(); // decode and update Dshot telemetry
1273 #endif
1274 gyroFiltering(currentTimeUs);
1277 // Function for loop trigger
1278 FAST_CODE void taskMainPidLoop(timeUs_t currentTimeUs)
1281 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_GYROPID_SYNC)
1282 if (lockMainPID() != 0) return;
1283 #endif
1285 // DEBUG_PIDLOOP, timings for:
1286 // 0 - gyroUpdate()
1287 // 1 - subTaskPidController()
1288 // 2 - subTaskMotorUpdate()
1289 // 3 - subTaskPidSubprocesses()
1290 DEBUG_SET(DEBUG_PIDLOOP, 0, micros() - currentTimeUs);
1292 subTaskRcCommand(currentTimeUs);
1293 subTaskPidController(currentTimeUs);
1294 subTaskMotorUpdate(currentTimeUs);
1295 subTaskPidSubprocesses(currentTimeUs);
1297 DEBUG_SET(DEBUG_CYCLETIME, 0, getTaskDeltaTimeUs(TASK_SELF));
1298 DEBUG_SET(DEBUG_CYCLETIME, 1, getAverageSystemLoadPercent());
1301 bool isFlipOverAfterCrashActive(void)
1303 return flipOverAfterCrashActive;
1306 timeUs_t getLastDisarmTimeUs(void)
1308 return lastDisarmTimeUs;
1311 bool isTryingToArm(void)
1313 return (tryingToArm != ARMING_DELAYED_DISARMED);
1316 void resetTryingToArm(void)
1318 tryingToArm = ARMING_DELAYED_DISARMED;
1321 bool isLaunchControlActive(void)
1323 #ifdef USE_LAUNCH_CONTROL
1324 return launchControlState == LAUNCH_CONTROL_ACTIVE;
1325 #else
1326 return false;
1327 #endif