/* * This file is part of Cleanflight. * * Cleanflight is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * Cleanflight is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ #include #include #include #include #include "platform.h" #include "debug.h" #include "common/maths.h" #include "common/axis.h" #include "common/color.h" #include "common/utils.h" #include "common/filter.h" #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/compass.h" #include "drivers/light_led.h" #include "drivers/gpio.h" #include "drivers/system.h" #include "drivers/serial.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/gyro_sync.h" #include "sensors/sensors.h" #include "sensors/boardalignment.h" #include "sensors/sonar.h" #include "sensors/compass.h" #include "sensors/acceleration.h" #include "sensors/barometer.h" #include "sensors/gyro.h" #include "sensors/battery.h" #include "io/beeper.h" #include "io/display.h" #include "io/escservo.h" #include "io/rc_controls.h" #include "io/rc_curves.h" #include "io/gimbal.h" #include "io/gps.h" #include "io/ledstrip.h" #include "io/serial.h" #include "io/serial_cli.h" #include "io/serial_msp.h" #include "io/statusindicator.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/transponder_ir.h" #include "io/osd.h" #include "io/vtx.h" #include "rx/rx.h" #include "rx/msp.h" #include "telemetry/telemetry.h" #include "blackbox/blackbox.h" #include "flight/mixer.h" #include "flight/pid.h" #include "flight/imu.h" #include "flight/altitudehold.h" #include "flight/failsafe.h" #include "flight/gtune.h" #include "flight/navigation.h" #include "config/runtime_config.h" #include "config/config.h" #include "config/config_profile.h" #include "config/config_master.h" #include "scheduler/scheduler.h" #include "scheduler/scheduler_tasks.h" // June 2013 V2.2-dev enum { ALIGN_GYRO = 0, ALIGN_ACCEL = 1, ALIGN_MAG = 2 }; /* VBAT monitoring interval (in microseconds) - 1s*/ #define VBATINTERVAL (6 * 3500) /* IBat monitoring interval (in microseconds) - 6 default looptimes */ #define IBATINTERVAL (6 * 3500) #define GYRO_WATCHDOG_DELAY 80 // delay for gyro sync #define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine uint16_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 int16_t magHold; int16_t headFreeModeHold; uint8_t motorControlEnable = false; int16_t telemTemperature1; // gyro sensor temperature static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero extern uint32_t currentTime; extern uint8_t PIDweight[3]; uint16_t filteredCycleTime; static bool isRXDataNew; static bool armingCalibrationWasInitialised; float setpointRate[3]; float rcInput[3]; extern pidControllerFuncPtr pid_controller; void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta) { masterConfig.accelerometerTrims.values.roll += rollAndPitchTrimsDelta->values.roll; masterConfig.accelerometerTrims.values.pitch += rollAndPitchTrimsDelta->values.pitch; saveConfigAndNotify(); } #ifdef GTUNE void updateGtuneState(void) { static bool GTuneWasUsed = false; if (IS_RC_MODE_ACTIVE(BOXGTUNE)) { if (!FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { ENABLE_FLIGHT_MODE(GTUNE_MODE); init_Gtune(¤tProfile->pidProfile); GTuneWasUsed = true; } if (!FLIGHT_MODE(GTUNE_MODE) && !ARMING_FLAG(ARMED) && GTuneWasUsed) { saveConfigAndNotify(); GTuneWasUsed = false; } } else { if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { DISABLE_FLIGHT_MODE(GTUNE_MODE); } } } #endif bool isCalibrating() { #ifdef BARO if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) { return true; } #endif // Note: compass calibration is handled completely differently, outside of the main loop, see f.CALIBRATE_MAG return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete()); } float calculateSetpointRate(int axis, int16_t rc) { float angleRate; if (isSuperExpoActive()) { rcInput[axis] = (axis == YAW) ? (ABS(rc) / (500.0f * (currentControlRateProfile->rcYawRate8 / 100.0f))) : (ABS(rc) / (500.0f * (currentControlRateProfile->rcRate8 / 100.0f))); float rcFactor = 1.0f / (constrainf(1.0f - (rcInput[axis] * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f)); angleRate = rcFactor * ((27 * rc) / 16.0f); } else { angleRate = (float)((currentControlRateProfile->rates[axis] + 27) * rc) / 16.0f; } if (currentProfile->pidProfile.pidController == PID_CONTROLLER_LEGACY) return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection else return constrainf(angleRate / 4.1f, -1997.0f, 1997.0f); // Rate limit protection (deg/sec) } void scaleRcCommandToFpvCamAngle(void) { //recalculate sin/cos only when masterConfig.rxConfig.fpvCamAngleDegrees changed static uint8_t lastFpvCamAngleDegrees = 0; static float cosFactor = 1.0; static float sinFactor = 0.0; if (lastFpvCamAngleDegrees != masterConfig.rxConfig.fpvCamAngleDegrees){ lastFpvCamAngleDegrees = masterConfig.rxConfig.fpvCamAngleDegrees; cosFactor = cos_approx(masterConfig.rxConfig.fpvCamAngleDegrees * RAD); sinFactor = sin_approx(masterConfig.rxConfig.fpvCamAngleDegrees * RAD); } int16_t roll = setpointRate[ROLL]; int16_t yaw = setpointRate[YAW]; setpointRate[ROLL] = constrain(roll * cosFactor - yaw * sinFactor, -500, 500); setpointRate[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500); } void processRcCommand(void) { static int16_t lastCommand[4] = { 0, 0, 0, 0 }; static int16_t deltaRC[4] = { 0, 0, 0, 0 }; static int16_t factor, rcInterpolationFactor; uint16_t rxRefreshRate; bool readyToCalculateRate = false; if (masterConfig.rxConfig.rcInterpolation || flightModeFlags) { if (isRXDataNew) { // Set RC refresh rate for sampling and channels to filter switch (masterConfig.rxConfig.rcInterpolation) { case(RC_SMOOTHING_AUTO): rxRefreshRate = constrain(getTaskDeltaTime(TASK_RX), 1000, 20000) + 1000; // Add slight overhead to prevent ramps break; case(RC_SMOOTHING_MANUAL): rxRefreshRate = 1000 * masterConfig.rxConfig.rcInterpolationInterval; break; case(RC_SMOOTHING_OFF): case(RC_SMOOTHING_DEFAULT): default: initRxRefreshRate(&rxRefreshRate); } rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1; if (debugMode == DEBUG_RC_INTERPOLATION) { for (int axis = 0; axis < 2; axis++) debug[axis] = rcCommand[axis]; debug[3] = rxRefreshRate; } for (int channel=0; channel < 4; channel++) { deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); lastCommand[channel] = rcCommand[channel]; } factor = rcInterpolationFactor - 1; } else { factor--; } // Interpolate steps of rcCommand if (factor > 0) { for (int channel=0; channel < 4; channel++) rcCommand[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; } else { factor = 0; } readyToCalculateRate = true; } else { factor = 0; // reset factor in case of level modes flip flopping } if (readyToCalculateRate || isRXDataNew) { for (int axis = 0; axis < 3; axis++) setpointRate[axis] = calculateSetpointRate(axis, rcCommand[axis]); isRXDataNew = false; // Scaling of AngleRate to camera angle (Mixing Roll and Yaw) if (masterConfig.rxConfig.fpvCamAngleDegrees && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && !FLIGHT_MODE(HEADFREE_MODE)) scaleRcCommandToFpvCamAngle(); } } static void updateRcCommands(void) { // PITCH & ROLL only dynamic PID adjustment, depending on throttle value int32_t prop; if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) { prop = 100; } else { if (rcData[THROTTLE] < 2000) { prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint); } else { prop = 100 - currentControlRateProfile->dynThrPID; } } for (int axis = 0; axis < 3; axis++) { // non coupled PID reduction scaler used in PID controller 1 and PID controller 2. PIDweight[axis] = prop; int32_t tmp = MIN(ABS(rcData[axis] - masterConfig.rxConfig.midrc), 500); if (axis == ROLL || axis == PITCH) { if (tmp > masterConfig.rcControlsConfig.deadband) { tmp -= masterConfig.rcControlsConfig.deadband; } else { tmp = 0; } rcCommand[axis] = rcLookup(tmp, currentControlRateProfile->rcExpo8, currentControlRateProfile->rcRate8); } else if (axis == YAW) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { tmp -= masterConfig.rcControlsConfig.yaw_deadband; } else { tmp = 0; } rcCommand[axis] = rcLookup(tmp, currentControlRateProfile->rcYawExpo8, currentControlRateProfile->rcYawRate8) * -masterConfig.yaw_control_direction;; } if (rcData[axis] < masterConfig.rxConfig.midrc) { rcCommand[axis] = -rcCommand[axis]; } } int32_t tmp; if (feature(FEATURE_3D)) { tmp = constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX); tmp = (uint32_t)(tmp - PWM_RANGE_MIN); } else { tmp = constrain(rcData[THROTTLE], masterConfig.rxConfig.mincheck, PWM_RANGE_MAX); tmp = (uint32_t)(tmp - masterConfig.rxConfig.mincheck) * PWM_RANGE_MIN / (PWM_RANGE_MAX - masterConfig.rxConfig.mincheck); } rcCommand[THROTTLE] = rcLookupThrottle(tmp); if (feature(FEATURE_3D) && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH) && !failsafeIsActive()) { fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000); rcCommand[THROTTLE] = masterConfig.rxConfig.midrc + qMultiply(throttleScaler, PWM_RANGE_MAX - masterConfig.rxConfig.midrc); } if (FLIGHT_MODE(HEADFREE_MODE)) { const float radDiff = degreesToRadians(DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headFreeModeHold); const float cosDiff = cos_approx(radDiff); const float sinDiff = sin_approx(radDiff); const int16_t rcCommand_PITCH = rcCommand[PITCH] * cosDiff + rcCommand[ROLL] * sinDiff; rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff; rcCommand[PITCH] = rcCommand_PITCH; } } static void updateLEDs(void) { if (ARMING_FLAG(ARMED)) { LED0_ON; } else { if (IS_RC_MODE_ACTIVE(BOXARM) == 0 || armingCalibrationWasInitialised) { ENABLE_ARMING_FLAG(OK_TO_ARM); } if (!STATE(SMALL_ANGLE)) { DISABLE_ARMING_FLAG(OK_TO_ARM); } if (isCalibrating() || (averageSystemLoadPercent > 100)) { warningLedFlash(); DISABLE_ARMING_FLAG(OK_TO_ARM); } else { if (ARMING_FLAG(OK_TO_ARM)) { warningLedDisable(); } else { warningLedFlash(); } } warningLedUpdate(); } } void mwDisarm(void) { armingCalibrationWasInitialised = false; if (ARMING_FLAG(ARMED)) { DISABLE_ARMING_FLAG(ARMED); #ifdef BLACKBOX if (feature(FEATURE_BLACKBOX)) { finishBlackbox(); } #endif beeper(BEEPER_DISARMING); // emit disarm tone } } #define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT) void releaseSharedTelemetryPorts(void) { serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); while (sharedPort) { mspReleasePortIfAllocated(sharedPort); sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); } } void mwArm(void) { static bool firstArmingCalibrationWasCompleted; if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) { gyroSetCalibrationCycles(); armingCalibrationWasInitialised = true; firstArmingCalibrationWasCompleted = true; } if (!isGyroCalibrationComplete()) return; // prevent arming before gyro is calibrated if (ARMING_FLAG(OK_TO_ARM)) { if (ARMING_FLAG(ARMED)) { return; } if (IS_RC_MODE_ACTIVE(BOXFAILSAFE)) { return; } if (!ARMING_FLAG(PREVENT_ARMING)) { ENABLE_ARMING_FLAG(ARMED); ENABLE_ARMING_FLAG(WAS_EVER_ARMED); headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); #ifdef BLACKBOX if (feature(FEATURE_BLACKBOX)) { serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP); if (sharedBlackboxAndMspPort) { mspReleasePortIfAllocated(sharedBlackboxAndMspPort); } startBlackbox(); } #endif disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero //beep to indicate arming #ifdef GPS if (feature(FEATURE_GPS) && STATE(GPS_FIX) && GPS_numSat >= 5) beeper(BEEPER_ARMING_GPS_FIX); else beeper(BEEPER_ARMING); #else beeper(BEEPER_ARMING); #endif return; } } if (!ARMING_FLAG(ARMED)) { beeperConfirmationBeeps(1); } } // Automatic ACC Offset Calibration bool AccInflightCalibrationArmed = false; bool AccInflightCalibrationMeasurementDone = false; bool AccInflightCalibrationSavetoEEProm = false; bool AccInflightCalibrationActive = false; uint16_t InflightcalibratingA = 0; void handleInflightCalibrationStickPosition(void) { if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing AccInflightCalibrationMeasurementDone = false; AccInflightCalibrationSavetoEEProm = true; } else { AccInflightCalibrationArmed = !AccInflightCalibrationArmed; if (AccInflightCalibrationArmed) { beeper(BEEPER_ACC_CALIBRATION); } else { beeper(BEEPER_ACC_CALIBRATION_FAIL); } } } static void updateInflightCalibrationState(void) { if (AccInflightCalibrationArmed && ARMING_FLAG(ARMED) && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !IS_RC_MODE_ACTIVE(BOXARM)) { // Copter is airborne and you are turning it off via boxarm : start measurement InflightcalibratingA = 50; AccInflightCalibrationArmed = false; } if (IS_RC_MODE_ACTIVE(BOXCALIB)) { // Use the Calib Option to activate : Calib = TRUE measurement started, Land and Calib = 0 measurement stored if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone) InflightcalibratingA = 50; AccInflightCalibrationActive = true; } else if (AccInflightCalibrationMeasurementDone && !ARMING_FLAG(ARMED)) { AccInflightCalibrationMeasurementDone = false; AccInflightCalibrationSavetoEEProm = true; } } void updateMagHold(void) { if (ABS(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) { int16_t dif = DECIDEGREES_TO_DEGREES(attitude.values.yaw) - magHold; if (dif <= -180) dif += 360; if (dif >= +180) dif -= 360; dif *= -masterConfig.yaw_control_direction; if (STATE(SMALL_ANGLE)) rcCommand[YAW] -= dif * currentProfile->pidProfile.P8[PIDMAG] / 30; // 18 deg } else magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); } void processRx(void) { static bool armedBeeperOn = false; static bool airmodeIsActivated; calculateRxChannelsAndUpdateFailsafe(currentTime); // in 3D mode, we need to be able to disarm by switch at any time if (feature(FEATURE_3D)) { if (!IS_RC_MODE_ACTIVE(BOXARM)) mwDisarm(); } updateRSSI(currentTime); if (feature(FEATURE_FAILSAFE)) { if (currentTime > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) { failsafeStartMonitoring(); } failsafeUpdateState(); } throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); if (isAirmodeActive() && ARMING_FLAG(ARMED)) { if (rcCommand[THROTTLE] >= masterConfig.rxConfig.airModeActivateThreshold) airmodeIsActivated = true; // Prevent Iterm from being reset } else { airmodeIsActivated = false; } /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */ if (throttleStatus == THROTTLE_LOW && !airmodeIsActivated) { pidResetErrorGyroState(); if (currentProfile->pidProfile.pidAtMinThrottle) pidStabilisationState(PID_STABILISATION_ON); else pidStabilisationState(PID_STABILISATION_OFF); } else { pidStabilisationState(PID_STABILISATION_ON); } // When armed and motors aren't spinning, do beeps and then disarm // board after delay so users without buzzer won't lose fingers. // mixTable constrains motor commands, so checking throttleStatus is enough if (ARMING_FLAG(ARMED) && feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING) ) { if (isUsingSticksForArming()) { if (throttleStatus == THROTTLE_LOW) { if (masterConfig.auto_disarm_delay != 0 && (int32_t)(disarmAt - millis()) < 0 ) { // auto-disarm configured and delay is over mwDisarm(); armedBeeperOn = false; } else { // still armed; do warning beeps while armed beeper(BEEPER_ARMED); armedBeeperOn = true; } } else { // throttle is not low if (masterConfig.auto_disarm_delay != 0) { // extend disarm time disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; } if (armedBeeperOn) { beeperSilence(); armedBeeperOn = false; } } } else { // arming is via AUX switch; beep while throttle low if (throttleStatus == THROTTLE_LOW) { beeper(BEEPER_ARMED); armedBeeperOn = true; } else if (armedBeeperOn) { beeperSilence(); armedBeeperOn = false; } } } processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.disarm_kill_switch); if (feature(FEATURE_INFLIGHT_ACC_CAL)) { updateInflightCalibrationState(); } updateActivatedModes(masterConfig.modeActivationConditions); if (!cliMode) { updateAdjustmentStates(masterConfig.adjustmentRanges); processRcAdjustments(currentControlRateProfile, &masterConfig.rxConfig); } bool canUseHorizonMode = true; if ((IS_RC_MODE_ACTIVE(BOXANGLE) || (feature(FEATURE_FAILSAFE) && failsafeIsActive())) && (sensors(SENSOR_ACC))) { // bumpless transfer to Level mode canUseHorizonMode = false; if (!FLIGHT_MODE(ANGLE_MODE)) { ENABLE_FLIGHT_MODE(ANGLE_MODE); } } else { DISABLE_FLIGHT_MODE(ANGLE_MODE); // failsafe support } if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) { DISABLE_FLIGHT_MODE(ANGLE_MODE); if (!FLIGHT_MODE(HORIZON_MODE)) { ENABLE_FLIGHT_MODE(HORIZON_MODE); } } else { DISABLE_FLIGHT_MODE(HORIZON_MODE); } if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { LED1_ON; } else { LED1_OFF; } #ifdef MAG if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) { if (IS_RC_MODE_ACTIVE(BOXMAG)) { if (!FLIGHT_MODE(MAG_MODE)) { ENABLE_FLIGHT_MODE(MAG_MODE); magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); } } else { DISABLE_FLIGHT_MODE(MAG_MODE); } if (IS_RC_MODE_ACTIVE(BOXHEADFREE)) { if (!FLIGHT_MODE(HEADFREE_MODE)) { ENABLE_FLIGHT_MODE(HEADFREE_MODE); } } else { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } if (IS_RC_MODE_ACTIVE(BOXHEADADJ)) { headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); // acquire new heading } } #endif #ifdef GPS if (sensors(SENSOR_GPS)) { updateGpsWaypointsAndMode(); } #endif if (IS_RC_MODE_ACTIVE(BOXPASSTHRU)) { ENABLE_FLIGHT_MODE(PASSTHRU_MODE); } else { DISABLE_FLIGHT_MODE(PASSTHRU_MODE); } if (masterConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerMode == MIXER_AIRPLANE) { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } #ifdef TELEMETRY if (feature(FEATURE_TELEMETRY)) { if ((!masterConfig.telemetryConfig.telemetry_switch && ARMING_FLAG(ARMED)) || (masterConfig.telemetryConfig.telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) { releaseSharedTelemetryPorts(); } else { // the telemetry state must be checked immediately so that shared serial ports are released. telemetryCheckState(); mspAllocateSerialPorts(&masterConfig.serialConfig); } } #endif #ifdef VTX vtxUpdateActivatedChannel(); #endif } void subTaskPidController(void) { const uint32_t startTime = micros(); // PID - note this is function pointer set by setPIDController() pid_controller( ¤tProfile->pidProfile, masterConfig.max_angle_inclination, &masterConfig.accelerometerTrims, &masterConfig.rxConfig ); if (debugMode == DEBUG_PIDLOOP) {debug[2] = micros() - startTime;} } void subTaskMainSubprocesses(void) { const uint32_t startTime = micros(); // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. if (gyro.temperature) { gyro.temperature(&telemTemperature1); } #ifdef MAG if (sensors(SENSOR_MAG)) { updateMagHold(); } #endif #ifdef GTUNE updateGtuneState(); #endif #if defined(BARO) || defined(SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { applyAltHold(&masterConfig.airplaneConfig); } } #endif // If we're armed, at minimum throttle, and we do arming via the // sticks, do not process yaw input from the rx. We do this so the // motors do not spin up while we are trying to arm or disarm. // Allow yaw control for tricopters if the user wants the servo to move even when unarmed. if (isUsingSticksForArming() && rcData[THROTTLE] <= masterConfig.rxConfig.mincheck #ifndef USE_QUAD_MIXER_ONLY #ifdef USE_SERVOS && !((masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI) && masterConfig.mixerConfig.tri_unarmed_servo) #endif && masterConfig.mixerMode != MIXER_AIRPLANE && masterConfig.mixerMode != MIXER_FLYING_WING #endif ) { rcCommand[YAW] = 0; setpointRate[YAW] = 0; } if (masterConfig.throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) { rcCommand[THROTTLE] += calculateThrottleAngleCorrection(masterConfig.throttle_correction_value); } processRcCommand(); #ifdef GPS if (sensors(SENSOR_GPS)) { if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) { updateGpsStateForHomeAndHoldMode(); } } #endif #ifdef USE_SDCARD afatfs_poll(); #endif #ifdef BLACKBOX if (!cliMode && feature(FEATURE_BLACKBOX)) { handleBlackbox(); } #endif #ifdef TRANSPONDER updateTransponder(); #endif if (debugMode == DEBUG_PIDLOOP) {debug[1] = micros() - startTime;} } void subTaskMotorUpdate(void) { const uint32_t startTime = micros(); if (debugMode == DEBUG_CYCLETIME) { static uint32_t previousMotorUpdateTime; const uint32_t currentDeltaTime = startTime - previousMotorUpdateTime; debug[2] = currentDeltaTime; debug[3] = currentDeltaTime - targetPidLooptime; previousMotorUpdateTime = startTime; } mixTable(¤tProfile->pidProfile); #ifdef USE_SERVOS filterServos(); writeServos(); #endif if (motorControlEnable) { writeMotors(); } if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;} } uint8_t setPidUpdateCountDown(void) { if (masterConfig.gyro_soft_lpf_hz) { return masterConfig.pid_process_denom - 1; } else { return 1; } } // Function for loop trigger void taskMainPidLoopCheck(void) { static uint32_t previousTime; static bool runTaskMainSubprocesses; const uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF); cycleTime = micros() - previousTime; previousTime = micros(); if (debugMode == DEBUG_CYCLETIME) { debug[0] = cycleTime; debug[1] = averageSystemLoadPercent; } const uint32_t startTime = micros(); while (true) { if (gyroSyncCheckUpdate(&gyro) || ((currentDeltaTime + (micros() - previousTime)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) { static uint8_t pidUpdateCountdown; if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting if (runTaskMainSubprocesses) { subTaskMainSubprocesses(); runTaskMainSubprocesses = false; } gyroUpdate(); if (pidUpdateCountdown) { pidUpdateCountdown--; } else { pidUpdateCountdown = setPidUpdateCountDown(); subTaskPidController(); subTaskMotorUpdate(); runTaskMainSubprocesses = true; } break; } } } void taskUpdateAccelerometer(void) { imuUpdateAccelerometer(&masterConfig.accelerometerTrims); } void taskUpdateAttitude(void) { imuUpdateAttitude(); } void taskHandleSerial(void) { handleSerial(); } void taskUpdateBeeper(void) { beeperUpdate(); //call periodic beeper handler } void taskUpdateBattery(void) { #ifdef USE_ADC static uint32_t vbatLastServiced = 0; if (feature(FEATURE_VBAT)) { if (cmp32(currentTime, vbatLastServiced) >= VBATINTERVAL) { vbatLastServiced = currentTime; updateBattery(); } } #endif static uint32_t ibatLastServiced = 0; if (feature(FEATURE_CURRENT_METER)) { int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced); if (ibatTimeSinceLastServiced >= IBATINTERVAL) { ibatLastServiced = currentTime; updateCurrentMeter(ibatTimeSinceLastServiced, &masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); } } } bool taskUpdateRxCheck(uint32_t currentDeltaTime) { UNUSED(currentDeltaTime); updateRx(currentTime); return shouldProcessRx(currentTime); } void taskUpdateRxMain(void) { processRx(); isRXDataNew = true; #if !defined(BARO) && !defined(SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); #endif updateLEDs(); #ifdef BARO if (sensors(SENSOR_BARO)) { updateAltHoldState(); } #endif #ifdef SONAR if (sensors(SENSOR_SONAR)) { updateSonarAltHoldState(); } #endif } #ifdef GPS void taskProcessGPS(void) { // if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck // hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will // change this based on available hardware if (feature(FEATURE_GPS)) { gpsThread(); } if (sensors(SENSOR_GPS)) { updateGpsIndicator(currentTime); } } #endif #ifdef MAG void taskUpdateCompass(void) { if (sensors(SENSOR_MAG)) { updateCompass(&masterConfig.magZero); } } #endif #ifdef BARO void taskUpdateBaro(void) { if (sensors(SENSOR_BARO)) { uint32_t newDeadline = baroUpdate(); rescheduleTask(TASK_SELF, newDeadline); } } #endif #ifdef SONAR void taskUpdateSonar(void) { if (sensors(SENSOR_SONAR)) { sonarUpdate(); } } #endif #if defined(BARO) || defined(SONAR) void taskCalculateAltitude(void) { if (false #if defined(BARO) || (sensors(SENSOR_BARO) && isBaroReady()) #endif #if defined(SONAR) || sensors(SENSOR_SONAR) #endif ) { calculateEstimatedAltitude(currentTime); }} #endif #ifdef DISPLAY void taskUpdateDisplay(void) { if (feature(FEATURE_DISPLAY)) { updateDisplay(); } } #endif #ifdef TELEMETRY void taskTelemetry(void) { telemetryCheckState(); if (!cliMode && feature(FEATURE_TELEMETRY)) { telemetryProcess(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); } } #endif #ifdef LED_STRIP void taskLedStrip(void) { if (feature(FEATURE_LED_STRIP)) { updateLedStrip(); } } #endif #ifdef TRANSPONDER void taskTransponder(void) { if (feature(FEATURE_TRANSPONDER)) { updateTransponder(); } } #endif #ifdef OSD void taskUpdateOsd(void) { if (feature(FEATURE_OSD)) { updateOsd(); } } #endif