Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / fc / fc_core.c
blobda40f9149f50a8676111536bafdb48d8e9e7806c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdlib.h>
20 #include <stdint.h>
22 #include "platform.h"
24 #include "blackbox/blackbox.h"
26 #include "build/debug.h"
28 #include "common/maths.h"
29 #include "common/axis.h"
30 #include "common/color.h"
31 #include "common/utils.h"
32 #include "common/filter.h"
34 #include "drivers/light_led.h"
35 #include "drivers/serial.h"
36 #include "drivers/time.h"
37 #include "drivers/system.h"
38 #include "drivers/pwm_output.h"
40 #include "sensors/sensors.h"
41 #include "sensors/diagnostics.h"
42 #include "sensors/boardalignment.h"
43 #include "sensors/acceleration.h"
44 #include "sensors/barometer.h"
45 #include "sensors/compass.h"
46 #include "sensors/pitotmeter.h"
47 #include "sensors/gyro.h"
48 #include "sensors/battery.h"
49 #include "sensors/rangefinder.h"
50 #include "sensors/opflow.h"
51 #include "sensors/esc_sensor.h"
53 #include "fc/fc_core.h"
54 #include "fc/cli.h"
55 #include "fc/config.h"
56 #include "fc/controlrate_profile.h"
57 #include "fc/multifunction.h"
58 #include "fc/rc_adjustments.h"
59 #include "fc/rc_smoothing.h"
60 #include "fc/rc_controls.h"
61 #include "fc/rc_curves.h"
62 #include "fc/rc_modes.h"
63 #include "fc/runtime_config.h"
65 #include "io/beeper.h"
66 #include "io/dashboard.h"
67 #include "io/gps.h"
68 #include "io/serial.h"
69 #include "io/statusindicator.h"
70 #include "io/asyncfatfs/asyncfatfs.h"
71 #include "io/piniobox.h"
73 #include "msp/msp_serial.h"
75 #include "navigation/navigation.h"
77 #include "rx/rx.h"
78 #include "rx/msp.h"
80 #include "scheduler/scheduler.h"
82 #include "telemetry/telemetry.h"
84 #include "flight/mixer_profile.h"
85 #include "flight/mixer.h"
86 #include "flight/servos.h"
87 #include "flight/pid.h"
88 #include "flight/imu.h"
89 #include "flight/rate_dynamics.h"
91 #include "flight/failsafe.h"
92 #include "flight/power_limits.h"
94 #include "config/feature.h"
95 #include "common/vector.h"
96 #include "programming/pid.h"
98 // June 2013 V2.2-dev
100 enum {
101 ALIGN_GYRO = 0,
102 ALIGN_ACCEL = 1,
103 ALIGN_MAG = 2
106 #define EMERGENCY_ARMING_TIME_WINDOW_MS 10000
107 #define EMERGENCY_ARMING_COUNTER_STEP_MS 1000
108 #define EMERGENCY_ARMING_MIN_ARM_COUNT 10
109 #define EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS 5000
111 timeDelta_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
112 static timeUs_t flightTime = 0;
113 static timeUs_t armTime = 0;
115 EXTENDED_FASTRAM float dT;
117 int16_t headFreeModeHold;
119 uint8_t motorControlEnable = false;
121 static bool isRXDataNew;
122 static disarmReason_t lastDisarmReason = DISARM_NONE;
123 timeUs_t lastDisarmTimeUs = 0;
124 timeMs_t emergRearmStabiliseTimeout = 0;
126 static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible
127 static timeMs_t prearmActivationTime = 0;
129 static bool isAccRequired(void) {
130 return isModeActivationConditionPresent(BOXNAVPOSHOLD) ||
131 isModeActivationConditionPresent(BOXNAVRTH) ||
132 isModeActivationConditionPresent(BOXNAVWP) ||
133 isModeActivationConditionPresent(BOXANGLE) ||
134 isModeActivationConditionPresent(BOXHORIZON) ||
135 isModeActivationConditionPresent(BOXNAVALTHOLD) ||
136 isModeActivationConditionPresent(BOXHEADINGHOLD) ||
137 isModeActivationConditionPresent(BOXNAVLAUNCH) ||
138 isModeActivationConditionPresent(BOXTURNASSIST) ||
139 isModeActivationConditionPresent(BOXNAVCOURSEHOLD) ||
140 isModeActivationConditionPresent(BOXSOARING) ||
141 failsafeConfig()->failsafe_procedure != FAILSAFE_PROCEDURE_DROP_IT;
144 bool areSensorsCalibrating(void)
146 #ifdef USE_BARO
147 if (sensors(SENSOR_BARO) && !baroIsCalibrationComplete()) {
148 return true;
150 #endif
152 #ifdef USE_MAG
153 if (sensors(SENSOR_MAG) && !compassIsCalibrationComplete()) {
154 return true;
156 #endif
158 #ifdef USE_PITOT
159 if (sensors(SENSOR_PITOT) && !pitotIsCalibrationComplete()) {
160 return true;
162 #endif
164 if (!navIsCalibrationComplete() && isAccRequired()) {
165 return true;
168 if (!accIsCalibrationComplete() && sensors(SENSOR_ACC) && isAccRequired()) {
169 return true;
172 if (!gyroIsCalibrationComplete()) {
173 return true;
176 return false;
179 int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband)
181 int16_t stickDeflection = 0;
183 #if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914
184 const int16_t value = rawData - PWM_RANGE_MIDDLE;
185 if (value < -500) {
186 stickDeflection = -500;
187 } else if (value > 500) {
188 stickDeflection = 500;
189 } else {
190 stickDeflection = value;
192 #else
193 stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500);
194 #endif
196 stickDeflection = applyDeadbandRescaled(stickDeflection, deadband, -500, 500);
197 return rcLookup(stickDeflection, rate);
200 static void updateArmingStatus(void)
202 if (ARMING_FLAG(ARMED)) {
203 LED0_ON;
204 } else {
205 /* CHECK: Run-time calibration */
206 static bool calibratingFinishedBeep = false;
207 if (areSensorsCalibrating()) {
208 ENABLE_ARMING_FLAG(ARMING_DISABLED_SENSORS_CALIBRATING);
209 calibratingFinishedBeep = false;
211 else {
212 DISABLE_ARMING_FLAG(ARMING_DISABLED_SENSORS_CALIBRATING);
214 if (!calibratingFinishedBeep) {
215 calibratingFinishedBeep = true;
216 beeper(BEEPER_RUNTIME_CALIBRATION_DONE);
220 /* CHECK: RX signal */
221 if (!failsafeIsReceivingRxData()) {
222 ENABLE_ARMING_FLAG(ARMING_DISABLED_RC_LINK);
224 else {
225 DISABLE_ARMING_FLAG(ARMING_DISABLED_RC_LINK);
228 /* CHECK: Throttle */
229 if (!armingConfig()->fixed_wing_auto_arm) {
230 // Don't want this check if fixed_wing_auto_arm is in use - machine arms on throttle > LOW
231 if (throttleStickIsLow()) {
232 DISABLE_ARMING_FLAG(ARMING_DISABLED_THROTTLE);
233 } else {
234 ENABLE_ARMING_FLAG(ARMING_DISABLED_THROTTLE);
238 /* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */
239 if (isNavLaunchEnabled()) {
240 if (isRollPitchStickDeflected(CONTROL_DEADBAND)) {
241 ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
242 } else {
243 DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
247 /* CHECK: Angle */
248 if (!STATE(SMALL_ANGLE)) {
249 ENABLE_ARMING_FLAG(ARMING_DISABLED_NOT_LEVEL);
251 else {
252 DISABLE_ARMING_FLAG(ARMING_DISABLED_NOT_LEVEL);
255 /* CHECK: CPU load */
256 if (isSystemOverloaded()) {
257 ENABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED);
259 else {
260 DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED);
263 /* CHECK: Navigation safety */
264 if (navigationIsBlockingArming(NULL) != NAV_ARMING_BLOCKER_NONE) {
265 ENABLE_ARMING_FLAG(ARMING_DISABLED_NAVIGATION_UNSAFE);
267 else {
268 DISABLE_ARMING_FLAG(ARMING_DISABLED_NAVIGATION_UNSAFE);
271 #if defined(USE_MAG)
272 /* CHECK: */
273 if (sensors(SENSOR_MAG) && !STATE(COMPASS_CALIBRATED)) {
274 ENABLE_ARMING_FLAG(ARMING_DISABLED_COMPASS_NOT_CALIBRATED);
276 else {
277 DISABLE_ARMING_FLAG(ARMING_DISABLED_COMPASS_NOT_CALIBRATED);
279 #endif
281 /* CHECK: */
282 if (
283 sensors(SENSOR_ACC) &&
284 !STATE(ACCELEROMETER_CALIBRATED) &&
285 // Require ACC calibration only if any of the setting might require it
286 isAccRequired()
288 ENABLE_ARMING_FLAG(ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED);
290 else {
291 DISABLE_ARMING_FLAG(ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED);
294 /* CHECK: */
295 if (!isHardwareHealthy()) {
296 ENABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
298 else {
299 DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
302 /* CHECK: BOXFAILSAFE */
303 if (IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
304 ENABLE_ARMING_FLAG(ARMING_DISABLED_BOXFAILSAFE);
306 else {
307 DISABLE_ARMING_FLAG(ARMING_DISABLED_BOXFAILSAFE);
310 /* CHECK: Do not allow arming if Servo AutoTrim is enabled */
311 if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
312 ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
314 else {
315 DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
318 #ifdef USE_DSHOT
319 /* CHECK: Don't arm if the DShot beeper was used recently, as there is a minimum delay before sending the next DShot command */
320 if (micros() - getLastDshotBeeperCommandTimeUs() < getDShotBeaconGuardDelayUs()) {
321 ENABLE_ARMING_FLAG(ARMING_DISABLED_DSHOT_BEEPER);
322 } else {
323 DISABLE_ARMING_FLAG(ARMING_DISABLED_DSHOT_BEEPER);
325 #else
326 DISABLE_ARMING_FLAG(ARMING_DISABLED_DSHOT_BEEPER);
327 #endif
329 if (isModeActivationConditionPresent(BOXPREARM)) {
330 if (IS_RC_MODE_ACTIVE(BOXPREARM)) {
331 if (prearmWasReset && (armingConfig()->prearmTimeoutMs == 0 || millis() - prearmActivationTime < armingConfig()->prearmTimeoutMs)) {
332 DISABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
333 } else {
334 ENABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
336 } else {
337 prearmWasReset = true;
338 prearmActivationTime = millis();
339 ENABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
341 } else {
342 DISABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
345 if (ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED) && !IS_RC_MODE_ACTIVE(BOXARM)) {
346 DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED);
349 /* CHECK: Arming switch */
350 // If arming is disabled and the ARM switch is on
351 // Note that this should be last check so all other blockers could be cleared correctly
352 // if blocking modes are linked to the same RC channel
353 if (isArmingDisabled() && IS_RC_MODE_ACTIVE(BOXARM)) {
354 ENABLE_ARMING_FLAG(ARMING_DISABLED_ARM_SWITCH);
355 } else if (!IS_RC_MODE_ACTIVE(BOXARM)) {
356 DISABLE_ARMING_FLAG(ARMING_DISABLED_ARM_SWITCH);
359 if (isArmingDisabled()) {
360 warningLedFlash();
361 } else {
362 warningLedDisable();
365 warningLedUpdate();
369 static bool emergencyArmingCanOverrideArmingDisabled(void)
371 uint32_t armingPrevention = armingFlags & ARMING_DISABLED_ALL_FLAGS;
372 armingPrevention &= ~ARMING_DISABLED_EMERGENCY_OVERRIDE;
373 return armingPrevention == 0;
376 static bool emergencyArmingIsEnabled(void)
378 return emergencyArmingUpdate(IS_RC_MODE_ACTIVE(BOXARM), false) && emergencyArmingCanOverrideArmingDisabled();
381 static void processPilotAndFailSafeActions(float dT)
383 if (failsafeShouldApplyControlInput()) {
384 // Failsafe will apply rcCommand for us
385 failsafeApplyControlInput();
387 else {
388 // Compute ROLL PITCH and YAW command
389 rcCommand[ROLL] = getAxisRcCommand(rxGetChannelValue(ROLL), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
390 rcCommand[PITCH] = getAxisRcCommand(rxGetChannelValue(PITCH), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
391 rcCommand[YAW] = -getAxisRcCommand(rxGetChannelValue(YAW), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcYawExpo8 : currentControlRateProfile->stabilized.rcYawExpo8, rcControlsConfig()->yaw_deadband);
393 // Apply manual control rates
394 if (FLIGHT_MODE(MANUAL_MODE)) {
395 rcCommand[ROLL] = rcCommand[ROLL] * currentControlRateProfile->manual.rates[FD_ROLL] / 100L;
396 rcCommand[PITCH] = rcCommand[PITCH] * currentControlRateProfile->manual.rates[FD_PITCH] / 100L;
397 rcCommand[YAW] = rcCommand[YAW] * currentControlRateProfile->manual.rates[FD_YAW] / 100L;
398 } else {
399 DEBUG_SET(DEBUG_RATE_DYNAMICS, 0, rcCommand[ROLL]);
400 rcCommand[ROLL] = applyRateDynamics(rcCommand[ROLL], ROLL, dT);
401 DEBUG_SET(DEBUG_RATE_DYNAMICS, 1, rcCommand[ROLL]);
403 DEBUG_SET(DEBUG_RATE_DYNAMICS, 2, rcCommand[PITCH]);
404 rcCommand[PITCH] = applyRateDynamics(rcCommand[PITCH], PITCH, dT);
405 DEBUG_SET(DEBUG_RATE_DYNAMICS, 3, rcCommand[PITCH]);
407 DEBUG_SET(DEBUG_RATE_DYNAMICS, 4, rcCommand[YAW]);
408 rcCommand[YAW] = applyRateDynamics(rcCommand[YAW], YAW, dT);
409 DEBUG_SET(DEBUG_RATE_DYNAMICS, 5, rcCommand[YAW]);
413 //Compute THROTTLE command
414 rcCommand[THROTTLE] = throttleStickMixedValue();
416 // Signal updated rcCommand values to Failsafe system
417 failsafeUpdateRcCommandValues();
419 if (FLIGHT_MODE(HEADFREE_MODE)) {
420 const float radDiff = degreesToRadians(DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headFreeModeHold);
421 const float cosDiff = cos_approx(radDiff);
422 const float sinDiff = sin_approx(radDiff);
423 const int16_t rcCommand_PITCH = rcCommand[PITCH] * cosDiff + rcCommand[ROLL] * sinDiff;
424 rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff;
425 rcCommand[PITCH] = rcCommand_PITCH;
430 void disarm(disarmReason_t disarmReason)
432 if (ARMING_FLAG(ARMED)) {
433 lastDisarmReason = disarmReason;
434 lastDisarmTimeUs = micros();
435 DISABLE_ARMING_FLAG(ARMED);
436 DISABLE_STATE(IN_FLIGHT_EMERG_REARM);
438 #ifdef USE_BLACKBOX
439 if (feature(FEATURE_BLACKBOX)) {
440 blackboxFinish();
442 #endif
443 #ifdef USE_DSHOT
444 if (FLIGHT_MODE(TURTLE_MODE)) {
445 sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_NORMAL);
446 DISABLE_FLIGHT_MODE(TURTLE_MODE);
448 #endif
449 statsOnDisarm();
450 logicConditionReset();
452 #ifdef USE_PROGRAMMING_FRAMEWORK
453 programmingPidReset();
454 #endif
455 beeper(BEEPER_DISARMING); // emit disarm tone
457 prearmWasReset = false;
461 timeUs_t getLastDisarmTimeUs(void) {
462 return lastDisarmTimeUs;
465 disarmReason_t getDisarmReason(void)
467 return lastDisarmReason;
470 bool emergencyArmingUpdate(bool armingSwitchIsOn, bool forceArm)
472 if (ARMING_FLAG(ARMED)) {
473 return false;
476 static timeMs_t timeout = 0;
477 static int8_t counter = 0;
478 static bool toggle;
479 timeMs_t currentTimeMs = millis();
481 if (timeout && currentTimeMs > timeout) {
482 timeout += EMERGENCY_ARMING_COUNTER_STEP_MS;
483 counter -= counter ? 1 : 0;
484 if (!counter) {
485 timeout = 0;
489 if (armingSwitchIsOn) {
490 if (!timeout && toggle) {
491 timeout = currentTimeMs + EMERGENCY_ARMING_TIME_WINDOW_MS;
493 counter += toggle;
494 toggle = false;
495 } else {
496 toggle = true;
499 if (forceArm) {
500 counter = EMERGENCY_ARMING_MIN_ARM_COUNT;
503 return counter >= EMERGENCY_ARMING_MIN_ARM_COUNT;
506 bool emergInflightRearmEnabled(void)
508 /* Emergency rearm allowed within 5s timeout period after disarm if craft still flying */
509 timeMs_t currentTimeMs = millis();
510 emergRearmStabiliseTimeout = 0;
512 if ((lastDisarmReason != DISARM_SWITCH) ||
513 (currentTimeMs > US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS)) {
514 return false;
517 // allow emergency rearm if MR has vertical speed at least 1.5 sec after disarm indicating still flying
518 bool mcDisarmVertVelCheck = STATE(MULTIROTOR) && (currentTimeMs > US2MS(lastDisarmTimeUs) + 1500) && fabsf(getEstimatedActualVelocity(Z)) > 100.0f;
520 if (isProbablyStillFlying() || mcDisarmVertVelCheck) {
521 emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft
522 ENABLE_STATE(IN_FLIGHT_EMERG_REARM);
523 return true;
526 return false; // craft doesn't appear to be flying, don't allow emergency rearm
529 void tryArm(void)
531 updateArmingStatus();
533 if (ARMING_FLAG(ARMED)) {
534 return;
537 #ifdef USE_DSHOT
538 #ifdef USE_MULTI_FUNCTIONS
539 const bool turtleIsActive = IS_RC_MODE_ACTIVE(BOXTURTLE) || MULTI_FUNC_FLAG(MF_TURTLE_MODE);
540 #else
541 const bool turtleIsActive = IS_RC_MODE_ACTIVE(BOXTURTLE);
542 #endif
543 if (STATE(MULTIROTOR) && turtleIsActive && !FLIGHT_MODE(TURTLE_MODE) && emergencyArmingCanOverrideArmingDisabled() && isMotorProtocolDshot()) {
544 sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_REVERSED);
545 ENABLE_ARMING_FLAG(ARMED);
546 ENABLE_FLIGHT_MODE(TURTLE_MODE);
547 return;
549 #endif
551 #ifdef USE_PROGRAMMING_FRAMEWORK
552 if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled() ||
553 LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) {
554 #else
555 if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled()) {
556 #endif
557 // If nav_extra_arming_safety was bypassed we always
558 // allow bypassing it even without the sticks set
559 // in the correct position to allow re-arming quickly
560 // in case of a mid-air accidental disarm.
561 bool usedBypass = false;
562 navigationIsBlockingArming(&usedBypass);
563 if (usedBypass) {
564 ENABLE_STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED);
567 lastDisarmReason = DISARM_NONE;
569 ENABLE_ARMING_FLAG(ARMED);
570 ENABLE_ARMING_FLAG(WAS_EVER_ARMED);
571 //It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction
572 ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD);
574 if (!STATE(IN_FLIGHT_EMERG_REARM)) {
575 resetLandingDetectorActiveState(); // reset landing detector after arming to avoid false detection before flight
576 logicConditionReset();
577 #ifdef USE_PROGRAMMING_FRAMEWORK
578 programmingPidReset();
579 #endif
582 headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
584 resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
586 #ifdef USE_BLACKBOX
587 if (feature(FEATURE_BLACKBOX)) {
588 serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
589 if (sharedBlackboxAndMspPort) {
590 mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
592 blackboxStart();
594 #endif
596 //beep to indicate arming
597 if (navigationPositionEstimateIsHealthy()) {
598 beeper(BEEPER_ARMING_GPS_FIX);
599 } else {
600 beeper(BEEPER_ARMING);
603 statsOnArm();
605 return;
608 if (!ARMING_FLAG(ARMED)) {
609 beeperConfirmationBeeps(1);
613 #define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
615 void releaseSharedTelemetryPorts(void) {
616 serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
617 while (sharedPort) {
618 mspSerialReleasePortIfAllocated(sharedPort);
619 sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
623 void processRx(timeUs_t currentTimeUs)
625 // Calculate RPY channel data
626 calculateRxChannelsAndUpdateFailsafe(currentTimeUs);
628 // in 3D mode, we need to be able to disarm by switch at any time
629 if (feature(FEATURE_REVERSIBLE_MOTORS)) {
630 if (!IS_RC_MODE_ACTIVE(BOXARM)) {
631 disarm(DISARM_SWITCH_3D);
635 updateRSSI(currentTimeUs);
637 // Update failsafe monitoring system
638 if (currentTimeUs > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) {
639 failsafeStartMonitoring();
642 failsafeUpdateState();
644 const bool throttleIsLow = throttleStickIsLow();
646 // When armed and motors aren't spinning, do beeps periodically
647 if (ARMING_FLAG(ARMED) && ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY)) {
648 static bool armedBeeperOn = false;
650 if (throttleIsLow) {
651 beeper(BEEPER_ARMED);
652 armedBeeperOn = true;
653 } else if (armedBeeperOn) {
654 beeperSilence();
655 armedBeeperOn = false;
659 processRcStickPositions(throttleIsLow);
660 processAirmode();
661 updateActivatedModes();
663 #ifdef USE_PINIOBOX
664 pinioBoxUpdate();
665 #endif
667 if (!cliMode) {
668 bool canUseRxData = rxIsReceivingSignal() && !FLIGHT_MODE(FAILSAFE_MODE);
669 updateAdjustmentStates(canUseRxData);
670 processRcAdjustments(CONST_CAST(controlRateConfig_t*, currentControlRateProfile), canUseRxData);
673 // Angle mode forced on briefly after emergency inflight rearm to help stabilise attitude (currently limited to MR)
674 bool emergRearmAngleEnforce = STATE(MULTIROTOR) && emergRearmStabiliseTimeout > US2MS(currentTimeUs);
675 bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || emergRearmAngleEnforce;
677 /* Disable stabilised modes initially, will be enabled as required with priority ANGLE > HORIZON > ANGLEHOLD
678 * MANUAL mode has priority over these modes except when ANGLE auto enabled */
679 DISABLE_FLIGHT_MODE(ANGLE_MODE);
680 DISABLE_FLIGHT_MODE(HORIZON_MODE);
681 DISABLE_FLIGHT_MODE(ANGLEHOLD_MODE);
683 if (sensors(SENSOR_ACC) && (!FLIGHT_MODE(MANUAL_MODE) || autoEnableAngle)) {
684 if (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle) {
685 ENABLE_FLIGHT_MODE(ANGLE_MODE);
686 } else if (IS_RC_MODE_ACTIVE(BOXHORIZON)) {
687 ENABLE_FLIGHT_MODE(HORIZON_MODE);
688 } else if (STATE(AIRPLANE) && IS_RC_MODE_ACTIVE(BOXANGLEHOLD)) {
689 ENABLE_FLIGHT_MODE(ANGLEHOLD_MODE);
693 if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
694 LED1_ON;
695 } else {
696 LED1_OFF;
699 /* Flaperon mode */
700 if (IS_RC_MODE_ACTIVE(BOXFLAPERON) && STATE(FLAPERON_AVAILABLE)) {
701 ENABLE_FLIGHT_MODE(FLAPERON);
702 } else {
703 DISABLE_FLIGHT_MODE(FLAPERON);
706 /* Turn assistant mode */
707 if (IS_RC_MODE_ACTIVE(BOXTURNASSIST) || navigationRequiresTurnAssistance()) {
708 ENABLE_FLIGHT_MODE(TURN_ASSISTANT);
709 } else {
710 DISABLE_FLIGHT_MODE(TURN_ASSISTANT);
713 if (sensors(SENSOR_ACC)) {
714 if (IS_RC_MODE_ACTIVE(BOXHEADINGHOLD)) {
715 if (!FLIGHT_MODE(HEADING_MODE)) {
716 resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
717 ENABLE_FLIGHT_MODE(HEADING_MODE);
719 } else {
720 DISABLE_FLIGHT_MODE(HEADING_MODE);
724 #if defined(USE_MAG)
725 if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
726 if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && STATE(MULTIROTOR)) {
727 ENABLE_FLIGHT_MODE(HEADFREE_MODE);
728 } else {
729 DISABLE_FLIGHT_MODE(HEADFREE_MODE);
731 if (IS_RC_MODE_ACTIVE(BOXHEADADJ) && STATE(MULTIROTOR)) {
732 headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); // acquire new heading
735 #endif
737 // Handle passthrough mode
738 if (STATE(FIXED_WING_LEGACY)) {
739 if ((IS_RC_MODE_ACTIVE(BOXMANUAL) && !navigationRequiresAngleMode() && !failsafeRequiresAngleMode()) || // Normal activation of passthrough
740 (!ARMING_FLAG(ARMED) && areSensorsCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating
741 ENABLE_FLIGHT_MODE(MANUAL_MODE);
742 } else {
743 DISABLE_FLIGHT_MODE(MANUAL_MODE);
745 } else {
746 DISABLE_FLIGHT_MODE(MANUAL_MODE);
749 /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered.
750 This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air
751 Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */
753 if (!ARMING_FLAG(ARMED)) {
754 DISABLE_STATE(ANTI_WINDUP_DEACTIVATED);
757 const rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus();
759 // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL)
760 if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) {
761 DISABLE_STATE(ANTI_WINDUP);
762 pidResetErrorAccumulators();
764 else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) {
765 if (throttleIsLow) {
766 if (STATE(AIRMODE_ACTIVE)) {
767 if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) {
768 ENABLE_STATE(ANTI_WINDUP);
770 else {
771 DISABLE_STATE(ANTI_WINDUP);
774 else {
775 DISABLE_STATE(ANTI_WINDUP);
776 pidResetErrorAccumulators();
779 else {
780 DISABLE_STATE(ANTI_WINDUP);
783 else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) {
784 if (throttleIsLow) {
785 if (STATE(AIRMODE_ACTIVE)) {
786 if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) {
787 ENABLE_STATE(ANTI_WINDUP);
789 else {
790 DISABLE_STATE(ANTI_WINDUP);
793 else {
794 DISABLE_STATE(ANTI_WINDUP);
795 pidResetErrorAccumulators();
798 else {
799 DISABLE_STATE(ANTI_WINDUP);
800 if (rollPitchStatus != CENTERED) {
801 ENABLE_STATE(ANTI_WINDUP_DEACTIVATED);
805 else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) {
806 DISABLE_STATE(ANTI_WINDUP);
807 //This case applies only to MR when Airmode management is throttle threshold activated
808 if (throttleIsLow && !STATE(AIRMODE_ACTIVE)) {
809 pidResetErrorAccumulators();
812 //---------------------------------------------------------
813 if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
814 DISABLE_FLIGHT_MODE(HEADFREE_MODE);
817 #if defined(USE_AUTOTUNE_FIXED_WING) || defined(USE_AUTOTUNE_MULTIROTOR)
818 autotuneUpdateState();
819 #endif
821 #ifdef USE_TELEMETRY
822 if (feature(FEATURE_TELEMETRY)) {
823 if ((!telemetryConfig()->telemetry_switch && ARMING_FLAG(ARMED)) ||
824 (telemetryConfig()->telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
826 releaseSharedTelemetryPorts();
827 } else {
828 // the telemetry state must be checked immediately so that shared serial ports are released.
829 telemetryCheckState();
830 mspSerialAllocatePorts();
833 #endif
834 // Sound a beeper if the flight mode state has changed
835 updateFlightModeChangeBeeper();
838 // Function for loop trigger
839 void FAST_CODE taskGyro(timeUs_t currentTimeUs) {
840 UNUSED(currentTimeUs);
841 // getTaskDeltaTime() returns delta time frozen at the moment of entering the scheduler. currentTime is frozen at the very same point.
842 // To make busy-waiting timeout work we need to account for time spent within busy-waiting loop
843 const timeDelta_t currentDeltaTime = getTaskDeltaTime(TASK_SELF);
845 /* Update actual hardware readings */
846 gyroUpdate();
848 #ifdef USE_OPFLOW
849 if (sensors(SENSOR_OPFLOW)) {
850 opflowGyroUpdateCallback(currentDeltaTime);
852 #endif
855 static void applyThrottleTiltCompensation(void)
857 if (STATE(MULTIROTOR)) {
858 int16_t thrTiltCompStrength = 0;
860 if (navigationRequiresThrottleTiltCompensation()) {
861 thrTiltCompStrength = 100;
863 else if (systemConfig()->throttle_tilt_compensation_strength && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
864 thrTiltCompStrength = systemConfig()->throttle_tilt_compensation_strength;
867 if (thrTiltCompStrength) {
868 const int throttleIdleValue = getThrottleIdleValue();
869 float tiltCompFactor = 1.0f / constrainf(calculateCosTiltAngle(), 0.6f, 1.0f); // max tilt about 50 deg
870 tiltCompFactor = 1.0f + (tiltCompFactor - 1.0f) * (thrTiltCompStrength / 100.f);
872 rcCommand[THROTTLE] = setDesiredThrottle(throttleIdleValue + (rcCommand[THROTTLE] - throttleIdleValue) * tiltCompFactor, false);
877 void taskMainPidLoop(timeUs_t currentTimeUs)
880 cycleTime = getTaskDeltaTime(TASK_SELF);
881 dT = (float)cycleTime * 0.000001f;
883 if (ARMING_FLAG(ARMED) && (!STATE(FIXED_WING_LEGACY) || !isNavLaunchEnabled() || (isNavLaunchEnabled() && fixedWingLaunchStatus() >= FW_LAUNCH_DETECTED))) {
884 flightTime += cycleTime;
885 armTime += cycleTime;
886 updateAccExtremes();
889 if (!ARMING_FLAG(ARMED)) {
890 armTime = 0;
892 // Delay saving for 0.5s to allow other functions to process save actions on disarm
893 if (currentTimeUs - lastDisarmTimeUs > USECS_PER_SEC / 2) {
894 processDelayedSave();
898 if (armTime > 1 * USECS_PER_SEC) { // reset in flight emerg rearm flag 1 sec after arming once it's served its purpose
899 DISABLE_STATE(IN_FLIGHT_EMERG_REARM);
902 #if defined(SITL_BUILD)
903 if (ARMING_FLAG(SIMULATOR_MODE_HITL) || lockMainPID()) {
904 #endif
906 gyroFilter();
908 imuUpdateAccelerometer();
909 imuUpdateAttitude(currentTimeUs);
911 #if defined(SITL_BUILD)
913 #endif
915 processPilotAndFailSafeActions(dT);
917 updateArmingStatus();
919 if (rxConfig()->rcFilterFrequency) {
920 rcInterpolationApply(isRXDataNew, currentTimeUs);
923 if (isRXDataNew) {
924 updateWaypointsAndNavigationMode();
926 isRXDataNew = false;
928 updatePositionEstimator();
929 applyWaypointNavigationAndAltitudeHold();
931 // Apply throttle tilt compensation
932 applyThrottleTiltCompensation();
934 #ifdef USE_POWER_LIMITS
935 powerLimiterApply(&rcCommand[THROTTLE]);
936 #endif
938 // Calculate stabilisation
939 pidController(dT);
941 mixTable();
943 if (isMixerUsingServos()) {
944 servoMixer(dT);
945 processServoAutotrim(dT);
948 //Servos should be filtered or written only when mixer is using servos or special feaures are enabled
950 #ifdef USE_SIMULATOR
951 if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) {
952 if (isServoOutputEnabled()) {
953 writeServos();
956 if (motorControlEnable) {
957 writeMotors();
960 #else
961 if (isServoOutputEnabled()) {
962 writeServos();
965 if (motorControlEnable) {
966 writeMotors();
968 #endif
969 // Check if landed, FW and MR
970 if (STATE(ALTITUDE_CONTROL)) {
971 updateLandingStatus(US2MS(currentTimeUs));
974 #ifdef USE_BLACKBOX
975 if (!cliMode && feature(FEATURE_BLACKBOX)) {
976 blackboxUpdate(micros());
978 #endif
981 // This function is called in a busy-loop, everything called from here should do it's own
982 // scheduling and avoid doing heavy calculations
983 void taskRunRealtimeCallbacks(timeUs_t currentTimeUs)
985 UNUSED(currentTimeUs);
987 #ifdef USE_SDCARD
988 afatfs_poll();
989 #endif
991 #ifdef USE_DSHOT
992 pwmCompleteMotorUpdate();
993 #endif
995 #ifdef USE_ESC_SENSOR
996 escSensorUpdate(currentTimeUs);
997 #endif
1000 bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
1002 UNUSED(currentDeltaTime);
1004 return rxUpdateCheck(currentTimeUs, currentDeltaTime);
1007 void taskUpdateRxMain(timeUs_t currentTimeUs)
1009 processRx(currentTimeUs);
1010 isRXDataNew = true;
1013 // returns seconds
1014 float getFlightTime(void)
1016 return US2S(flightTime);
1019 void resetFlightTime(void) {
1020 flightTime = 0;
1023 float getArmTime(void)
1025 return US2S(armTime);
1028 void fcReboot(bool bootLoader)
1030 // stop motor/servo outputs
1031 stopMotors();
1032 stopPwmAllMotors();
1034 // extra delay before reboot to give ESCs chance to reset
1035 delay(1000);
1037 if (bootLoader) {
1038 systemResetToBootloader();
1040 else {
1041 systemReset();
1044 while (true);