diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 46a1bb9135..7395cf1660 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -448,7 +448,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) #endif case FLIGHT_LOG_FIELD_CONDITION_RSSI: - return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC); + return rxConfig()->rssi_channel > 0 || featureConfigured(FEATURE_RSSI_ADC); case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME: return blackboxConfig()->p_ratio != 1; @@ -1488,7 +1488,7 @@ STATIC_UNIT_TESTED void blackboxLogIteration(timeUs_t currentTimeUs) writeInterframe(); } #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { if (blackboxShouldLogGpsHomeFrame()) { writeGPSHomeFrame(); writeGPSFrame(currentTimeUs); @@ -1554,7 +1554,7 @@ void blackboxUpdate(timeUs_t currentTimeUs) if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER); } else #endif diff --git a/src/main/cms/cms_menu_ledstrip.c b/src/main/cms/cms_menu_ledstrip.c index 335e3972a9..f8ef00f7fa 100644 --- a/src/main/cms/cms_menu_ledstrip.c +++ b/src/main/cms/cms_menu_ledstrip.c @@ -48,7 +48,7 @@ static uint8_t cmsx_FeatureLedstrip; static long cmsx_Ledstrip_FeatureRead(void) { if (!featureRead) { - cmsx_FeatureLedstrip = feature(FEATURE_LED_STRIP) ? 1 : 0; + cmsx_FeatureLedstrip = featureConfigured(FEATURE_LED_STRIP) ? 1 : 0; featureRead = true; } diff --git a/src/main/config/feature.c b/src/main/config/feature.c index f054c12bd8..a1ce317e5e 100644 --- a/src/main/config/feature.c +++ b/src/main/config/feature.c @@ -29,8 +29,6 @@ #include "pg/pg_ids.h" -static uint32_t activeFeaturesLatch = 0; - PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0); PG_RESET_TEMPLATE(featureConfig_t, featureConfig, @@ -52,21 +50,11 @@ void intFeatureClearAll(uint32_t *features) *features = 0; } -void latchActiveFeatures(void) -{ - activeFeaturesLatch = featureConfig()->enabledFeatures; -} - bool featureConfigured(uint32_t mask) { return featureConfig()->enabledFeatures & mask; } -bool feature(uint32_t mask) -{ - return activeFeaturesLatch & mask; -} - void featureSet(uint32_t mask) { intFeatureSet(mask, &featureConfigMutable()->enabledFeatures); diff --git a/src/main/config/feature.h b/src/main/config/feature.h index 56ee75a5b9..a0d0b16e6a 100644 --- a/src/main/config/feature.h +++ b/src/main/config/feature.h @@ -62,9 +62,7 @@ typedef struct featureConfig_s { PG_DECLARE(featureConfig_t, featureConfig); -void latchActiveFeatures(void); bool featureConfigured(uint32_t mask); -bool feature(uint32_t mask); void featureSet(uint32_t mask); void featureClear(uint32_t mask); void featureClearAll(void); diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index e97cb2e12e..93806febb7 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -268,7 +268,7 @@ void updateArmingStatus(void) && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_CALIBRATING)); /* Ignore ARMING_DISABLED_THROTTLE (once arm switch is on) if we are in 3D mode */ - bool ignoreThrottle = feature(FEATURE_3D) + bool ignoreThrottle = featureConfigured(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3D) && !flight3DConfig()->switched_mode3d && !(getArmingDisableFlags() & ~(ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_THROTTLE)); @@ -313,7 +313,7 @@ void disarm(void) #endif BEEP_OFF; #ifdef USE_DSHOT - if (isMotorProtocolDshot() && flipOverAfterCrashMode && !feature(FEATURE_3D)) { + if (isMotorProtocolDshot() && flipOverAfterCrashMode && !featureConfigured(FEATURE_3D)) { pwmWriteDshotCommand(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, false); } #endif @@ -352,7 +352,7 @@ void tryArm(void) if (isMotorProtocolDshot() && isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH)) { if (!(IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) || (tryingToArm == ARMING_DELAYED_CRASHFLIP))) { flipOverAfterCrashMode = false; - if (!feature(FEATURE_3D)) { + if (!featureConfigured(FEATURE_3D)) { pwmWriteDshotCommand(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, false); } } else { @@ -360,7 +360,7 @@ void tryArm(void) #ifdef USE_RUNAWAY_TAKEOFF runawayTakeoffCheckDisabled = false; #endif - if (!feature(FEATURE_3D)) { + if (!featureConfigured(FEATURE_3D)) { pwmWriteDshotCommand(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_REVERSED, false); } } @@ -387,7 +387,7 @@ void tryArm(void) //beep to indicate arming #ifdef USE_GPS - if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) { + if (featureConfigured(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) { beeper(BEEPER_ARMING_GPS_FIX); } else { beeper(BEEPER_ARMING); @@ -517,7 +517,7 @@ void runawayTakeoffTemporaryDisable(uint8_t disableFlag) uint8_t calculateThrottlePercent(void) { uint8_t ret = 0; - if (feature(FEATURE_3D) + if (featureConfigured(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3D) && !flight3DConfig()->switched_mode3d) { @@ -560,7 +560,7 @@ bool processRx(timeUs_t currentTimeUs) } // in 3D mode, we need to be able to disarm by switch at any time - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { if (!IS_RC_MODE_ACTIVE(BOXARM)) disarm(); } @@ -615,7 +615,7 @@ bool processRx(timeUs_t currentTimeUs) // - sticks are active and have deflection greater than runaway_takeoff_deactivate_stick_percent // - pidSum on all axis is less then runaway_takeoff_deactivate_pidlimit bool inStableFlight = false; - if (!feature(FEATURE_MOTOR_STOP) || isAirmodeActive() || (throttleStatus != THROTTLE_LOW)) { // are motors running? + if (!featureConfigured(FEATURE_MOTOR_STOP) || isAirmodeActive() || (throttleStatus != THROTTLE_LOW)) { // are motors running? const uint8_t lowThrottleLimit = pidConfig()->runaway_takeoff_deactivate_throttle; const uint8_t midThrottleLimit = constrain(lowThrottleLimit * 2, lowThrottleLimit * 2, RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT); if ((((throttlePercent >= lowThrottleLimit) && areSticksActive(RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT)) || (throttlePercent >= midThrottleLimit)) @@ -667,9 +667,9 @@ bool processRx(timeUs_t currentTimeUs) // 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) + && featureConfigured(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING) - && !feature(FEATURE_3D) + && !featureConfigured(FEATURE_3D) && !isAirmodeActive() ) { if (isUsingSticksForArming()) { @@ -711,7 +711,7 @@ bool processRx(timeUs_t currentTimeUs) processRcStickPositions(); - if (feature(FEATURE_INFLIGHT_ACC_CAL)) { + if (featureConfigured(FEATURE_INFLIGHT_ACC_CAL)) { updateInflightCalibrationState(); } @@ -814,7 +814,7 @@ bool processRx(timeUs_t currentTimeUs) } #ifdef USE_TELEMETRY - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { bool enableSharedPortTelemetry = (!isModeActivationConditionPresent(BOXTELEMETRY) && ARMING_FLAG(ARMED)) || (isModeActivationConditionPresent(BOXTELEMETRY) && IS_RC_MODE_ACTIVE(BOXTELEMETRY)); if (enableSharedPortTelemetry && !sharedPortTelemetryEnabled) { mspSerialReleaseSharedTelemetryPorts(); @@ -872,7 +872,7 @@ static FAST_CODE void subTaskPidController(timeUs_t currentTimeUs) && !runawayTakeoffCheckDisabled && !flipOverAfterCrashMode && !runawayTakeoffTemporarilyDisabled - && (!feature(FEATURE_MOTOR_STOP) || isAirmodeActive() || (calculateThrottleStatus() != THROTTLE_LOW))) { + && (!featureConfigured(FEATURE_MOTOR_STOP) || isAirmodeActive() || (calculateThrottleStatus() != THROTTLE_LOW))) { if (((fabsf(pidData[FD_PITCH].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD) || (fabsf(pidData[FD_ROLL].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD) diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 4f077fa559..185b1b0e91 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -255,9 +255,6 @@ void init(void) debugMode = systemConfig()->debug_mode; - // Latch active features to be used for feature() in the remainder of init(). - latchActiveFeatures(); - #ifdef TARGET_PREINIT targetPreInit(); #endif @@ -299,7 +296,7 @@ void init(void) #endif #if defined(USE_SPEKTRUM_BIND) - if (feature(FEATURE_RX_SERIAL)) { + if (featureConfigured(FEATURE_RX_SERIAL)) { switch (rxConfig()->serialrx_provider) { case SERIALRX_SPEKTRUM1024: case SERIALRX_SPEKTRUM2048: @@ -330,23 +327,23 @@ void init(void) #endif #if defined(AVOID_UART1_FOR_PWM_PPM) - serialInit(feature(FEATURE_SOFTSERIAL), - feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE); + serialInit(featureConfigured(FEATURE_SOFTSERIAL), + featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE); #elif defined(AVOID_UART2_FOR_PWM_PPM) - serialInit(feature(FEATURE_SOFTSERIAL), - feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE); + serialInit(featureConfigured(FEATURE_SOFTSERIAL), + featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE); #elif defined(AVOID_UART3_FOR_PWM_PPM) - serialInit(feature(FEATURE_SOFTSERIAL), - feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE); + serialInit(featureConfigured(FEATURE_SOFTSERIAL), + featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE); #else - serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE); + serialInit(featureConfigured(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE); #endif mixerInit(mixerConfig()->mixerMode); mixerConfigureOutput(); uint16_t idlePulse = motorConfig()->mincommand; - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { idlePulse = flight3DConfig()->neutral3d; } if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) { @@ -360,12 +357,12 @@ void init(void) if (0) {} #if defined(USE_PPM) - else if (feature(FEATURE_RX_PPM)) { + else if (featureConfigured(FEATURE_RX_PPM)) { ppmRxInit(ppmConfig()); } #endif #if defined(USE_PWM) - else if (feature(FEATURE_RX_PARALLEL_PWM)) { + else if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { pwmRxInit(pwmConfig()); } #endif @@ -452,13 +449,13 @@ void init(void) // XXX These kind of code should goto target/config.c? // XXX And these no longer work properly as FEATURE_RANGEFINDER does control HCSR04 runtime configuration. #if defined(RANGEFINDER_HCSR04_SOFTSERIAL2_EXCLUSIVE) && defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL2) - if (feature(FEATURE_RANGEFINDER) && feature(FEATURE_SOFTSERIAL)) { + if (featureConfigured(FEATURE_RANGEFINDER) && featureConfigured(FEATURE_SOFTSERIAL)) { serialRemovePort(SERIAL_PORT_SOFTSERIAL2); } #endif #if defined(RANGEFINDER_HCSR04_SOFTSERIAL1_EXCLUSIVE) && defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL1) - if (feature(FEATURE_RANGEFINDER) && feature(FEATURE_SOFTSERIAL)) { + if (featureConfigured(FEATURE_RANGEFINDER) && featureConfigured(FEATURE_SOFTSERIAL)) { serialRemovePort(SERIAL_PORT_SOFTSERIAL1); } #endif @@ -468,9 +465,9 @@ void init(void) adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC); // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2 - adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC); + adcConfigMutable()->rssi.enabled = featureConfigured(FEATURE_RSSI_ADC); #ifdef USE_RX_SPI - adcConfigMutable()->rssi.enabled |= (feature(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D); + adcConfigMutable()->rssi.enabled |= (featureConfigured(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D); #endif adcInit(adcConfig()); #endif @@ -499,7 +496,7 @@ void init(void) servosInit(); servoConfigureOutput(); if (isMixerUsingServos()) { - //pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING); + //pwm_params.useChannelForwarding = featureConfigured(FEATURE_CHANNEL_FORWARDING); servoDevInit(&servoConfig()->dev); } servosFilterInit(); @@ -561,7 +558,7 @@ void init(void) #if defined(USE_OSD) && !defined(USE_OSD_SLAVE) //The OSD need to be initialised after GYRO to avoid GYRO initialisation failure on some targets - if (feature(FEATURE_OSD)) { + if (featureConfigured(FEATURE_OSD)) { #if defined(USE_MAX7456) // If there is a max7456 chip for the OSD then use it osdDisplayPort = max7456DisplayPortInit(vcdProfile()); @@ -590,7 +587,7 @@ void init(void) #ifdef USE_DASHBOARD // Dashbord will register with CMS by itself. - if (feature(FEATURE_DASHBOARD)) { + if (featureConfigured(FEATURE_DASHBOARD)) { dashboardInit(); } #endif @@ -601,7 +598,7 @@ void init(void) #endif #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { gpsInit(); } #endif @@ -609,19 +606,19 @@ void init(void) #ifdef USE_LED_STRIP ledStripInit(); - if (feature(FEATURE_LED_STRIP)) { + if (featureConfigured(FEATURE_LED_STRIP)) { ledStripEnable(); } #endif #ifdef USE_TELEMETRY - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { telemetryInit(); } #endif #ifdef USE_ESC_SENSOR - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { escSensorInit(); } #endif @@ -631,7 +628,7 @@ void init(void) #endif #ifdef USE_TRANSPONDER - if (feature(FEATURE_TRANSPONDER)) { + if (featureConfigured(FEATURE_TRANSPONDER)) { transponderInit(); transponderStartRepeating(); systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED; @@ -714,7 +711,7 @@ void init(void) batteryInit(); // always needs doing, regardless of features. #ifdef USE_DASHBOARD - if (feature(FEATURE_DASHBOARD)) { + if (featureConfigured(FEATURE_DASHBOARD)) { #ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY dashboardShowFixedPage(PAGE_GPS); #else @@ -728,8 +725,6 @@ void init(void) rcdeviceInit(); #endif // USE_RCDEVICE - // Latch active features AGAIN since some may be modified by init(). - latchActiveFeatures(); pwmEnableMotors(); setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME); diff --git a/src/main/fc/fc_rc.c b/src/main/fc/fc_rc.c index 7a68797ced..eca6e1be25 100644 --- a/src/main/fc/fc_rc.c +++ b/src/main/fc/fc_rc.c @@ -203,7 +203,7 @@ static void checkForThrottleErrorResetState(uint16_t rxRefreshRate) const int rxRefreshRateMs = rxRefreshRate / 1000; const int indexMax = constrain(THROTTLE_DELTA_MS / rxRefreshRateMs, 1, THROTTLE_BUFFER_MAX); - const int16_t throttleVelocityThreshold = (feature(FEATURE_3D)) ? currentPidProfile->itermThrottleThreshold / 2 : currentPidProfile->itermThrottleThreshold; + const int16_t throttleVelocityThreshold = (featureConfigured(FEATURE_3D)) ? currentPidProfile->itermThrottleThreshold / 2 : currentPidProfile->itermThrottleThreshold; rcCommandThrottlePrevious[index++] = rcCommand[THROTTLE]; if (index >= indexMax) { @@ -621,7 +621,7 @@ FAST_CODE FAST_CODE_NOINLINE void updateRcCommands(void) } int32_t tmp; - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { tmp = constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX); tmp = (uint32_t)(tmp - PWM_RANGE_MIN); } else { @@ -635,7 +635,7 @@ FAST_CODE FAST_CODE_NOINLINE void updateRcCommands(void) rcCommand[THROTTLE] = rcLookupThrottle(tmp); - if (feature(FEATURE_3D) && !failsafeIsActive()) { + if (featureConfigured(FEATURE_3D) && !failsafeIsActive()) { if (!flight3DConfig()->switched_mode3d) { if (IS_RC_MODE_ACTIVE(BOX3D)) { fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000); diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index ffa5d48c9d..4b789945ef 100644 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -216,7 +216,7 @@ static void taskCalculateAltitude(timeUs_t currentTimeUs) #ifdef USE_TELEMETRY static void taskTelemetry(timeUs_t currentTimeUs) { - if (!cliMode && feature(FEATURE_TELEMETRY)) { + if (!cliMode && featureConfigured(FEATURE_TELEMETRY)) { subTaskTelemetryPollSensors(currentTimeUs); telemetryProcess(currentTimeUs); @@ -251,12 +251,12 @@ void fcTasksInit(void) #ifdef USE_OSD_SLAVE const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts; #else - const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || feature(FEATURE_OSD); + const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || featureConfigured(FEATURE_OSD); #endif setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts); #ifdef USE_TRANSPONDER - setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER)); + setTaskEnabled(TASK_TRANSPONDER, featureConfigured(FEATURE_TRANSPONDER)); #endif #ifdef STACK_CHECK @@ -285,7 +285,7 @@ void fcTasksInit(void) setTaskEnabled(TASK_BEEPER, true); #endif #ifdef USE_GPS - setTaskEnabled(TASK_GPS, feature(FEATURE_GPS)); + setTaskEnabled(TASK_GPS, featureConfigured(FEATURE_GPS)); #endif #ifdef USE_MAG setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG)); @@ -294,13 +294,13 @@ void fcTasksInit(void) setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO)); #endif #if defined(USE_BARO) || defined(USE_GPS) - setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || feature(FEATURE_GPS)); + setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || featureConfigured(FEATURE_GPS)); #endif #ifdef USE_DASHBOARD - setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD)); + setTaskEnabled(TASK_DASHBOARD, featureConfigured(FEATURE_DASHBOARD)); #endif #ifdef USE_TELEMETRY - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { setTaskEnabled(TASK_TELEMETRY, true); if (rxConfig()->serialrx_provider == SERIALRX_JETIEXBUS) { // Reschedule telemetry to 500hz for Jeti Exbus @@ -312,19 +312,19 @@ void fcTasksInit(void) } #endif #ifdef USE_LED_STRIP - setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP)); + setTaskEnabled(TASK_LEDSTRIP, featureConfigured(FEATURE_LED_STRIP)); #endif #ifdef USE_TRANSPONDER - setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER)); + setTaskEnabled(TASK_TRANSPONDER, featureConfigured(FEATURE_TRANSPONDER)); #endif #ifdef USE_OSD - setTaskEnabled(TASK_OSD, feature(FEATURE_OSD) && osdInitialized()); + setTaskEnabled(TASK_OSD, featureConfigured(FEATURE_OSD) && osdInitialized()); #endif #ifdef USE_BST setTaskEnabled(TASK_BST_MASTER_PROCESS, true); #endif #ifdef USE_ESC_SENSOR - setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR)); + setTaskEnabled(TASK_ESC_SENSOR, featureConfigured(FEATURE_ESC_SENSOR)); #endif #ifdef USE_ADC_INTERNAL setTaskEnabled(TASK_ADC_INTERNAL, true); @@ -336,7 +336,7 @@ void fcTasksInit(void) #ifdef USE_MSP_DISPLAYPORT setTaskEnabled(TASK_CMS, true); #else - setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DASHBOARD)); + setTaskEnabled(TASK_CMS, featureConfigured(FEATURE_OSD) || featureConfigured(FEATURE_DASHBOARD)); #endif #endif #ifdef USE_VTX_CONTROL diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 902a8ad944..eea48c2178 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -113,7 +113,7 @@ bool areSticksInApModePosition(uint16_t ap_mode) throttleStatus_e calculateThrottleStatus(void) { - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { if (IS_RC_MODE_ACTIVE(BOX3D) || flight3DConfig()->switched_mode3d) { if (rcData[THROTTLE] < rxConfig()->mincheck) { return THROTTLE_LOW; @@ -240,7 +240,7 @@ void processRcStickPositions() gyroStartCalibration(false); #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { GPS_reset_home_position(); } #endif @@ -253,7 +253,7 @@ void processRcStickPositions() return; } - if (feature(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) { + if (featureConfigured(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) { // Inflight ACC Calibration handleInflightCalibrationStickPosition(); return; diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c index 631dea62f6..ce2212dbbb 100644 --- a/src/main/fc/rc_modes.c +++ b/src/main/fc/rc_modes.c @@ -59,7 +59,7 @@ void rcModeUpdate(boxBitmask_t *newState) } bool isAirmodeActive(void) { - return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || feature(FEATURE_AIRMODE)); + return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || featureConfigured(FEATURE_AIRMODE)); } bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) { diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 56069fc07b..38a72a55cd 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -383,7 +383,7 @@ void initEscEndpoints(void) case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT150: disarmMotorOutput = DSHOT_DISARM_COMMAND; - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { motorOutputLow = DSHOT_MIN_THROTTLE + ((DSHOT_3D_DEADBAND_LOW - DSHOT_MIN_THROTTLE) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue); } else { motorOutputLow = DSHOT_MIN_THROTTLE + ((DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue); @@ -395,7 +395,7 @@ void initEscEndpoints(void) break; #endif default: - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { disarmMotorOutput = flight3DConfig()->neutral3d; motorOutputLow = flight3DConfig()->limit3d_low; motorOutputHigh = flight3DConfig()->limit3d_high; @@ -536,7 +536,7 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs) static timeUs_t reversalTimeUs = 0; // time when motors last reversed in 3D mode float currentThrottleInputRange = 0; - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { if (!ARMING_FLAG(ARMED)) { rcThrottlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming. } @@ -708,7 +708,7 @@ static void applyMixToMotors(float motorMix[MAX_SUPPORTED_MOTORS]) motorOutput = constrain(motorOutput, motorRangeMin, motorRangeMax); } // Motor stop handling - if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) { + if (featureConfigured(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !featureConfigured(FEATURE_3D) && !isAirmodeActive()) { if (((rcData[THROTTLE]) < rxConfig()->mincheck)) { motorOutput = disarmMotorOutput; } @@ -851,7 +851,7 @@ float convertExternalToMotor(uint16_t externalValue) case true: externalValue = constrain(externalValue, PWM_RANGE_MIN, PWM_RANGE_MAX); - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { if (externalValue == PWM_RANGE_MID) { motorValue = DSHOT_DISARM_COMMAND; } else if (externalValue < PWM_RANGE_MID) { @@ -880,7 +880,7 @@ uint16_t convertMotorToExternal(float motorValue) switch ((int)isMotorProtocolDshot()) { #ifdef USE_DSHOT case true: - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { if (motorValue == DSHOT_DISARM_COMMAND || motorValue < DSHOT_MIN_THROTTLE) { externalValue = PWM_RANGE_MID; } else if (motorValue <= DSHOT_3D_DEADBAND_LOW) { diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index d1e75d0b1a..29e6332826 100644 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -224,7 +224,7 @@ void servosInit(void) // enable servos for mixes that require them. note, this shifts motor counts. useServo = mixers[currentMixerMode].useServo; // if we want camstab/trig, that also enables servos, even if mixer doesn't - if (feature(FEATURE_SERVO_TILT) || feature(FEATURE_CHANNEL_FORWARDING)) { + if (featureConfigured(FEATURE_SERVO_TILT) || featureConfigured(FEATURE_CHANNEL_FORWARDING)) { useServo = 1; } @@ -377,13 +377,13 @@ void writeServos(void) } // Two servos for SERVO_TILT, if enabled - if (feature(FEATURE_SERVO_TILT) || currentMixerMode == MIXER_GIMBAL) { + if (featureConfigured(FEATURE_SERVO_TILT) || currentMixerMode == MIXER_GIMBAL) { updateGimbalServos(servoIndex); servoIndex += 2; } // forward AUX to remaining servo outputs (not constrained) - if (feature(FEATURE_CHANNEL_FORWARDING)) { + if (featureConfigured(FEATURE_CHANNEL_FORWARDING)) { forwardAuxChannelsToServos(servoIndex); servoIndex += MAX_AUX_CHANNEL_COUNT; } @@ -406,7 +406,7 @@ void servoMixer(void) input[INPUT_STABILIZED_YAW] = pidData[FD_YAW].Sum * PID_SERVO_MIXER_SCALING; // Reverse yaw servo when inverted in 3D mode - if (feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->midrc)) { + if (featureConfigured(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->midrc)) { input[INPUT_STABILIZED_YAW] *= -1; } } @@ -498,7 +498,7 @@ static void servoTable(void) } // camera stabilization - if (feature(FEATURE_SERVO_TILT)) { + if (featureConfigured(FEATURE_SERVO_TILT)) { // center at fixed position, or vary either pitch or roll by RC channel servo[SERVO_GIMBAL_PITCH] = determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); servo[SERVO_GIMBAL_ROLL] = determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index 4df132dd2e..d54a353a5c 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -2946,7 +2946,7 @@ static void cliDshotProg(char *cmdline) pwmWriteDshotCommand(escIndex, getMotorCount(), command, true); } else { #if defined(USE_ESC_SENSOR) && defined(USE_ESC_SENSOR_INFO) - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { if (escIndex != ALL_MOTORS) { executeEscInfoCommand(escIndex); } else { diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index 92ee499981..2168ababd0 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1018,7 +1018,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) #if defined(USE_ESC_SENSOR) case MSP_ESC_SENSOR_DATA: - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { sbufWriteU8(dst, getMotorCount()); for (int i = 0; i < getMotorCount(); i++) { const escSensorData_t *escData = getEscSensorData(i); diff --git a/src/main/interface/msp_box.c b/src/main/interface/msp_box.c index 3740f987b9..a7e03103f6 100644 --- a/src/main/interface/msp_box.c +++ b/src/main/interface/msp_box.c @@ -166,11 +166,11 @@ void initActiveBoxIds(void) #define BME(boxId) do { bitArraySet(&ena, boxId); } while (0) BME(BOXARM); BME(BOXPREARM); - if (!feature(FEATURE_AIRMODE)) { + if (!featureConfigured(FEATURE_AIRMODE)) { BME(BOXAIRMODE); } - if (!feature(FEATURE_ANTI_GRAVITY)) { + if (!featureConfigured(FEATURE_ANTI_GRAVITY)) { BME(BOXANTIGRAVITY); } @@ -188,9 +188,9 @@ void initActiveBoxIds(void) #endif #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { #ifdef USE_GPS_RESCUE - if (!feature(FEATURE_3D)) { + if (!featureConfigured(FEATURE_3D)) { BME(BOXGPSRESCUE); } #endif @@ -207,7 +207,7 @@ void initActiveBoxIds(void) BME(BOXBEEPERON); #ifdef USE_LED_STRIP - if (feature(FEATURE_LED_STRIP)) { + if (featureConfigured(FEATURE_LED_STRIP)) { BME(BOXLEDLOW); } #endif @@ -221,7 +221,7 @@ void initActiveBoxIds(void) BME(BOXFPVANGLEMIX); - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { BME(BOX3D); } @@ -229,18 +229,18 @@ void initActiveBoxIds(void) BME(BOXFLIPOVERAFTERCRASH); } - if (feature(FEATURE_SERVO_TILT)) { + if (featureConfigured(FEATURE_SERVO_TILT)) { BME(BOXCAMSTAB); } - if (feature(FEATURE_INFLIGHT_ACC_CAL)) { + if (featureConfigured(FEATURE_INFLIGHT_ACC_CAL)) { BME(BOXCALIB); } BME(BOXOSD); #ifdef USE_TELEMETRY - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { BME(BOXTELEMETRY); } #endif diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 6513594477..b663985736 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -384,7 +384,7 @@ void beeperUpdate(timeUs_t currentTimeUs) if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { beeper(BEEPER_RX_SET); #ifdef USE_GPS - } else if (feature(FEATURE_GPS) && IS_RC_MODE_ACTIVE(BOXBEEPGPSCOUNT)) { + } else if (featureConfigured(FEATURE_GPS) && IS_RC_MODE_ACTIVE(BOXBEEPGPSCOUNT)) { beeperGpsStatus(); #endif } diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c index 20abe2a8e3..eb560363a4 100644 --- a/src/main/io/dashboard.c +++ b/src/main/io/dashboard.c @@ -357,7 +357,7 @@ static void showProfilePage(void) #ifdef USE_GPS static void showGpsPage(void) { - if (!feature(FEATURE_GPS)) { + if (!featureConfigured(FEATURE_GPS)) { pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; return; } diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 19c0ad0447..2d1aa4ffd9 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -1214,7 +1214,7 @@ static void gpsHandlePassthrough(uint8_t data) { gpsNewData(data); #ifdef USE_DASHBOARD - if (feature(FEATURE_DASHBOARD)) { + if (featureConfigured(FEATURE_DASHBOARD)) { dashboardUpdate(micros()); } #endif @@ -1230,7 +1230,7 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) serialSetMode(gpsPort, gpsPort->mode | MODE_TX); #ifdef USE_DASHBOARD - if (feature(FEATURE_DASHBOARD)) { + if (featureConfigured(FEATURE_DASHBOARD)) { dashboardShowFixedPage(PAGE_GPS); } #endif diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 42de3f40bf..0a9d98d121 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -788,7 +788,7 @@ static bool osdDrawSingleElement(uint8_t item) #ifdef USE_ESC_SENSOR // Show warning if we lose motor output, the ESC is overheating or excessive current draw - if (feature(FEATURE_ESC_SENSOR) && osdWarnGetState(OSD_WARNING_ESC_FAIL)) { + if (featureConfigured(FEATURE_ESC_SENSOR) && osdWarnGetState(OSD_WARNING_ESC_FAIL)) { char escWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE]; unsigned pos = 0; @@ -956,13 +956,13 @@ static bool osdDrawSingleElement(uint8_t item) #ifdef USE_ESC_SENSOR case OSD_ESC_TMP: - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(escDataCombined->temperature * 10) / 10, osdGetTemperatureSymbolForSelectedUnit()); } break; case OSD_ESC_RPM: - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { tfp_sprintf(buff, "%5d", escDataCombined == NULL ? 0 : calcEscRpm(escDataCombined->rpm)); } break; @@ -1040,7 +1040,7 @@ static void osdDrawElements(void) #endif // GPS #ifdef USE_ESC_SENSOR - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { osdDrawSingleElement(OSD_ESC_TMP); osdDrawSingleElement(OSD_ESC_RPM); } @@ -1226,7 +1226,7 @@ void osdUpdateAlarms(void) } #ifdef USE_ESC_SENSOR - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { // This works because the combined ESC data contains the maximum temperature seen amongst all ESCs if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escDataCombined->temperature >= osdConfig()->esc_temp_alarm) { SET_BLINK(OSD_ESC_TMP); @@ -1560,7 +1560,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs) blinkState = (currentTimeUs / 200000) % 2; #ifdef USE_ESC_SENSOR - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { escDataCombined = getEscSensorData(ESC_SENSOR_COMBINED); } #endif diff --git a/src/main/io/vtx_rtc6705.c b/src/main/io/vtx_rtc6705.c index 5ea31f169f..6433aeffcc 100644 --- a/src/main/io/vtx_rtc6705.c +++ b/src/main/io/vtx_rtc6705.c @@ -72,7 +72,7 @@ bool vtxRTC6705Init(void) bool vtxRTC6705CanUpdate(void) { #if defined(MAX7456_SPI_INSTANCE) && defined(RTC6705_SPI_INSTANCE) && defined(SPI_SHARED_MAX7456_AND_RTC6705) - if (feature(FEATURE_OSD)) { + if (featureConfigured(FEATURE_OSD)) { return !max7456DmaInProgress(); } #endif diff --git a/src/main/osd_slave/osd_slave_init.c b/src/main/osd_slave/osd_slave_init.c new file mode 100644 index 0000000000..2a37ec4b42 --- /dev/null +++ b/src/main/osd_slave/osd_slave_init.c @@ -0,0 +1,308 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "blackbox/blackbox.h" + +#include "common/axis.h" +#include "common/color.h" +#include "common/maths.h" +#include "common/printf.h" + +#include "config/config_eeprom.h" +#include "config/feature.h" + +#include "drivers/adc.h" +#include "drivers/bus.h" +#include "drivers/bus_i2c.h" +#include "drivers/bus_spi.h" +#include "drivers/dma.h" +#include "drivers/exti.h" +#include "drivers/inverter.h" +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/nvic.h" +#include "drivers/sensor.h" +#include "drivers/serial.h" +#include "drivers/serial_softserial.h" +#include "drivers/serial_uart.h" +#include "drivers/sound_beeper.h" +#include "drivers/system.h" +#include "drivers/time.h" +#include "drivers/timer.h" +#include "drivers/transponder_ir.h" +#include "drivers/usb_io.h" + +#include "fc/config.h" +#include "fc/rc_controls.h" +#include "fc/fc_tasks.h" +#include "fc/runtime_config.h" + +#include "interface/cli.h" +#include "interface/msp.h" + +#include "msp/msp_serial.h" + +#include "io/beeper.h" +#include "io/displayport_max7456.h" +#include "io/flashfs.h" +#include "io/ledstrip.h" +#include "io/osd_slave.h" +#include "io/serial.h" +#include "io/transponder_ir.h" + +#include "osd_slave/osd_slave_init.h" + +#include "pg/adc.h" +#include "pg/bus_i2c.h" +#include "pg/bus_spi.h" +#include "pg/pg.h" +#include "pg/pg_ids.h" +#include "pg/vcd.h" + +#include "scheduler/scheduler.h" + +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/battery.h" + +#ifdef USE_HARDWARE_REVISION_DETECTION +#include "hardware_revision.h" +#endif + +#include "build/build_config.h" +#include "build/debug.h" + +#ifdef TARGET_PREINIT +void targetPreInit(void); +#endif + +uint8_t systemState = SYSTEM_STATE_INITIALISING; + +void processLoopback(void) +{ +} + + +#ifdef BUS_SWITCH_PIN +void busSwitchInit(void) +{ +static IO_t busSwitchResetPin = IO_NONE; + + busSwitchResetPin = IOGetByTag(IO_TAG(BUS_SWITCH_PIN)); + IOInit(busSwitchResetPin, OWNER_SYSTEM, 0); + IOConfigGPIO(busSwitchResetPin, IOCFG_OUT_PP); + + // ENABLE + IOLo(busSwitchResetPin); +} +#endif + +void init(void) +{ +#ifdef USE_HAL_DRIVER + HAL_Init(); +#endif + + printfSupportInit(); + + systemInit(); + + // initialize IO (needed for all IO operations) + IOInitGlobal(); + +#ifdef USE_HARDWARE_REVISION_DETECTION + detectHardwareRevision(); +#endif + + initEEPROM(); + + ensureEEPROMStructureIsValid(); + readEEPROM(); + + systemState |= SYSTEM_STATE_CONFIG_LOADED; + + debugMode = systemConfig()->debug_mode; + + // Latch active features to be used for featureConfigured() in the remainder of init(). + latchActiveFeatures(); + +#ifdef TARGET_PREINIT + targetPreInit(); +#endif + + ledInit(statusLedConfig()); + LED2_ON; + +#ifdef USE_EXTI + EXTIInit(); +#endif + + delay(100); + + timerInit(); // timer must be initialized before any channel is allocated + +#ifdef BUS_SWITCH_PIN + busSwitchInit(); +#endif + +#if defined(USE_UART) && !defined(SIMULATOR_BUILD) + uartPinConfigure(serialPinConfig()); +#endif + + serialInit(false, SERIAL_PORT_NONE); + +#ifdef USE_BEEPER + beeperInit(beeperDevConfig()); +#endif +/* temp until PGs are implemented. */ +#ifdef USE_INVERTER + initInverters(); +#endif + +#ifdef TARGET_BUS_INIT + targetBusInit(); +#else + +#ifdef USE_SPI + spiPinConfigure(spiPinConfig(0)); + + // Initialize CS lines and keep them high + spiPreInit(); + +#ifdef USE_SPI_DEVICE_1 + spiInit(SPIDEV_1); +#endif +#ifdef USE_SPI_DEVICE_2 + spiInit(SPIDEV_2); +#endif +#ifdef USE_SPI_DEVICE_3 + spiInit(SPIDEV_3); +#endif +#ifdef USE_SPI_DEVICE_4 + spiInit(SPIDEV_4); +#endif +#endif /* USE_SPI */ + +#ifdef USE_I2C + i2cHardwareConfigure(i2cConfig(0)); + + // Note: Unlike UARTs which are configured when client is present, + // I2C buses are initialized unconditionally if they are configured. + +#ifdef USE_I2C_DEVICE_1 + i2cInit(I2CDEV_1); +#endif +#ifdef USE_I2C_DEVICE_2 + i2cInit(I2CDEV_2); +#endif +#ifdef USE_I2C_DEVICE_3 + i2cInit(I2CDEV_3); +#endif +#ifdef USE_I2C_DEVICE_4 + i2cInit(I2CDEV_4); +#endif +#endif /* USE_I2C */ + +#endif /* TARGET_BUS_INIT */ + +#ifdef USE_HARDWARE_REVISION_DETECTION + updateHardwareRevision(); +#endif + +#ifdef USE_ADC + adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC); + adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC); + + adcConfigMutable()->rssi.enabled = featureConfigured(FEATURE_RSSI_ADC); + adcInit(adcConfig()); +#endif + + LED1_ON; + LED0_OFF; + LED2_OFF; + + for (int i = 0; i < 10; i++) { + LED1_TOGGLE; + LED0_TOGGLE; +#if defined(USE_BEEPER) + delay(25); + if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_SYSTEM_INIT))) BEEP_ON; + delay(25); + BEEP_OFF; +#else + delay(50); +#endif + } + LED0_OFF; + LED1_OFF; + + mspInit(); + mspSerialInit(); + +#ifdef USE_CLI + cliInit(serialConfig()); +#endif + + displayPort_t *osdDisplayPort = NULL; + +#if defined(USE_MAX7456) + // If there is a max7456 chip for the OSD then use it + osdDisplayPort = max7456DisplayPortInit(vcdProfile()); + // osdInit will register with CMS by itself. + osdSlaveInit(osdDisplayPort); +#endif + +#ifdef USE_LED_STRIP + ledStripInit(); + + if (featureConfigured(FEATURE_LED_STRIP)) { + ledStripEnable(); + } +#endif + +#ifdef USE_USB_DETECT + usbCableDetectInit(); +#endif + +#ifdef USE_TRANSPONDER + if (featureConfigured(FEATURE_TRANSPONDER)) { + transponderInit(); + transponderStartRepeating(); + systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED; + } +#endif + + timerStart(); + + batteryInit(); + + // Latch active features AGAIN since some may be modified by init(). + latchActiveFeatures(); + + fcTasksInit(); + + systemState |= SYSTEM_STATE_READY; +} diff --git a/src/main/rx/cc2500_frsky_d.c b/src/main/rx/cc2500_frsky_d.c index 52aaa95e63..ab49cff4cf 100644 --- a/src/main/rx/cc2500_frsky_d.c +++ b/src/main/rx/cc2500_frsky_d.c @@ -305,7 +305,7 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro void frSkyDInit(void) { #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_FRSKY_HUB) - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { telemetryEnabled = initFrSkyHubTelemetryExternal(frSkyDTelemetryWriteByte); } #endif diff --git a/src/main/rx/cc2500_frsky_x.c b/src/main/rx/cc2500_frsky_x.c index f37da6967c..ca9432db13 100644 --- a/src/main/rx/cc2500_frsky_x.c +++ b/src/main/rx/cc2500_frsky_x.c @@ -543,7 +543,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro void frSkyXInit(void) { #if defined(USE_TELEMETRY_SMARTPORT) - if (feature(FEATURE_TELEMETRY)) { + if (featureConfigured(FEATURE_TELEMETRY)) { telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame); } #endif diff --git a/src/main/rx/pwm.c b/src/main/rx/pwm.c index 356752797f..d85fc32783 100644 --- a/src/main/rx/pwm.c +++ b/src/main/rx/pwm.c @@ -60,10 +60,10 @@ void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) rxRuntimeConfig->rxRefreshRate = 20000; // configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled - if (feature(FEATURE_RX_PARALLEL_PWM)) { + if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT; rxRuntimeConfig->rcReadRawFn = pwmReadRawRC; - } else if (feature(FEATURE_RX_PPM)) { + } else if (featureConfigured(FEATURE_RX_PPM)) { rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT; rxRuntimeConfig->rcReadRawFn = ppmReadRawRC; } diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 347881a54c..8d595a9d55 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -248,7 +248,7 @@ void rxInit(void) rcInvalidPulsPeriod[i] = millis() + MAX_INVALID_PULS_TIME; } - rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec; + rcData[THROTTLE] = (featureConfigured(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec; // Initialize ARM switch to OFF position when arming via switch is defined // TODO - move to rc_mode.c @@ -268,10 +268,9 @@ void rxInit(void) } #ifdef USE_SERIAL_RX - if (feature(FEATURE_RX_SERIAL)) { + if (featureConfigured(FEATURE_RX_SERIAL)) { const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig); if (!enabled) { - featureClear(FEATURE_RX_SERIAL); rxRuntimeConfig.rcReadRawFn = nullReadRawRC; rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus; } @@ -279,17 +278,16 @@ void rxInit(void) #endif #ifdef USE_RX_MSP - if (feature(FEATURE_RX_MSP)) { + if (featureConfigured(FEATURE_RX_MSP)) { rxMspInit(rxConfig(), &rxRuntimeConfig); needRxSignalMaxDelayUs = DELAY_5_HZ; } #endif #ifdef USE_RX_SPI - if (feature(FEATURE_RX_SPI)) { + if (featureConfigured(FEATURE_RX_SPI)) { const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeConfig); if (!enabled) { - featureClear(FEATURE_RX_SPI); rxRuntimeConfig.rcReadRawFn = nullReadRawRC; rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus; } @@ -297,13 +295,13 @@ void rxInit(void) #endif #if defined(USE_PWM) || defined(USE_PPM) - if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) { + if (featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_PARALLEL_PWM)) { rxPwmInit(rxConfig(), &rxRuntimeConfig); } #endif #if defined(USE_ADC) - if (feature(FEATURE_RSSI_ADC)) { + if (featureConfigured(FEATURE_RSSI_ADC)) { rssiSource = RSSI_SOURCE_ADC; } else #endif @@ -346,14 +344,14 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime) bool useDataDrivenProcessing = true; #if defined(USE_PWM) || defined(USE_PPM) - if (feature(FEATURE_RX_PPM)) { + if (featureConfigured(FEATURE_RX_PPM)) { if (isPPMDataBeingReceived()) { signalReceived = true; rxIsInFailsafeMode = false; needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs; resetPPMDataReceivedState(); } - } else if (feature(FEATURE_RX_PARALLEL_PWM)) { + } else if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { if (isPWMDataBeingReceived()) { signalReceived = true; rxIsInFailsafeMode = false; @@ -437,7 +435,7 @@ static uint16_t getRxfailValue(uint8_t channel) case YAW: return rxConfig()->midrc; case THROTTLE: - if (feature(FEATURE_3D)) + if (featureConfigured(FEATURE_3D)) return rxConfig()->midrc; else return rxConfig()->rx_min_usec; @@ -512,7 +510,7 @@ static void detectAndApplySignalLossBehaviour(void) } } } - if (feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM)) { + if (featureConfigured(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM)) { // smooth output for PWM and PPM rcData[channel] = calculateChannelMovingAverage(channel, sample); } else { diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 9045b68631..79075ca69a 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -238,7 +238,7 @@ void spektrumBind(rxConfig_t *rxConfig) switch (rxConfig->serialrx_provider) { case SERIALRX_SRXL: #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL) - if (feature(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) { + if (featureConfigured(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) { bindPin = txPin; } break; @@ -322,7 +322,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig switch (rxConfig->serialrx_provider) { case SERIALRX_SRXL: #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SRXL) - srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared); + srxlEnabled = (featureConfigured(FEATURE_TELEMETRY) && !portShared); FALLTHROUGH; #endif case SERIALRX_SPEKTRUM2048: diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 882fbccd12..a3479d30bd 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -528,7 +528,7 @@ void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims) performAcclerationCalibration(rollAndPitchTrims); } - if (feature(FEATURE_INFLIGHT_ACC_CAL)) { + if (featureConfigured(FEATURE_INFLIGHT_ACC_CAL)) { performInflightAccelerationCalibration(rollAndPitchTrims); } diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 28c86d7e4e..d2170d80b2 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -121,7 +121,7 @@ void batteryUpdateVoltage(timeUs_t currentTimeUs) switch (batteryConfig()->voltageMeterSource) { #ifdef USE_ESC_SENSOR case VOLTAGE_METER_ESC: - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { voltageMeterESCRefresh(); voltageMeterESCReadCombined(&voltageMeter); } @@ -399,7 +399,7 @@ void batteryUpdateCurrentMeter(timeUs_t currentTimeUs) case CURRENT_METER_VIRTUAL: { #ifdef USE_VIRTUAL_CURRENT_METER throttleStatus_e throttleStatus = calculateThrottleStatus(); - bool throttleLowAndMotorStop = (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)); + bool throttleLowAndMotorStop = (throttleStatus == THROTTLE_LOW && featureConfigured(FEATURE_MOTOR_STOP)); int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000; currentMeterVirtualRefresh(lastUpdateAt, ARMING_FLAG(ARMED), throttleLowAndMotorStop, throttleOffset); @@ -410,7 +410,7 @@ void batteryUpdateCurrentMeter(timeUs_t currentTimeUs) case CURRENT_METER_ESC: #ifdef USE_ESC_SENSOR - if (feature(FEATURE_ESC_SENSOR)) { + if (featureConfigured(FEATURE_ESC_SENSOR)) { currentMeterESCRefresh(lastUpdateAt); currentMeterESCReadCombined(¤tMeter); } diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 958fc43f53..7ada2bd594 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -148,7 +148,7 @@ bool isEscSensorActive(void) escSensorData_t *getEscSensorData(uint8_t motorNumber) { - if (!feature(FEATURE_ESC_SENSOR)) { + if (!featureConfigured(FEATURE_ESC_SENSOR)) { return NULL; } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 427720bcd7..bb18fa3a0b 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -744,7 +744,7 @@ static void gyroInitFilterNotch2(gyroSensor_t *gyroSensor, uint16_t notchHz, uin #ifdef USE_GYRO_DATA_ANALYSE static bool isDynamicFilterActive(void) { - return feature(FEATURE_DYNAMIC_FILTER); + return featureConfigured(FEATURE_DYNAMIC_FILTER); } static void gyroInitFilterDynamicNotch(gyroSensor_t *gyroSensor) diff --git a/src/main/target/BLUEJAYF4/initialisation.c b/src/main/target/BLUEJAYF4/initialisation.c index 2ee012a2ce..fb746befc3 100644 --- a/src/main/target/BLUEJAYF4/initialisation.c +++ b/src/main/target/BLUEJAYF4/initialisation.c @@ -56,7 +56,7 @@ void targetPreInit(void) serialPortConfig_t *portConfig = serialFindPortConfiguration(SERIAL_PORT_USART1); if (portConfig) { bool smartportEnabled = (portConfig->functionMask & FUNCTION_TELEMETRY_SMARTPORT); - if (smartportEnabled && (!telemetryConfig()->telemetry_inverted) && (feature(FEATURE_TELEMETRY))) { + if (smartportEnabled && (!telemetryConfig()->telemetry_inverted) && (featureConfigured(FEATURE_TELEMETRY))) { high = true; } } diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 6b39529f97..7b3efd45f8 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -436,7 +436,7 @@ void pwmCompleteMotorUpdate(uint8_t motorCount) { // for gazebo8 ArduCopterPlugin remap, normal range = [0.0, 1.0], 3D rang = [-1.0, 1.0] double outScale = 1000.0; - if (feature(FEATURE_3D)) { + if (featureConfigured(FEATURE_3D)) { outScale = 500.0; } diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 6f9fd09254..68fab96b7a 100644 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -445,7 +445,7 @@ void initCrsfTelemetry(void) crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX); } crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX); - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX); } crsfScheduleCount = (uint8_t)index; diff --git a/src/main/telemetry/frsky_hub.c b/src/main/telemetry/frsky_hub.c index bc4ef15acc..2adfec3c5f 100644 --- a/src/main/telemetry/frsky_hub.c +++ b/src/main/telemetry/frsky_hub.c @@ -193,7 +193,7 @@ static void sendThrottleOrBatterySizeAsRpm(void) if (ARMING_FLAG(ARMED)) { const throttleStatus_e throttleStatus = calculateThrottleStatus(); uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; - if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) { + if (throttleStatus == THROTTLE_LOW && featureConfigured(FEATURE_MOTOR_STOP)) { throttleForRPM = 0; } data = throttleForRPM; diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index 38481bc181..a76197ea04 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -228,7 +228,7 @@ static uint16_t getRPM() if (ARMING_FLAG(ARMED)) { const throttleStatus_e throttleStatus = calculateThrottleStatus(); rpm = rcCommand[THROTTLE]; // / BLADE_NUMBER_DIVIDER; - if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) rpm = 0; + if (throttleStatus == THROTTLE_LOW && featureConfigured(FEATURE_MOTOR_STOP)) rpm = 0; } else { rpm = (uint16_t)(batteryConfig()->batteryCapacity); // / BLADE_NUMBER_DIVIDER } diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 1b7ceabb87..b5a21b232e 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -318,7 +318,7 @@ static void smartPortSendPackage(uint16_t id, uint32_t val) } static bool reportExtendedEscSensors(void) { - return feature(FEATURE_ESC_SENSOR) && telemetryConfig()->smartport_use_extra_sensors; + return featureConfigured(FEATURE_ESC_SENSOR) && telemetryConfig()->smartport_use_extra_sensors; } #define ADD_SENSOR(dataId) frSkyDataIdTableInfo.table[frSkyDataIdTableInfo.index++] = dataId @@ -332,7 +332,7 @@ static void initSmartPortSensors(void) if (isBatteryVoltageConfigured()) { #ifdef USE_ESC_SENSOR - if (!reportExtendedEscSensors()) + if (!featureConfigured(FEATURE_ESC_SENSOR)) { #endif { ADD_SENSOR(FSSP_DATAID_VFAS); @@ -365,7 +365,7 @@ static void initSmartPortSensors(void) } #ifdef USE_GPS - if (feature(FEATURE_GPS)) { + if (featureConfigured(FEATURE_GPS)) { ADD_SENSOR(FSSP_DATAID_SPEED); ADD_SENSOR(FSSP_DATAID_LATLONG); ADD_SENSOR(FSSP_DATAID_LATLONG); // twice (one for lat, one for long) @@ -719,7 +719,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear // provide GPS lock status smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + gpsSol.numSat); *clearToSend = false; - } else if (feature(FEATURE_GPS)) { + } else if (featureConfigured(FEATURE_GPS)) { smartPortSendPackage(id, 0); *clearToSend = false; } else