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/>.
28 #include "blackbox/blackbox.h"
29 #include "blackbox/blackbox_fielddefs.h"
31 #include "build/debug.h"
37 #include "common/axis.h"
38 #include "common/filter.h"
39 #include "common/maths.h"
40 #include "common/utils.h"
42 #include "config/config.h"
43 #include "config/feature.h"
45 #include "drivers/dshot.h"
46 #include "drivers/dshot_command.h"
47 #include "drivers/light_led.h"
48 #include "drivers/motor.h"
49 #include "drivers/sound_beeper.h"
50 #include "drivers/system.h"
51 #include "drivers/time.h"
52 #include "drivers/transponder_ir.h"
54 #include "fc/controlrate_profile.h"
56 #include "fc/rc_adjustments.h"
57 #include "fc/rc_controls.h"
58 #include "fc/runtime_config.h"
61 #include "flight/failsafe.h"
62 #include "flight/gps_rescue.h"
64 #if defined(USE_GYRO_DATA_ANALYSE)
65 #include "flight/gyroanalyse.h"
68 #include "flight/imu.h"
69 #include "flight/mixer.h"
70 #include "flight/pid.h"
71 #include "flight/position.h"
72 #include "flight/rpm_filter.h"
73 #include "flight/servos.h"
75 #include "io/beeper.h"
77 #include "io/pidaudio.h"
78 #include "io/serial.h"
79 #include "io/servos.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"
91 #include "pg/pg_ids.h"
96 #include "scheduler/scheduler.h"
98 #include "sensors/acceleration.h"
99 #include "sensors/barometer.h"
100 #include "sensors/battery.h"
101 #include "sensors/boardalignment.h"
102 #include "sensors/compass.h"
103 #include "sensors/gyro.h"
105 #include "telemetry/telemetry.h"
117 ARMING_DELAYED_DISARMED
= 0,
118 ARMING_DELAYED_NORMAL
= 1,
119 ARMING_DELAYED_CRASHFLIP
= 2,
120 ARMING_DELAYED_LAUNCH_CONTROL
= 3,
123 #define GYRO_WATCHDOG_DELAY 80 // delay for gyro sync
125 #ifdef USE_RUNAWAY_TAKEOFF
126 #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
127 #define RUNAWAY_TAKEOFF_ACTIVATE_DELAY 75000 // (75ms) Time in microseconds where pidSum is above threshold to trigger
128 #define RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT 15 // 15% - minimum stick deflection during deactivation phase
129 #define RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT 100 // 10.0% - pidSum limit during deactivation phase
130 #define RUNAWAY_TAKEOFF_GYRO_LIMIT_RP 15 // Roll/pitch 15 deg/sec threshold to prevent triggering during bench testing without props
131 #define RUNAWAY_TAKEOFF_GYRO_LIMIT_YAW 50 // Yaw 50 deg/sec threshold to prevent triggering during bench testing without props
132 #define RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT 75 // High throttle limit to accelerate deactivation (halves the deactivation delay)
134 #define DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE 0
135 #define DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY 1
136 #define DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY 2
137 #define DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME 3
139 #define DEBUG_RUNAWAY_TAKEOFF_TRUE 1
140 #define DEBUG_RUNAWAY_TAKEOFF_FALSE 0
143 #if defined(USE_GPS) || defined(USE_MAG)
147 static FAST_DATA_ZERO_INIT
uint8_t pidUpdateCounter
;
149 static bool flipOverAfterCrashActive
= false;
151 static timeUs_t disarmAt
; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
153 static int lastArmingDisabledReason
= 0;
154 static timeUs_t lastDisarmTimeUs
;
155 static int tryingToArm
= ARMING_DELAYED_DISARMED
;
157 #ifdef USE_RUNAWAY_TAKEOFF
158 static timeUs_t runawayTakeoffDeactivateUs
= 0;
159 static timeUs_t runawayTakeoffAccumulatedUs
= 0;
160 static bool runawayTakeoffCheckDisabled
= false;
161 static timeUs_t runawayTakeoffTriggerUs
= 0;
162 static bool runawayTakeoffTemporarilyDisabled
= false;
165 #ifdef USE_LAUNCH_CONTROL
166 static launchControlState_e launchControlState
= LAUNCH_CONTROL_DISABLED
;
168 const char * const osdLaunchControlModeNames
[] = {
175 PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t
, throttleCorrectionConfig
, PG_THROTTLE_CORRECTION_CONFIG
, 0);
177 PG_RESET_TEMPLATE(throttleCorrectionConfig_t
, throttleCorrectionConfig
,
178 .throttle_correction_value
= 0, // could 10 with althold or 40 for fpv
179 .throttle_correction_angle
= 800 // could be 80.0 deg with atlhold or 45.0 for fpv
182 static bool isCalibrating(void)
184 return (sensors(SENSOR_GYRO
) && !gyroIsCalibrationComplete())
186 || (sensors(SENSOR_ACC
) && !accIsCalibrationComplete())
189 || (sensors(SENSOR_BARO
) && !baroIsCalibrationComplete())
192 || (sensors(SENSOR_MAG
) && !compassIsCalibrationComplete())
197 #ifdef USE_LAUNCH_CONTROL
198 bool canUseLaunchControl(void)
201 && !isUsingSticksForArming() // require switch arming for safety
202 && IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL
)
203 && (!featureIsEnabled(FEATURE_MOTOR_STOP
) || airmodeIsEnabled()) // can't use when motors are stopped
204 && !featureIsEnabled(FEATURE_3D
) // pitch control is not 3D aware
205 && (flightModeFlags
== 0)) { // don't want to use unless in acro mode
212 void resetArmingDisabled(void)
214 lastArmingDisabledReason
= 0;
218 static bool accNeedsCalibration(void)
220 if (sensors(SENSOR_ACC
)) {
222 // Check to see if the ACC has already been calibrated
223 if (accHasBeenCalibrated()) {
227 // We've determined that there's a detected ACC that has not
228 // yet been calibrated. Check to see if anything is using the
229 // ACC that would be affected by the lack of calibration.
231 // Check for any configured modes that use the ACC
232 if (isModeActivationConditionPresent(BOXANGLE
) ||
233 isModeActivationConditionPresent(BOXHORIZON
) ||
234 isModeActivationConditionPresent(BOXGPSRESCUE
) ||
235 isModeActivationConditionPresent(BOXCAMSTAB
) ||
236 isModeActivationConditionPresent(BOXCALIB
) ||
237 isModeActivationConditionPresent(BOXACROTRAINER
)) {
242 // Launch Control only requires the ACC if a angle limit is set
243 if (isModeActivationConditionPresent(BOXLAUNCHCONTROL
) && currentPidProfile
->launchControlAngleLimit
) {
248 // Check for any enabled OSD elements that need the ACC
249 if (featureIsEnabled(FEATURE_OSD
)) {
250 if (osdNeedsAccelerometer()) {
256 #ifdef USE_GPS_RESCUE
257 // Check if failsafe will use GPS Rescue
258 if (failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_GPS_RESCUE
) {
268 void updateArmingStatus(void)
270 if (ARMING_FLAG(ARMED
)) {
273 // Check if the power on arming grace time has elapsed
274 if ((getArmingDisableFlags() & ARMING_DISABLED_BOOT_GRACE_TIME
) && (millis() >= systemConfig()->powerOnArmingGraceTime
* 1000)
276 // We also need to prevent arming until it's possible to send DSHOT commands.
277 // Otherwise if the initial arming is in crash-flip the motor direction commands
278 // might not be sent.
279 && (!isMotorProtocolDshot() || dshotStreamingCommandsAreEnabled())
282 // If so, unset the grace time arming disable flag
283 unsetArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME
);
286 // Clear the crash flip active status
287 flipOverAfterCrashActive
= false;
289 // If switch is used for arming then check it is not defaulting to on when the RX link recovers from a fault
290 if (!isUsingSticksForArming()) {
291 static bool hadRx
= false;
292 const bool haveRx
= rxIsReceivingSignal();
294 const bool justGotRxBack
= !hadRx
&& haveRx
;
296 if (justGotRxBack
&& IS_RC_MODE_ACTIVE(BOXARM
)) {
297 // If the RX has just started to receive a signal again and the arm switch is on, apply arming restriction
298 setArmingDisabled(ARMING_DISABLED_BAD_RX_RECOVERY
);
299 } else if (haveRx
&& !IS_RC_MODE_ACTIVE(BOXARM
)) {
300 // If RX signal is OK and the arm switch is off, remove arming restriction
301 unsetArmingDisabled(ARMING_DISABLED_BAD_RX_RECOVERY
);
307 if (IS_RC_MODE_ACTIVE(BOXFAILSAFE
)) {
308 setArmingDisabled(ARMING_DISABLED_BOXFAILSAFE
);
310 unsetArmingDisabled(ARMING_DISABLED_BOXFAILSAFE
);
313 if (calculateThrottleStatus() != THROTTLE_LOW
) {
314 setArmingDisabled(ARMING_DISABLED_THROTTLE
);
316 unsetArmingDisabled(ARMING_DISABLED_THROTTLE
);
319 if (!isUpright() && !IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH
)) {
320 setArmingDisabled(ARMING_DISABLED_ANGLE
);
322 unsetArmingDisabled(ARMING_DISABLED_ANGLE
);
325 if (getAverageSystemLoadPercent() > LOAD_PERCENTAGE_ONE
) {
326 setArmingDisabled(ARMING_DISABLED_LOAD
);
328 unsetArmingDisabled(ARMING_DISABLED_LOAD
);
331 if (isCalibrating()) {
332 setArmingDisabled(ARMING_DISABLED_CALIBRATING
);
334 unsetArmingDisabled(ARMING_DISABLED_CALIBRATING
);
337 if (isModeActivationConditionPresent(BOXPREARM
)) {
338 if (IS_RC_MODE_ACTIVE(BOXPREARM
) && !ARMING_FLAG(WAS_ARMED_WITH_PREARM
)) {
339 unsetArmingDisabled(ARMING_DISABLED_NOPREARM
);
341 setArmingDisabled(ARMING_DISABLED_NOPREARM
);
345 #ifdef USE_GPS_RESCUE
346 if (gpsRescueIsConfigured()) {
347 if (gpsRescueConfig()->allowArmingWithoutFix
|| STATE(GPS_FIX
) || ARMING_FLAG(WAS_EVER_ARMED
) || IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH
)) {
348 unsetArmingDisabled(ARMING_DISABLED_GPS
);
350 setArmingDisabled(ARMING_DISABLED_GPS
);
352 if (IS_RC_MODE_ACTIVE(BOXGPSRESCUE
)) {
353 setArmingDisabled(ARMING_DISABLED_RESC
);
355 unsetArmingDisabled(ARMING_DISABLED_RESC
);
360 #ifdef USE_RPM_FILTER
361 // USE_RPM_FILTER will only be defined if USE_DSHOT and USE_DSHOT_TELEMETRY are defined
362 // If the RPM filter is anabled and any motor isn't providing telemetry, then disable arming
363 if (isRpmFilterEnabled() && !isDshotTelemetryActive()) {
364 setArmingDisabled(ARMING_DISABLED_RPMFILTER
);
366 unsetArmingDisabled(ARMING_DISABLED_RPMFILTER
);
370 #ifdef USE_DSHOT_BITBANG
371 if (isDshotBitbangActive(&motorConfig()->dev
) && dshotBitbangGetStatus() != DSHOT_BITBANG_STATUS_OK
) {
372 setArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG
);
374 unsetArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG
);
378 if (IS_RC_MODE_ACTIVE(BOXPARALYZE
)) {
379 setArmingDisabled(ARMING_DISABLED_PARALYZE
);
383 if (accNeedsCalibration()) {
384 setArmingDisabled(ARMING_DISABLED_ACC_CALIBRATION
);
386 unsetArmingDisabled(ARMING_DISABLED_ACC_CALIBRATION
);
390 if (!isMotorProtocolEnabled()) {
391 setArmingDisabled(ARMING_DISABLED_MOTOR_PROTOCOL
);
394 if (!isUsingSticksForArming()) {
395 if (!IS_RC_MODE_ACTIVE(BOXARM
)) {
396 #ifdef USE_RUNAWAY_TAKEOFF
397 unsetArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF
);
399 unsetArmingDisabled(ARMING_DISABLED_CRASH_DETECTED
);
402 /* Ignore ARMING_DISABLED_CALIBRATING if we are going to calibrate gyro on first arm */
403 bool ignoreGyro
= armingConfig()->gyro_cal_on_first_arm
404 && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH
| ARMING_DISABLED_CALIBRATING
));
406 /* Ignore ARMING_DISABLED_THROTTLE (once arm switch is on) if we are in 3D mode */
407 bool ignoreThrottle
= featureIsEnabled(FEATURE_3D
)
408 && !IS_RC_MODE_ACTIVE(BOX3D
)
409 && !flight3DConfig()->switched_mode3d
410 && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH
| ARMING_DISABLED_THROTTLE
));
412 // If arming is disabled and the ARM switch is on
413 if (isArmingDisabled()
416 && IS_RC_MODE_ACTIVE(BOXARM
)) {
417 setArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
418 } else if (!IS_RC_MODE_ACTIVE(BOXARM
)) {
419 unsetArmingDisabled(ARMING_DISABLED_ARM_SWITCH
);
423 if (isArmingDisabled()) {
433 void disarm(flightLogDisarmReason_e reason
)
435 if (ARMING_FLAG(ARMED
)) {
436 if (!flipOverAfterCrashActive
) {
437 ENABLE_ARMING_FLAG(WAS_EVER_ARMED
);
439 DISABLE_ARMING_FLAG(ARMED
);
440 lastDisarmTimeUs
= micros();
443 if (flipOverAfterCrashActive
|| isLaunchControlActive()) {
444 osdSuppressStats(true);
449 flightLogEvent_disarm_t eventData
;
450 eventData
.reason
= reason
;
451 blackboxLogEvent(FLIGHT_LOG_EVENT_DISARM
, (flightLogEventData_t
*)&eventData
);
453 if (blackboxConfig()->device
&& blackboxConfig()->mode
!= BLACKBOX_MODE_ALWAYS_ON
) { // Close the log upon disarm except when logging mode is ALWAYS ON
461 if (isMotorProtocolDshot() && flipOverAfterCrashActive
&& !featureIsEnabled(FEATURE_3D
)) {
462 dshotCommandWrite(ALL_MOTORS
, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL
, DSHOT_CMD_TYPE_INLINE
);
465 #ifdef USE_PERSISTENT_STATS
466 if (!flipOverAfterCrashActive
) {
471 flipOverAfterCrashActive
= false;
473 // if ARMING_DISABLED_RUNAWAY_TAKEOFF is set then we want to play it's beep pattern instead
474 if (!(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF
| ARMING_DISABLED_CRASH_DETECTED
))) {
475 beeper(BEEPER_DISARMING
); // emit disarm tone
482 if (armingConfig()->gyro_cal_on_first_arm
) {
483 gyroStartCalibration(true);
486 updateArmingStatus();
488 if (!isArmingDisabled()) {
489 if (ARMING_FLAG(ARMED
)) {
493 const timeUs_t currentTimeUs
= micros();
496 if (currentTimeUs
- getLastDshotBeaconCommandTimeUs() < DSHOT_BEACON_GUARD_DELAY_US
) {
497 if (tryingToArm
== ARMING_DELAYED_DISARMED
) {
498 if (IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH
)) {
499 tryingToArm
= ARMING_DELAYED_CRASHFLIP
;
500 #ifdef USE_LAUNCH_CONTROL
501 } else if (canUseLaunchControl()) {
502 tryingToArm
= ARMING_DELAYED_LAUNCH_CONTROL
;
505 tryingToArm
= ARMING_DELAYED_NORMAL
;
511 if (isMotorProtocolDshot() && isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH
)) {
512 if (!(IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH
) || (tryingToArm
== ARMING_DELAYED_CRASHFLIP
))) {
513 flipOverAfterCrashActive
= false;
514 if (!featureIsEnabled(FEATURE_3D
)) {
515 dshotCommandWrite(ALL_MOTORS
, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL
, DSHOT_CMD_TYPE_INLINE
);
518 flipOverAfterCrashActive
= true;
519 #ifdef USE_RUNAWAY_TAKEOFF
520 runawayTakeoffCheckDisabled
= false;
522 if (!featureIsEnabled(FEATURE_3D
)) {
523 dshotCommandWrite(ALL_MOTORS
, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_REVERSED
, DSHOT_CMD_TYPE_INLINE
);
529 #ifdef USE_LAUNCH_CONTROL
530 if (!flipOverAfterCrashActive
&& (canUseLaunchControl() || (tryingToArm
== ARMING_DELAYED_LAUNCH_CONTROL
))) {
531 if (launchControlState
== LAUNCH_CONTROL_DISABLED
) { // only activate if it hasn't already been triggered
532 launchControlState
= LAUNCH_CONTROL_ACTIVE
;
538 osdSuppressStats(false);
540 ENABLE_ARMING_FLAG(ARMED
);
544 #ifdef USE_ACRO_TRAINER
545 pidAcroTrainerInit();
546 #endif // USE_ACRO_TRAINER
548 if (isModeActivationConditionPresent(BOXPREARM
)) {
549 ENABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM
);
551 imuQuaternionHeadfreeOffsetSet();
553 #if defined(USE_GYRO_DATA_ANALYSE)
557 disarmAt
= currentTimeUs
+ armingConfig()->auto_disarm_delay
* 1e6
; // start disarm timeout, will be extended when throttle is nonzero
559 lastArmingDisabledReason
= 0;
562 GPS_reset_home_position();
564 //beep to indicate arming
565 if (featureIsEnabled(FEATURE_GPS
)) {
566 if (STATE(GPS_FIX
) && gpsSol
.numSat
>= 5) {
567 beeper(BEEPER_ARMING_GPS_FIX
);
569 beeper(BEEPER_ARMING_GPS_NO_FIX
);
572 beeper(BEEPER_ARMING
);
575 beeper(BEEPER_ARMING
);
578 #ifdef USE_PERSISTENT_STATS
582 #ifdef USE_RUNAWAY_TAKEOFF
583 runawayTakeoffDeactivateUs
= 0;
584 runawayTakeoffAccumulatedUs
= 0;
585 runawayTakeoffTriggerUs
= 0;
589 if (!isFirstArmingGyroCalibrationRunning()) {
590 int armingDisabledReason
= ffs(getArmingDisableFlags());
591 if (lastArmingDisabledReason
!= armingDisabledReason
) {
592 lastArmingDisabledReason
= armingDisabledReason
;
594 beeperWarningBeeps(armingDisabledReason
);
600 // Automatic ACC Offset Calibration
601 bool AccInflightCalibrationArmed
= false;
602 bool AccInflightCalibrationMeasurementDone
= false;
603 bool AccInflightCalibrationSavetoEEProm
= false;
604 bool AccInflightCalibrationActive
= false;
605 uint16_t InflightcalibratingA
= 0;
607 void handleInflightCalibrationStickPosition(void)
609 if (AccInflightCalibrationMeasurementDone
) {
610 // trigger saving into eeprom after landing
611 AccInflightCalibrationMeasurementDone
= false;
612 AccInflightCalibrationSavetoEEProm
= true;
614 AccInflightCalibrationArmed
= !AccInflightCalibrationArmed
;
615 if (AccInflightCalibrationArmed
) {
616 beeper(BEEPER_ACC_CALIBRATION
);
618 beeper(BEEPER_ACC_CALIBRATION_FAIL
);
623 static void updateInflightCalibrationState(void)
625 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
626 InflightcalibratingA
= 50;
627 AccInflightCalibrationArmed
= false;
629 if (IS_RC_MODE_ACTIVE(BOXCALIB
)) { // Use the Calib Option to activate : Calib = TRUE measurement started, Land and Calib = 0 measurement stored
630 if (!AccInflightCalibrationActive
&& !AccInflightCalibrationMeasurementDone
)
631 InflightcalibratingA
= 50;
632 AccInflightCalibrationActive
= true;
633 } else if (AccInflightCalibrationMeasurementDone
&& !ARMING_FLAG(ARMED
)) {
634 AccInflightCalibrationMeasurementDone
= false;
635 AccInflightCalibrationSavetoEEProm
= true;
639 #if defined(USE_GPS) || defined(USE_MAG)
640 static void updateMagHold(void)
642 if (fabsf(rcCommand
[YAW
]) < 15 && FLIGHT_MODE(MAG_MODE
)) {
643 int16_t dif
= DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
) - magHold
;
648 dif
*= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed
);
650 rcCommand
[YAW
] -= dif
* currentPidProfile
->pid
[PID_MAG
].P
/ 30; // 18 deg
653 magHold
= DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
);
657 #ifdef USE_VTX_CONTROL
658 static bool canUpdateVTX(void)
660 #ifdef USE_VTX_RTC6705
661 return vtxRTC6705CanUpdate();
667 #if defined(USE_RUNAWAY_TAKEOFF) || defined(USE_GPS_RESCUE)
668 // determine if the R/P/Y stick deflection exceeds the specified limit - integer math is good enough here.
669 bool areSticksActive(uint8_t stickPercentLimit
)
671 for (int axis
= FD_ROLL
; axis
<= FD_YAW
; axis
++) {
672 const uint8_t deadband
= axis
== FD_YAW
? rcControlsConfig()->yaw_deadband
: rcControlsConfig()->deadband
;
673 uint8_t stickPercent
= 0;
674 if ((rcData
[axis
] >= PWM_RANGE_MAX
) || (rcData
[axis
] <= PWM_RANGE_MIN
)) {
677 if (rcData
[axis
] > (rxConfig()->midrc
+ deadband
)) {
678 stickPercent
= ((rcData
[axis
] - rxConfig()->midrc
- deadband
) * 100) / (PWM_RANGE_MAX
- rxConfig()->midrc
- deadband
);
679 } else if (rcData
[axis
] < (rxConfig()->midrc
- deadband
)) {
680 stickPercent
= ((rxConfig()->midrc
- deadband
- rcData
[axis
]) * 100) / (rxConfig()->midrc
- deadband
- PWM_RANGE_MIN
);
683 if (stickPercent
>= stickPercentLimit
) {
691 #ifdef USE_RUNAWAY_TAKEOFF
692 // allow temporarily disabling runaway takeoff prevention if we are connected
693 // to the configurator and the ARMING_DISABLED_MSP flag is cleared.
694 void runawayTakeoffTemporaryDisable(uint8_t disableFlag
)
696 runawayTakeoffTemporarilyDisabled
= disableFlag
;
701 // calculate the throttle stick percent - integer math is good enough here.
702 // returns negative values for reversed thrust in 3D mode
703 int8_t calculateThrottlePercent(void)
706 int channelData
= constrain(rcData
[THROTTLE
], PWM_RANGE_MIN
, PWM_RANGE_MAX
);
708 if (featureIsEnabled(FEATURE_3D
)
709 && !IS_RC_MODE_ACTIVE(BOX3D
)
710 && !flight3DConfig()->switched_mode3d
) {
712 if (channelData
> (rxConfig()->midrc
+ flight3DConfig()->deadband3d_throttle
)) {
713 ret
= ((channelData
- rxConfig()->midrc
- flight3DConfig()->deadband3d_throttle
) * 100) / (PWM_RANGE_MAX
- rxConfig()->midrc
- flight3DConfig()->deadband3d_throttle
);
714 } else if (channelData
< (rxConfig()->midrc
- flight3DConfig()->deadband3d_throttle
)) {
715 ret
= -((rxConfig()->midrc
- flight3DConfig()->deadband3d_throttle
- channelData
) * 100) / (rxConfig()->midrc
- flight3DConfig()->deadband3d_throttle
- PWM_RANGE_MIN
);
718 ret
= constrain(((channelData
- rxConfig()->mincheck
) * 100) / (PWM_RANGE_MAX
- rxConfig()->mincheck
), 0, 100);
719 if (featureIsEnabled(FEATURE_3D
)
720 && IS_RC_MODE_ACTIVE(BOX3D
)
721 && flight3DConfig()->switched_mode3d
) {
723 ret
= -ret
; // 3D on a switch is active
729 uint8_t calculateThrottlePercentAbs(void)
731 return ABS(calculateThrottlePercent());
734 static bool airmodeIsActivated
;
736 bool isAirmodeActivated()
738 return airmodeIsActivated
;
743 * processRx called from taskUpdateRxMain
745 bool processRx(timeUs_t currentTimeUs
)
747 timeDelta_t frameAgeUs
;
748 timeDelta_t frameDeltaUs
= rxGetFrameDelta(&frameAgeUs
);
750 DEBUG_SET(DEBUG_RX_TIMING
, 0, MIN(frameDeltaUs
/ 10, INT16_MAX
));
751 DEBUG_SET(DEBUG_RX_TIMING
, 1, MIN(frameAgeUs
/ 10, INT16_MAX
));
753 if (!calculateRxChannelsAndUpdateFailsafe(currentTimeUs
)) {
757 updateRcRefreshRate(currentTimeUs
);
759 // in 3D mode, we need to be able to disarm by switch at any time
760 if (featureIsEnabled(FEATURE_3D
)) {
761 if (!IS_RC_MODE_ACTIVE(BOXARM
))
762 disarm(DISARM_REASON_SWITCH
);
765 updateRSSI(currentTimeUs
);
767 if (currentTimeUs
> FAILSAFE_POWER_ON_DELAY_US
&& !failsafeIsMonitoring()) {
768 failsafeStartMonitoring();
770 failsafeUpdateState();
772 const throttleStatus_e throttleStatus
= calculateThrottleStatus();
773 const uint8_t throttlePercent
= calculateThrottlePercentAbs();
775 const bool launchControlActive
= isLaunchControlActive();
777 if (airmodeIsEnabled() && ARMING_FLAG(ARMED
) && !launchControlActive
) {
778 if (throttlePercent
>= rxConfig()->airModeActivateThreshold
) {
779 airmodeIsActivated
= true; // Prevent iterm from being reset
782 airmodeIsActivated
= false;
785 /* In airmode iterm should be prevented to grow when Low thottle and Roll + Pitch Centered.
786 This is needed to prevent iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */
787 if (throttleStatus
== THROTTLE_LOW
&& !airmodeIsActivated
&& !launchControlActive
) {
788 pidSetItermReset(true);
789 if (currentPidProfile
->pidAtMinThrottle
)
790 pidStabilisationState(PID_STABILISATION_ON
);
792 pidStabilisationState(PID_STABILISATION_OFF
);
794 pidSetItermReset(false);
795 pidStabilisationState(PID_STABILISATION_ON
);
798 #ifdef USE_RUNAWAY_TAKEOFF
799 // If runaway_takeoff_prevention is enabled, accumulate the amount of time that throttle
800 // is above runaway_takeoff_deactivate_throttle with the any of the R/P/Y sticks deflected
801 // to at least runaway_takeoff_stick_percent percent while the pidSum on all axis is kept low.
802 // Once the amount of accumulated time exceeds runaway_takeoff_deactivate_delay then disable
803 // prevention for the remainder of the battery.
805 if (ARMING_FLAG(ARMED
)
806 && pidConfig()->runaway_takeoff_prevention
807 && !runawayTakeoffCheckDisabled
808 && !flipOverAfterCrashActive
809 && !runawayTakeoffTemporarilyDisabled
812 // Determine if we're in "flight"
814 // - throttle over runaway_takeoff_deactivate_throttle_percent
815 // - sticks are active and have deflection greater than runaway_takeoff_deactivate_stick_percent
816 // - pidSum on all axis is less then runaway_takeoff_deactivate_pidlimit
817 bool inStableFlight
= false;
818 if (!featureIsEnabled(FEATURE_MOTOR_STOP
) || airmodeIsEnabled() || (throttleStatus
!= THROTTLE_LOW
)) { // are motors running?
819 const uint8_t lowThrottleLimit
= pidConfig()->runaway_takeoff_deactivate_throttle
;
820 const uint8_t midThrottleLimit
= constrain(lowThrottleLimit
* 2, lowThrottleLimit
* 2, RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT
);
821 if ((((throttlePercent
>= lowThrottleLimit
) && areSticksActive(RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT
)) || (throttlePercent
>= midThrottleLimit
))
822 && (fabsf(pidData
[FD_PITCH
].Sum
) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT
)
823 && (fabsf(pidData
[FD_ROLL
].Sum
) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT
)
824 && (fabsf(pidData
[FD_YAW
].Sum
) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT
)) {
826 inStableFlight
= true;
827 if (runawayTakeoffDeactivateUs
== 0) {
828 runawayTakeoffDeactivateUs
= currentTimeUs
;
833 // If we're in flight, then accumulate the time and deactivate once it exceeds runaway_takeoff_deactivate_delay milliseconds
834 if (inStableFlight
) {
835 if (runawayTakeoffDeactivateUs
== 0) {
836 runawayTakeoffDeactivateUs
= currentTimeUs
;
838 uint16_t deactivateDelay
= pidConfig()->runaway_takeoff_deactivate_delay
;
839 // at high throttle levels reduce deactivation delay by 50%
840 if (throttlePercent
>= RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT
) {
841 deactivateDelay
= deactivateDelay
/ 2;
843 if ((cmpTimeUs(currentTimeUs
, runawayTakeoffDeactivateUs
) + runawayTakeoffAccumulatedUs
) > deactivateDelay
* 1000) {
844 runawayTakeoffCheckDisabled
= true;
848 if (runawayTakeoffDeactivateUs
!= 0) {
849 runawayTakeoffAccumulatedUs
+= cmpTimeUs(currentTimeUs
, runawayTakeoffDeactivateUs
);
851 runawayTakeoffDeactivateUs
= 0;
853 if (runawayTakeoffDeactivateUs
== 0) {
854 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY
, DEBUG_RUNAWAY_TAKEOFF_FALSE
);
855 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME
, runawayTakeoffAccumulatedUs
/ 1000);
857 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY
, DEBUG_RUNAWAY_TAKEOFF_TRUE
);
858 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME
, (cmpTimeUs(currentTimeUs
, runawayTakeoffDeactivateUs
) + runawayTakeoffAccumulatedUs
) / 1000);
861 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_DELAY
, DEBUG_RUNAWAY_TAKEOFF_FALSE
);
862 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_DEACTIVATING_TIME
, DEBUG_RUNAWAY_TAKEOFF_FALSE
);
866 #ifdef USE_LAUNCH_CONTROL
867 if (ARMING_FLAG(ARMED
)) {
868 if (launchControlActive
&& (throttlePercent
> currentPidProfile
->launchControlThrottlePercent
)) {
869 // throttle limit trigger reached, launch triggered
870 // reset the iterms as they may be at high values from holding the launch position
871 launchControlState
= LAUNCH_CONTROL_TRIGGERED
;
875 if (launchControlState
== LAUNCH_CONTROL_TRIGGERED
) {
876 // If trigger mode is MULTIPLE then reset the state when disarmed
877 // and the mode switch is turned off.
878 // For trigger mode SINGLE we never reset the state and only a single
879 // launch is allowed until a reboot.
880 if (currentPidProfile
->launchControlAllowTriggerReset
&& !IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL
)) {
881 launchControlState
= LAUNCH_CONTROL_DISABLED
;
884 launchControlState
= LAUNCH_CONTROL_DISABLED
;
892 void processRxModes(timeUs_t currentTimeUs
)
894 static bool armedBeeperOn
= false;
896 static bool sharedPortTelemetryEnabled
= false;
898 const throttleStatus_e throttleStatus
= calculateThrottleStatus();
900 // When armed and motors aren't spinning, do beeps and then disarm
901 // board after delay so users without buzzer won't lose fingers.
902 // mixTable constrains motor commands, so checking throttleStatus is enough
903 const timeUs_t autoDisarmDelayUs
= armingConfig()->auto_disarm_delay
* 1e6
;
904 if (ARMING_FLAG(ARMED
)
905 && featureIsEnabled(FEATURE_MOTOR_STOP
)
907 && !featureIsEnabled(FEATURE_3D
)
908 && !airmodeIsEnabled()
909 && !FLIGHT_MODE(GPS_RESCUE_MODE
) // disable auto-disarm when GPS Rescue is active
911 if (isUsingSticksForArming()) {
912 if (throttleStatus
== THROTTLE_LOW
) {
913 if ((autoDisarmDelayUs
> 0) && (currentTimeUs
> disarmAt
)) {
914 // auto-disarm configured and delay is over
915 disarm(DISARM_REASON_THROTTLE_TIMEOUT
);
916 armedBeeperOn
= false;
918 // still armed; do warning beeps while armed
919 beeper(BEEPER_ARMED
);
920 armedBeeperOn
= true;
923 // throttle is not low - extend disarm time
924 disarmAt
= currentTimeUs
+ autoDisarmDelayUs
;
928 armedBeeperOn
= false;
932 // arming is via AUX switch; beep while throttle low
933 if (throttleStatus
== THROTTLE_LOW
) {
934 beeper(BEEPER_ARMED
);
935 armedBeeperOn
= true;
936 } else if (armedBeeperOn
) {
938 armedBeeperOn
= false;
942 disarmAt
= currentTimeUs
+ autoDisarmDelayUs
; // extend auto-disarm timer
945 if (!(IS_RC_MODE_ACTIVE(BOXPARALYZE
) && !ARMING_FLAG(ARMED
))
950 processRcStickPositions();
953 if (featureIsEnabled(FEATURE_INFLIGHT_ACC_CAL
)) {
954 updateInflightCalibrationState();
957 updateActivatedModes();
960 /* Enable beep warning when the crash flip mode is active */
961 if (flipOverAfterCrashActive
) {
962 beeper(BEEPER_CRASH_FLIP_MODE
);
966 if (!cliMode
&& !(IS_RC_MODE_ACTIVE(BOXPARALYZE
) && !ARMING_FLAG(ARMED
))) {
967 processRcAdjustments(currentControlRateProfile
);
970 bool canUseHorizonMode
= true;
972 if ((IS_RC_MODE_ACTIVE(BOXANGLE
) || failsafeIsActive()) && (sensors(SENSOR_ACC
))) {
973 // bumpless transfer to Level mode
974 canUseHorizonMode
= false;
976 if (!FLIGHT_MODE(ANGLE_MODE
)) {
977 ENABLE_FLIGHT_MODE(ANGLE_MODE
);
980 DISABLE_FLIGHT_MODE(ANGLE_MODE
); // failsafe support
983 if (IS_RC_MODE_ACTIVE(BOXHORIZON
) && canUseHorizonMode
) {
985 DISABLE_FLIGHT_MODE(ANGLE_MODE
);
987 if (!FLIGHT_MODE(HORIZON_MODE
)) {
988 ENABLE_FLIGHT_MODE(HORIZON_MODE
);
991 DISABLE_FLIGHT_MODE(HORIZON_MODE
);
994 #ifdef USE_GPS_RESCUE
995 if (ARMING_FLAG(ARMED
) && (IS_RC_MODE_ACTIVE(BOXGPSRESCUE
) || (failsafeIsActive() && failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_GPS_RESCUE
))) {
996 if (!FLIGHT_MODE(GPS_RESCUE_MODE
)) {
997 ENABLE_FLIGHT_MODE(GPS_RESCUE_MODE
);
1000 DISABLE_FLIGHT_MODE(GPS_RESCUE_MODE
);
1004 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
)) {
1006 // increase frequency of attitude task to reduce drift when in angle or horizon mode
1007 rescheduleTask(TASK_ATTITUDE
, TASK_PERIOD_HZ(500));
1010 rescheduleTask(TASK_ATTITUDE
, TASK_PERIOD_HZ(100));
1013 if (!IS_RC_MODE_ACTIVE(BOXPREARM
) && ARMING_FLAG(WAS_ARMED_WITH_PREARM
)) {
1014 DISABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM
);
1017 #if defined(USE_ACC) || defined(USE_MAG)
1018 if (sensors(SENSOR_ACC
) || sensors(SENSOR_MAG
)) {
1019 #if defined(USE_GPS) || defined(USE_MAG)
1020 if (IS_RC_MODE_ACTIVE(BOXMAG
)) {
1021 if (!FLIGHT_MODE(MAG_MODE
)) {
1022 ENABLE_FLIGHT_MODE(MAG_MODE
);
1023 magHold
= DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
);
1026 DISABLE_FLIGHT_MODE(MAG_MODE
);
1029 if (IS_RC_MODE_ACTIVE(BOXHEADFREE
) && !FLIGHT_MODE(GPS_RESCUE_MODE
)) {
1030 if (!FLIGHT_MODE(HEADFREE_MODE
)) {
1031 ENABLE_FLIGHT_MODE(HEADFREE_MODE
);
1034 DISABLE_FLIGHT_MODE(HEADFREE_MODE
);
1036 if (IS_RC_MODE_ACTIVE(BOXHEADADJ
) && !FLIGHT_MODE(GPS_RESCUE_MODE
)) {
1037 if (imuQuaternionHeadfreeOffsetSet()) {
1038 beeper(BEEPER_RX_SET
);
1044 if (IS_RC_MODE_ACTIVE(BOXPASSTHRU
)) {
1045 ENABLE_FLIGHT_MODE(PASSTHRU_MODE
);
1047 DISABLE_FLIGHT_MODE(PASSTHRU_MODE
);
1050 if (mixerConfig()->mixerMode
== MIXER_FLYING_WING
|| mixerConfig()->mixerMode
== MIXER_AIRPLANE
) {
1051 DISABLE_FLIGHT_MODE(HEADFREE_MODE
);
1054 #ifdef USE_TELEMETRY
1055 if (featureIsEnabled(FEATURE_TELEMETRY
)) {
1056 bool enableSharedPortTelemetry
= (!isModeActivationConditionPresent(BOXTELEMETRY
) && ARMING_FLAG(ARMED
)) || (isModeActivationConditionPresent(BOXTELEMETRY
) && IS_RC_MODE_ACTIVE(BOXTELEMETRY
));
1057 if (enableSharedPortTelemetry
&& !sharedPortTelemetryEnabled
) {
1058 mspSerialReleaseSharedTelemetryPorts();
1059 telemetryCheckState();
1061 sharedPortTelemetryEnabled
= true;
1062 } else if (!enableSharedPortTelemetry
&& sharedPortTelemetryEnabled
) {
1063 // the telemetry state must be checked immediately so that shared serial ports are released.
1064 telemetryCheckState();
1065 mspSerialAllocatePorts();
1067 sharedPortTelemetryEnabled
= false;
1072 #ifdef USE_VTX_CONTROL
1073 vtxUpdateActivatedChannel();
1075 if (canUpdateVTX()) {
1076 handleVTXControlButton();
1080 #ifdef USE_ACRO_TRAINER
1081 pidSetAcroTrainerState(IS_RC_MODE_ACTIVE(BOXACROTRAINER
) && sensors(SENSOR_ACC
));
1082 #endif // USE_ACRO_TRAINER
1084 #ifdef USE_RC_SMOOTHING_FILTER
1085 if (ARMING_FLAG(ARMED
) && !rcSmoothingInitializationComplete()) {
1086 beeper(BEEPER_RC_SMOOTHING_INIT_FAIL
);
1090 pidSetAntiGravityState(IS_RC_MODE_ACTIVE(BOXANTIGRAVITY
) || featureIsEnabled(FEATURE_ANTI_GRAVITY
));
1093 static FAST_CODE
void subTaskPidController(timeUs_t currentTimeUs
)
1095 uint32_t startTime
= 0;
1096 if (debugMode
== DEBUG_PIDLOOP
) {startTime
= micros();}
1097 // PID - note this is function pointer set by setPIDController()
1098 pidController(currentPidProfile
, currentTimeUs
);
1099 DEBUG_SET(DEBUG_PIDLOOP
, 1, micros() - startTime
);
1101 #ifdef USE_RUNAWAY_TAKEOFF
1102 // Check to see if runaway takeoff detection is active (anti-taz), the pidSum is over the threshold,
1103 // and gyro rate for any axis is above the limit for at least the activate delay period.
1104 // If so, disarm for safety
1105 if (ARMING_FLAG(ARMED
)
1107 && pidConfig()->runaway_takeoff_prevention
1108 && !runawayTakeoffCheckDisabled
1109 && !flipOverAfterCrashActive
1110 && !runawayTakeoffTemporarilyDisabled
1111 && !FLIGHT_MODE(GPS_RESCUE_MODE
) // disable Runaway Takeoff triggering if GPS Rescue is active
1112 && (!featureIsEnabled(FEATURE_MOTOR_STOP
) || airmodeIsEnabled() || (calculateThrottleStatus() != THROTTLE_LOW
))) {
1114 if (((fabsf(pidData
[FD_PITCH
].Sum
) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD
)
1115 || (fabsf(pidData
[FD_ROLL
].Sum
) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD
)
1116 || (fabsf(pidData
[FD_YAW
].Sum
) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD
))
1117 && ((gyroAbsRateDps(FD_PITCH
) > RUNAWAY_TAKEOFF_GYRO_LIMIT_RP
)
1118 || (gyroAbsRateDps(FD_ROLL
) > RUNAWAY_TAKEOFF_GYRO_LIMIT_RP
)
1119 || (gyroAbsRateDps(FD_YAW
) > RUNAWAY_TAKEOFF_GYRO_LIMIT_YAW
))) {
1121 if (runawayTakeoffTriggerUs
== 0) {
1122 runawayTakeoffTriggerUs
= currentTimeUs
+ RUNAWAY_TAKEOFF_ACTIVATE_DELAY
;
1123 } else if (currentTimeUs
> runawayTakeoffTriggerUs
) {
1124 setArmingDisabled(ARMING_DISABLED_RUNAWAY_TAKEOFF
);
1125 disarm(DISARM_REASON_RUNAWAY_TAKEOFF
);
1128 runawayTakeoffTriggerUs
= 0;
1130 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE
, DEBUG_RUNAWAY_TAKEOFF_TRUE
);
1131 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY
, runawayTakeoffTriggerUs
== 0 ? DEBUG_RUNAWAY_TAKEOFF_FALSE
: DEBUG_RUNAWAY_TAKEOFF_TRUE
);
1133 runawayTakeoffTriggerUs
= 0;
1134 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_ENABLED_STATE
, DEBUG_RUNAWAY_TAKEOFF_FALSE
);
1135 DEBUG_SET(DEBUG_RUNAWAY_TAKEOFF
, DEBUG_RUNAWAY_TAKEOFF_ACTIVATING_DELAY
, DEBUG_RUNAWAY_TAKEOFF_FALSE
);
1140 #ifdef USE_PID_AUDIO
1141 if (isModeActivationConditionPresent(BOXPIDAUDIO
)) {
1147 static FAST_CODE_NOINLINE
void subTaskPidSubprocesses(timeUs_t currentTimeUs
)
1149 uint32_t startTime
= 0;
1150 if (debugMode
== DEBUG_PIDLOOP
) {
1151 startTime
= micros();
1154 #if defined(USE_GPS) || defined(USE_MAG)
1155 if (sensors(SENSOR_GPS
) || sensors(SENSOR_MAG
)) {
1161 if (!cliMode
&& blackboxConfig()->device
) {
1162 blackboxUpdate(currentTimeUs
);
1165 UNUSED(currentTimeUs
);
1168 DEBUG_SET(DEBUG_PIDLOOP
, 3, micros() - startTime
);
1171 #ifdef USE_TELEMETRY
1172 #define GYRO_TEMP_READ_DELAY_US 3e6 // Only read the gyro temp every 3 seconds
1173 void subTaskTelemetryPollSensors(timeUs_t currentTimeUs
)
1175 static timeUs_t lastGyroTempTimeUs
= 0;
1177 if (cmpTimeUs(currentTimeUs
, lastGyroTempTimeUs
) >= GYRO_TEMP_READ_DELAY_US
) {
1178 // Read out gyro temperature if used for telemmetry
1179 gyroReadTemperature();
1180 lastGyroTempTimeUs
= currentTimeUs
;
1185 static FAST_CODE
void subTaskMotorUpdate(timeUs_t currentTimeUs
)
1187 uint32_t startTime
= 0;
1188 if (debugMode
== DEBUG_CYCLETIME
) {
1189 startTime
= micros();
1190 static uint32_t previousMotorUpdateTime
;
1191 const uint32_t currentDeltaTime
= startTime
- previousMotorUpdateTime
;
1192 debug
[2] = currentDeltaTime
;
1193 debug
[3] = currentDeltaTime
- targetPidLooptime
;
1194 previousMotorUpdateTime
= startTime
;
1195 } else if (debugMode
== DEBUG_PIDLOOP
) {
1196 startTime
= micros();
1199 mixTable(currentTimeUs
);
1202 // motor outputs are used as sources for servo mixing, so motors must be calculated using mixTable() before servos.
1203 if (isMixerUsingServos()) {
1210 #ifdef USE_DSHOT_TELEMETRY_STATS
1211 if (debugMode
== DEBUG_DSHOT_RPM_ERRORS
&& useDshotTelemetry
) {
1212 const uint8_t motorCount
= MIN(getMotorCount(), 4);
1213 for (uint8_t i
= 0; i
< motorCount
; i
++) {
1214 debug
[i
] = getDshotTelemetryMotorInvalidPercent(i
);
1219 DEBUG_SET(DEBUG_PIDLOOP
, 2, micros() - startTime
);
1222 static FAST_CODE_NOINLINE
void subTaskRcCommand(timeUs_t currentTimeUs
)
1224 UNUSED(currentTimeUs
);
1226 // If we're armed, at minimum throttle, and we do arming via the
1227 // sticks, do not process yaw input from the rx. We do this so the
1228 // motors do not spin up while we are trying to arm or disarm.
1229 // Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
1230 if (isUsingSticksForArming() && rcData
[THROTTLE
] <= rxConfig()->mincheck
1231 #ifndef USE_QUAD_MIXER_ONLY
1233 && !((mixerConfig()->mixerMode
== MIXER_TRI
|| mixerConfig()->mixerMode
== MIXER_CUSTOM_TRI
) && servoConfig()->tri_unarmed_servo
)
1235 && mixerConfig()->mixerMode
!= MIXER_AIRPLANE
1236 && mixerConfig()->mixerMode
!= MIXER_FLYING_WING
1245 FAST_CODE
void taskGyroSample(timeUs_t currentTimeUs
)
1247 UNUSED(currentTimeUs
);
1249 if (pidUpdateCounter
% activePidLoopDenom
== 0) {
1250 pidUpdateCounter
= 0;
1255 FAST_CODE
bool gyroFilterReady(void)
1257 if (pidUpdateCounter
% activePidLoopDenom
== 0) {
1264 FAST_CODE
bool pidLoopReady(void)
1266 if ((pidUpdateCounter
% activePidLoopDenom
) == (activePidLoopDenom
/ 2)) {
1272 FAST_CODE
void taskFiltering(timeUs_t currentTimeUs
)
1274 gyroFiltering(currentTimeUs
);
1278 // Function for loop trigger
1279 FAST_CODE
void taskMainPidLoop(timeUs_t currentTimeUs
)
1282 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_GYROPID_SYNC)
1283 if (lockMainPID() != 0) return;
1286 // DEBUG_PIDLOOP, timings for:
1288 // 1 - subTaskPidController()
1289 // 2 - subTaskMotorUpdate()
1290 // 3 - subTaskPidSubprocesses()
1291 DEBUG_SET(DEBUG_PIDLOOP
, 0, micros() - currentTimeUs
);
1293 subTaskRcCommand(currentTimeUs
);
1294 subTaskPidController(currentTimeUs
);
1295 subTaskMotorUpdate(currentTimeUs
);
1296 subTaskPidSubprocesses(currentTimeUs
);
1298 if (debugMode
== DEBUG_CYCLETIME
) {
1299 DEBUG_SET(DEBUG_CYCLETIME
, 0, getTaskDeltaTimeUs(TASK_SELF
));
1300 DEBUG_SET(DEBUG_CYCLETIME
, 1, getAverageSystemLoadPercent());
1304 bool isFlipOverAfterCrashActive(void)
1306 return flipOverAfterCrashActive
;
1309 timeUs_t
getLastDisarmTimeUs(void)
1311 return lastDisarmTimeUs
;
1314 bool isTryingToArm()
1316 return (tryingToArm
!= ARMING_DELAYED_DISARMED
);
1319 void resetTryingToArm()
1321 tryingToArm
= ARMING_DELAYED_DISARMED
;
1324 bool isLaunchControlActive(void)
1326 #ifdef USE_LAUNCH_CONTROL
1327 return launchControlState
== LAUNCH_CONTROL_ACTIVE
;