diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 162f2bca6e..59dcd9a6ef 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -22,7 +22,7 @@ #include "platform.h" -#ifdef BLACKBOX +#ifdef USE_BLACKBOX #include "blackbox.h" #include "blackbox_encoding.h" @@ -187,15 +187,15 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"vbatLatest", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT}, {"amperageLatest",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC}, -#ifdef MAG +#ifdef USE_MAG {"magADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, {"magADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, {"magADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, #endif -#ifdef BARO +#ifdef USE_BARO {"BaroAlt", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO}, #endif -#ifdef SONAR +#ifdef USE_SONAR {"sonarRaw", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_SONAR}, #endif {"rssi", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RSSI}, @@ -226,7 +226,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)} }; -#ifdef GPS +#ifdef USE_GPS // GPS position/vel frame static const blackboxConditionalFieldDefinition_t blackboxGpsGFields[] = { {"time", -1, UNSIGNED, PREDICT(LAST_MAIN_FRAME_TIME), ENCODING(UNSIGNED_VB), CONDITION(NOT_LOGGING_EVERY_FRAME)}, @@ -291,13 +291,13 @@ typedef struct blackboxMainState_s { uint16_t vbatLatest; uint16_t amperageLatest; -#ifdef BARO +#ifdef USE_BARO int32_t BaroAlt; #endif -#ifdef MAG +#ifdef USE_MAG int16_t magADC[XYZ_AXIS_COUNT]; #endif -#ifdef SONAR +#ifdef USE_SONAR int32_t sonarRaw; #endif uint16_t rssi; @@ -412,14 +412,14 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) return currentPidProfile->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0; case FLIGHT_LOG_FIELD_CONDITION_MAG: -#ifdef MAG +#ifdef USE_MAG return sensors(SENSOR_MAG); #else return false; #endif case FLIGHT_LOG_FIELD_CONDITION_BARO: -#ifdef BARO +#ifdef USE_BARO return sensors(SENSOR_BARO); #else return false; @@ -432,7 +432,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) return batteryConfig()->currentMeterSource == CURRENT_METER_ADC; case FLIGHT_LOG_FIELD_CONDITION_SONAR: -#ifdef SONAR +#ifdef USE_SONAR return feature(FEATURE_SONAR); #else return false; @@ -550,19 +550,19 @@ static void writeIntraframe(void) blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest); } -#ifdef MAG +#ifdef USE_MAG if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { blackboxWriteSigned16VBArray(blackboxCurrent->magADC, XYZ_AXIS_COUNT); } #endif -#ifdef BARO +#ifdef USE_BARO if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) { blackboxWriteSignedVB(blackboxCurrent->BaroAlt); } #endif -#ifdef SONAR +#ifdef USE_SONAR if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) { blackboxWriteSignedVB(blackboxCurrent->sonarRaw); } @@ -678,7 +678,7 @@ static void writeInterframe(void) deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest; } -#ifdef MAG +#ifdef USE_MAG if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { for (int x = 0; x < XYZ_AXIS_COUNT; x++) { deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x]; @@ -686,13 +686,13 @@ static void writeInterframe(void) } #endif -#ifdef BARO +#ifdef USE_BARO if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) { deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt; } #endif -#ifdef SONAR +#ifdef USE_SONAR if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) { deltas[optionalFieldCount++] = blackboxCurrent->sonarRaw - blackboxLast->sonarRaw; } @@ -933,7 +933,7 @@ bool inMotorTestMode(void) { return false; } -#ifdef GPS +#ifdef USE_GPS static void writeGPSHomeFrame(void) { blackboxWrite('H'); @@ -990,7 +990,7 @@ static void loadMainState(timeUs_t currentTimeUs) blackboxCurrent->axisPID_D[i] = axisPID_D[i]; blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]); blackboxCurrent->accSmooth[i] = acc.accSmooth[i]; -#ifdef MAG +#ifdef USE_MAG blackboxCurrent->magADC[i] = mag.magADC[i]; #endif } @@ -1011,11 +1011,11 @@ static void loadMainState(timeUs_t currentTimeUs) blackboxCurrent->vbatLatest = getBatteryVoltageLatest(); blackboxCurrent->amperageLatest = getAmperageLatest(); -#ifdef BARO +#ifdef USE_BARO blackboxCurrent->BaroAlt = baro.BaroAlt; #endif -#ifdef SONAR +#ifdef USE_SONAR // Store the raw sonar value without applying tilt correction blackboxCurrent->sonarRaw = sonarRead(); #endif @@ -1387,7 +1387,7 @@ STATIC_UNIT_TESTED bool blackboxShouldLogIFrame(void) * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can * still be interpreted correctly. */ -#ifdef GPS +#ifdef USE_GPS STATIC_UNIT_TESTED bool blackboxShouldLogGpsHomeFrame(void) { if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] @@ -1442,7 +1442,7 @@ STATIC_UNIT_TESTED void blackboxLogIteration(timeUs_t currentTimeUs) loadMainState(currentTimeUs); writeInterframe(); } -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS)) { if (blackboxShouldLogGpsHomeFrame()) { writeGPSHomeFrame(); @@ -1508,7 +1508,7 @@ void blackboxUpdate(timeUs_t currentTimeUs) //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1 if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS)) { blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER); } else @@ -1516,7 +1516,7 @@ void blackboxUpdate(timeUs_t currentTimeUs) blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER); } break; -#ifdef GPS +#ifdef USE_GPS case BLACKBOX_STATE_SEND_GPS_H_HEADER: blackboxReplenishHeaderBudget(); //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1 diff --git a/src/main/blackbox/blackbox_encoding.c b/src/main/blackbox/blackbox_encoding.c index 35476b7ea5..7f09dc9b8e 100644 --- a/src/main/blackbox/blackbox_encoding.c +++ b/src/main/blackbox/blackbox_encoding.c @@ -6,7 +6,7 @@ #include "platform.h" -#ifdef BLACKBOX +#ifdef USE_BLACKBOX #include "blackbox_encoding.h" #include "blackbox_io.h" diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index ba078afe63..9b93ba9524 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -6,7 +6,7 @@ #include "platform.h" -#ifdef BLACKBOX +#ifdef USE_BLACKBOX #include "blackbox.h" #include "blackbox_io.h" diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 7a12e443a6..1f310b682b 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -31,7 +31,7 @@ #include "platform.h" -#ifdef CMS +#ifdef USE_CMS #include "build/build_config.h" #include "build/debug.h" @@ -317,7 +317,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row) } break; -#ifdef OSD +#ifdef USE_OSD case OME_VISIBLE: if (IS_PRINTVALUE(p) && p->data) { uint16_t *val = (uint16_t *)p->data; @@ -756,7 +756,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key) } break; -#ifdef OSD +#ifdef USE_OSD case OME_VISIBLE: if (p->data) { uint16_t *val = (uint16_t *)p->data; diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 1bcf7eb88d..f42c3e0e65 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -26,7 +26,7 @@ #include "platform.h" -#if defined(CMS) && defined(BLACKBOX) +#if defined(USE_CMS) && defined(USE_BLACKBOX) #include "build/version.h" diff --git a/src/main/cms/cms_menu_builtin.c b/src/main/cms/cms_menu_builtin.c index ce798f5be7..5acc95e558 100644 --- a/src/main/cms/cms_menu_builtin.c +++ b/src/main/cms/cms_menu_builtin.c @@ -26,7 +26,7 @@ #include "platform.h" -#ifdef CMS +#ifdef USE_CMS #include "build/version.h" @@ -95,7 +95,7 @@ static OSD_Entry menuFeaturesEntries[] = { {"--- FEATURES ---", OME_Label, NULL, NULL, 0}, -#if defined(BLACKBOX) +#if defined(USE_BLACKBOX) {"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0}, #endif #if defined(VTX_CONTROL) @@ -133,7 +133,7 @@ static OSD_Entry menuMainEntries[] = {"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0}, {"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0}, -#ifdef OSD +#ifdef USE_OSD {"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0}, #endif {"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0}, diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index 73a639f617..db81db349a 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -25,7 +25,7 @@ #include "platform.h" -#ifdef CMS +#ifdef USE_CMS #include "build/version.h" diff --git a/src/main/cms/cms_menu_ledstrip.c b/src/main/cms/cms_menu_ledstrip.c index a087d41d21..05be01f962 100644 --- a/src/main/cms/cms_menu_ledstrip.c +++ b/src/main/cms/cms_menu_ledstrip.c @@ -22,7 +22,7 @@ #include "platform.h" -#ifdef CMS +#ifdef USE_CMS #include "build/version.h" diff --git a/src/main/cms/cms_menu_misc.c b/src/main/cms/cms_menu_misc.c index c0bc5cb4a4..3559ca65dd 100644 --- a/src/main/cms/cms_menu_misc.c +++ b/src/main/cms/cms_menu_misc.c @@ -22,7 +22,7 @@ #include "platform.h" -#ifdef CMS +#ifdef USE_CMS #include "build/debug.h" #include "build/version.h" diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index e7522a9ac7..2fa323e349 100644 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -22,7 +22,7 @@ #include "platform.h" -#if defined(OSD) && defined(CMS) +#if defined(USE_OSD) && defined(USE_CMS) #include "build/version.h" @@ -76,7 +76,7 @@ OSD_Entry menuOsdActiveElemsEntries[] = #endif // VTX {"CURRENT (A)", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CURRENT_DRAW], 0}, {"USED MAH", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAH_DRAWN], 0}, -#ifdef GPS +#ifdef USE_GPS {"GPS SPEED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SPEED], 0}, {"GPS SATS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SATS], 0}, {"GPS LAT", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LAT], 0}, diff --git a/src/main/cms/cms_menu_vtx_rtc6705.c b/src/main/cms/cms_menu_vtx_rtc6705.c index 766c3f265d..fe25948ccf 100644 --- a/src/main/cms/cms_menu_vtx_rtc6705.c +++ b/src/main/cms/cms_menu_vtx_rtc6705.c @@ -21,7 +21,7 @@ #include "platform.h" -#ifdef CMS +#if defined(USE_CMS) #include "common/printf.h" #include "common/utils.h" @@ -33,6 +33,7 @@ #include "io/vtx_rtc6705.h" #include "io/vtx_settings_config.h" +#if defined(VTX_SETTINGS_CONFIG) static uint8_t cmsx_vtxBand; static uint8_t cmsx_vtxChannel; @@ -98,4 +99,6 @@ CMS_Menu cmsx_menuVtxRTC6705 = { .entries = cmsx_menuVtxEntries }; +#endif // VTX_SETTINGS_CONFIG + #endif // CMS diff --git a/src/main/cms/cms_menu_vtx_smartaudio.c b/src/main/cms/cms_menu_vtx_smartaudio.c index 1ce6d7cca3..c7f1db9804 100644 --- a/src/main/cms/cms_menu_vtx_smartaudio.c +++ b/src/main/cms/cms_menu_vtx_smartaudio.c @@ -21,7 +21,7 @@ #include "platform.h" -#if defined(CMS) && defined(VTX_SMARTAUDIO) +#if defined(USE_CMS) && defined(VTX_SMARTAUDIO) #include "common/printf.h" #include "common/utils.h" diff --git a/src/main/cms/cms_menu_vtx_tramp.c b/src/main/cms/cms_menu_vtx_tramp.c index 5e18a17c17..f74f836757 100644 --- a/src/main/cms/cms_menu_vtx_tramp.c +++ b/src/main/cms/cms_menu_vtx_tramp.c @@ -21,7 +21,7 @@ #include "platform.h" -#if defined(CMS) && defined(VTX_TRAMP) +#if defined(USE_CMS) && defined(VTX_TRAMP) #include "common/printf.h" #include "common/utils.h" diff --git a/src/main/cms/cms_types.h b/src/main/cms/cms_types.h index 4bea82e62a..60ebb6c12b 100644 --- a/src/main/cms/cms_types.h +++ b/src/main/cms/cms_types.h @@ -39,7 +39,7 @@ typedef enum OME_String, OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's //wlasciwosci elementow -#ifdef OSD +#ifdef USE_OSD OME_VISIBLE, #endif OME_TAB, diff --git a/src/main/common/gps_conversion.c b/src/main/common/gps_conversion.c index e19dd818cf..6d96365c1a 100644 --- a/src/main/common/gps_conversion.c +++ b/src/main/common/gps_conversion.c @@ -22,7 +22,7 @@ #include "platform.h" -#ifdef GPS +#ifdef USE_GPS #define DIGIT_TO_VAL(_x) (_x - '0') diff --git a/src/main/drivers/barometer/barometer_bmp085.c b/src/main/drivers/barometer/barometer_bmp085.c index 46e5d0420f..a5a21e384a 100644 --- a/src/main/drivers/barometer/barometer_bmp085.c +++ b/src/main/drivers/barometer/barometer_bmp085.c @@ -34,7 +34,7 @@ #include "barometer_bmp085.h" -#ifdef BARO +#ifdef USE_BARO #if defined(BARO_EOC_GPIO) diff --git a/src/main/drivers/barometer/barometer_bmp280.c b/src/main/drivers/barometer/barometer_bmp280.c index 8e8bcd132d..a4c16b2e59 100644 --- a/src/main/drivers/barometer/barometer_bmp280.c +++ b/src/main/drivers/barometer/barometer_bmp280.c @@ -34,7 +34,7 @@ #include "barometer_bmp280.h" -#if defined(BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)) +#if defined(USE_BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)) typedef struct bmp280_calib_param_s { uint16_t dig_T1; /* calibration T1 data */ diff --git a/src/main/drivers/barometer/barometer_ms5611.c b/src/main/drivers/barometer/barometer_ms5611.c index f38357bc03..8073a0d4f1 100644 --- a/src/main/drivers/barometer/barometer_ms5611.c +++ b/src/main/drivers/barometer/barometer_ms5611.c @@ -20,7 +20,7 @@ #include -#if defined(BARO) && (defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611)) +#if defined(USE_BARO) && (defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611)) #include "build/build_config.h" diff --git a/src/main/drivers/camera_control.c b/src/main/drivers/camera_control.c index 596e89b372..3c5d637724 100644 --- a/src/main/drivers/camera_control.c +++ b/src/main/drivers/camera_control.c @@ -56,7 +56,7 @@ #define CAMERA_CONTROL_PIN NONE #endif -#ifdef OSD +#ifdef USE_OSD #include "io/osd.h" #endif @@ -193,7 +193,7 @@ void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs) (void) holdDurationMs; #endif -#ifdef OSD +#ifdef USE_OSD // Force OSD timeout so we are alone on the display. resumeRefreshAt = 0; #endif diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 8a903d6b2c..6f7e3884f7 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -37,7 +37,7 @@ * */ -#if defined(SONAR) +#if defined(USE_SONAR) STATIC_UNIT_TESTED volatile int32_t measurement = -1; static uint32_t lastMeasurementAt; diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 55a5ad2537..dcc62ed0cd 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -2229,7 +2229,7 @@ static void cliExit(char *cmdline) cliWriter = NULL; } -#ifdef GPS +#ifdef USE_GPS static void cliGpsPassthrough(char *cmdline) { UNUSED(cmdline); @@ -3007,7 +3007,7 @@ static void cliStatus(char *cmdline) const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM))); cliPrintLinef("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d", constrain(averageSystemLoadPercent, 0, 100), getTaskDeltaTime(TASK_GYROPID), gyroRate, rxRate, systemRate); -#if defined(OSD) || !defined(MINIMAL_CLI) +#if defined(USE_OSD) || !defined(MINIMAL_CLI) /* Flag strings are present if OSD is compiled so may as well use them even with MINIMAL_CLI */ cliPrint("Arming disable flags:"); armingDisableFlags_e flags = getArmingDisableFlags(); @@ -3121,7 +3121,7 @@ const cliResourceValue_t resourceTable[] = { { OWNER_PPMINPUT, PG_PPM_CONFIG, offsetof(ppmConfig_t, ioTag), 0 }, { OWNER_PWMINPUT, PG_PWM_CONFIG, offsetof(pwmConfig_t, ioTags[0]), PWM_INPUT_PORT_COUNT }, #endif -#ifdef SONAR +#ifdef USE_SONAR { OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 }, { OWNER_SONAR_ECHO, PG_SONAR_CONFIG, offsetof(sonarConfig_t, echoTag), 0 }, #endif @@ -3162,10 +3162,10 @@ const cliResourceValue_t resourceTable[] = { { OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 }, { OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 }, #endif -#ifdef BARO +#ifdef USE_BARO { OWNER_BARO_CS, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_csn), 0 }, #endif -#ifdef MAG +#ifdef USE_MAG { OWNER_COMPASS_CS, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_spi_csn), 0 }, #endif }; @@ -3635,7 +3635,7 @@ const clicmd_t cmdTable[] = { #endif #endif CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet), -#ifdef GPS +#ifdef USE_GPS CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough), #endif CLI_COMMAND_DEF("help", NULL, NULL, cliHelp), diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 52bbe5a5b5..30c1d0376b 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -310,7 +310,7 @@ void activateConfig(void) useRcControlsConfig(currentPidProfile); useAdjustmentConfig(currentPidProfile); -#ifdef GPS +#ifdef USE_GPS gpsUsePIDs(currentPidProfile); #endif diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index bbc719f87c..fbb8a4b9fc 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -102,7 +102,7 @@ enum { #define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) int16_t magHold; #endif @@ -130,7 +130,7 @@ void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsD static bool isCalibrating(void) { -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) { return true; } @@ -237,7 +237,7 @@ void disarm(void) if (ARMING_FLAG(ARMED)) { DISABLE_ARMING_FLAG(ARMED); -#ifdef BLACKBOX +#ifdef USE_BLACKBOX if (blackboxConfig()->device) { blackboxFinish(); } @@ -289,7 +289,7 @@ void tryArm(void) lastArmingDisabledReason = 0; //beep to indicate arming -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) { beeper(BEEPER_ARMING_GPS_FIX); } else { @@ -349,7 +349,7 @@ static void updateInflightCalibrationState(void) } } -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) void updateMagHold(void) { if (ABS(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) { @@ -509,9 +509,9 @@ void processRx(timeUs_t currentTimeUs) DISABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM); } -#if defined(ACC) || defined(MAG) +#if defined(USE_ACC) || defined(USE_MAG) if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) { -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) if (IS_RC_MODE_ACTIVE(BOXMAG)) { if (!FLIGHT_MODE(MAG_MODE)) { ENABLE_FLIGHT_MODE(MAG_MODE); @@ -536,7 +536,7 @@ void processRx(timeUs_t currentTimeUs) } #endif -#ifdef GPS +#ifdef USE_GPS if (sensors(SENSOR_GPS)) { updateGpsWaypointsAndMode(); } @@ -594,13 +594,13 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs) gyroReadTemperature(); } -#ifdef MAG +#ifdef USE_MAG if (sensors(SENSOR_MAG)) { updateMagHold(); } #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { @@ -632,7 +632,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs) processRcCommand(); -#ifdef GPS +#ifdef USE_GPS if (sensors(SENSOR_GPS)) { if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) { updateGpsStateForHomeAndHoldMode(); @@ -644,7 +644,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs) afatfs_poll(); #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX if (!cliMode && blackboxConfig()->device) { blackboxUpdate(currentTimeUs); } diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index 55bc350914..f6f3b20f00 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -20,7 +20,7 @@ #include "common/time.h" #include "config/parameter_group.h" -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) extern int16_t magHold; #endif diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 1f0a9a3756..1a8976742d 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -472,13 +472,13 @@ void init(void) cameraControlInit(); #endif -#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL2) +#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(USE_SONAR) && defined(USE_SOFTSERIAL2) if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { serialRemovePort(SERIAL_PORT_SOFTSERIAL2); } #endif -#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL1) +#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(USE_SONAR) && defined(USE_SOFTSERIAL1) if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { serialRemovePort(SERIAL_PORT_SOFTSERIAL1); } @@ -550,15 +550,15 @@ void init(void) /* * CMS, display devices and OSD */ -#ifdef CMS +#ifdef USE_CMS cmsInit(); #endif -#if (defined(OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(CMS)) || defined(USE_OSD_SLAVE)) +#if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)) || defined(USE_OSD_SLAVE)) displayPort_t *osdDisplayPort = NULL; #endif -#if defined(OSD) && !defined(USE_OSD_SLAVE) +#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)) { @@ -573,7 +573,7 @@ void init(void) } #endif -#if defined(USE_OSD_SLAVE) && !defined(OSD) +#if defined(USE_OSD_SLAVE) && !defined(USE_OSD) #if defined(USE_MAX7456) // If there is a max7456 chip for the OSD then use it osdDisplayPort = max7456DisplayPortInit(vcdProfile()); @@ -582,7 +582,7 @@ void init(void) #endif #endif -#if defined(CMS) && defined(USE_MSP_DISPLAYPORT) +#if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) // If BFOSD is not active, then register MSP_DISPLAYPORT as a CMS device. if (!osdDisplayPort) cmsDisplayPortRegister(displayPortMspInit()); @@ -596,7 +596,7 @@ void init(void) #endif -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS)) { gpsInit(); navigationInit(); @@ -650,7 +650,7 @@ void init(void) } #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX blackboxInit(); #endif @@ -658,7 +658,7 @@ void init(void) accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); } gyroStartCalibration(false); -#ifdef BARO +#ifdef USE_BARO baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES); #endif @@ -731,4 +731,4 @@ void init(void) fcTasksInit(); systemState |= SYSTEM_STATE_READY; -} \ No newline at end of file +} diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index c5832a4dd8..7cfdbe5f09 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -413,7 +413,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce #ifdef USE_OSD_SLAVE sbufWriteU8(dst, 1); // 1 == OSD #else -#if defined(OSD) && defined(USE_MAX7456) +#if defined(USE_OSD) && defined(USE_MAX7456) sbufWriteU8(dst, 2); // 2 == FC with OSD #else sbufWriteU8(dst, 0); // 0 == FC @@ -617,7 +617,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce #define OSD_FLAGS_OSD_HARDWARE_MAX_7456 (1 << 4) uint8_t osdFlags = 0; -#if defined(OSD) +#if defined(USE_OSD) osdFlags |= OSD_FLAGS_OSD_FEATURE; #endif #if defined(USE_OSD_SLAVE) @@ -636,7 +636,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce sbufWriteU8(dst, 0); #endif -#ifdef OSD +#ifdef USE_OSD // OSD specific, not applicable to OSD slaves. // Configuration @@ -840,7 +840,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) break; case MSP_ALTITUDE: -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) sbufWriteU32(dst, getEstimatedAltitude()); #else sbufWriteU32(dst, 0); @@ -849,7 +849,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) break; case MSP_SONAR_ALTITUDE: -#if defined(SONAR) +#if defined(USE_SONAR) sbufWriteU32(dst, sonarGetLatestAltitude()); #else sbufWriteU32(dst, 0); @@ -929,7 +929,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) sbufWriteU16(dst, motorConfig()->mincommand); break; -#ifdef MAG +#ifdef USE_MAG case MSP_COMPASS_CONFIG: sbufWriteU16(dst, compassConfig()->mag_declination / 10); break; @@ -945,7 +945,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) break; #endif -#ifdef GPS +#ifdef USE_GPS case MSP_GPS_CONFIG: sbufWriteU8(dst, gpsConfig()->provider); sbufWriteU8(dst, gpsConfig()->sbasMode); @@ -1103,7 +1103,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) break; case MSP_BLACKBOX_CONFIG: -#ifdef BLACKBOX +#ifdef USE_BLACKBOX sbufWriteU8(dst, 1); //Blackbox supported sbufWriteU8(dst, blackboxConfig()->device); sbufWriteU8(dst, blackboxGetRateNum()); @@ -1255,7 +1255,7 @@ static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *arg, sb } #endif // USE_OSD_SLAVE -#ifdef GPS +#ifdef USE_GPS static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src) { uint8_t wp_no; @@ -1316,7 +1316,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) uint32_t i; uint8_t value; const unsigned int dataSize = sbufBytesRemaining(src); -#ifdef GPS +#ifdef USE_GPS uint8_t wp_no; int32_t lat = 0, lon = 0, alt = 0; #endif @@ -1352,7 +1352,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) } break; -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) case MSP_SET_HEADING: magHold = sbufReadU16(src); break; @@ -1470,7 +1470,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) motorConfigMutable()->mincommand = sbufReadU16(src); break; -#ifdef GPS +#ifdef USE_GPS case MSP_SET_GPS_CONFIG: gpsConfigMutable()->provider = sbufReadU8(src); gpsConfigMutable()->sbasMode = sbufReadU8(src); @@ -1479,7 +1479,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) break; #endif -#ifdef MAG +#ifdef USE_MAG case MSP_SET_COMPASS_CONFIG: compassConfigMutable()->mag_declination = sbufReadU16(src) * 10; break; @@ -1652,7 +1652,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) readEEPROM(); break; -#ifdef BLACKBOX +#ifdef USE_BLACKBOX case MSP_SET_BLACKBOX_CONFIG: // Don't allow config to be updated while Blackbox is logging if (blackboxMayEditConfig()) { @@ -1745,7 +1745,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) break; #endif -#ifdef GPS +#ifdef USE_GPS case MSP_SET_RAW_GPS: if (sbufReadU8(src)) { ENABLE_STATE(GPS_FIX); @@ -2066,7 +2066,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src) batteryConfigMutable()->currentMeterSource = sbufReadU8(src); break; -#if defined(OSD) || defined (USE_OSD_SLAVE) +#if defined(USE_OSD) || defined (USE_OSD_SLAVE) case MSP_SET_OSD_CONFIG: { const uint8_t addr = sbufReadU8(src); @@ -2078,7 +2078,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src) #else sbufReadU8(src); // Skip video system #endif -#if defined(OSD) +#if defined(USE_OSD) osdConfigMutable()->units = sbufReadU8(src); // Alarms @@ -2093,7 +2093,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src) } #endif } else if ((int8_t)addr == -2) { -#if defined(OSD) +#if defined(USE_OSD) // Timers uint8_t index = sbufReadU8(src); if (index > OSD_TIMER_COUNT) { @@ -2103,7 +2103,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src) #endif return MSP_RESULT_ERROR; } else { -#if defined(OSD) +#if defined(USE_OSD) const uint16_t value = sbufReadU16(src); /* Get screen index, 0 is post flight statistics, 1 and above are in flight OSD screens */ @@ -2173,7 +2173,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro mspFc4waySerialCommand(dst, src, mspPostProcessFn); ret = MSP_RESULT_ACK; #endif -#ifdef GPS +#ifdef USE_GPS } else if (cmdMSP == MSP_WP) { mspFcWpCommand(dst, src); ret = MSP_RESULT_ACK; diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index b5493b394a..b1da9954e6 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -167,19 +167,19 @@ void initActiveBoxIds(void) BME(BOXHEADADJ); } -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { BME(BOXBARO); } #endif -#ifdef MAG +#ifdef USE_MAG if (sensors(SENSOR_MAG)) { BME(BOXMAG); } #endif -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS)) { BME(BOXGPSHOME); BME(BOXGPSHOLD); @@ -187,7 +187,7 @@ void initActiveBoxIds(void) } #endif -#ifdef SONAR +#ifdef USE_SONAR if (feature(FEATURE_SONAR)) { BME(BOXSONAR); } @@ -207,7 +207,7 @@ void initActiveBoxIds(void) } #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX BME(BOXBLACKBOX); #ifdef USE_FLASHFS BME(BOXBLACKBOXERASE); diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index d46a1d927f..3fd0ad6181 100644 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -138,19 +138,19 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs) processRx(currentTimeUs); isRXDataNew = true; -#if !defined(BARO) && !defined(SONAR) +#if !defined(USE_BARO) && !defined(USE_SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); #endif updateArmingStatus(); -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { updateAltHoldState(); } #endif -#ifdef SONAR +#ifdef USE_SONAR if (sensors(SENSOR_SONAR)) { updateSonarAltHoldState(); } @@ -158,7 +158,7 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs) } #endif -#ifdef MAG +#ifdef USE_MAG static void taskUpdateCompass(timeUs_t currentTimeUs) { if (sensors(SENSOR_MAG)) { @@ -167,7 +167,7 @@ static void taskUpdateCompass(timeUs_t currentTimeUs) } #endif -#ifdef BARO +#ifdef USE_BARO static void taskUpdateBaro(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); @@ -181,14 +181,14 @@ static void taskUpdateBaro(timeUs_t currentTimeUs) } #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) static void taskCalculateAltitude(timeUs_t currentTimeUs) { if (false -#if defined(BARO) +#if defined(USE_BARO) || (sensors(SENSOR_BARO) && isBaroReady()) #endif -#if defined(SONAR) +#if defined(USE_SONAR) || sensors(SENSOR_SONAR) #endif ) { @@ -281,19 +281,19 @@ void fcTasksInit(void) #ifdef BEEPER setTaskEnabled(TASK_BEEPER, true); #endif -#ifdef GPS +#ifdef USE_GPS setTaskEnabled(TASK_GPS, feature(FEATURE_GPS)); #endif -#ifdef MAG +#ifdef USE_MAG setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG)); #endif -#ifdef BARO +#ifdef USE_BARO setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO)); #endif -#ifdef SONAR +#ifdef USE_SONAR setTaskEnabled(TASK_SONAR, sensors(SENSOR_SONAR)); #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)); #endif #ifdef USE_DASHBOARD @@ -317,7 +317,7 @@ void fcTasksInit(void) #ifdef TRANSPONDER setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER)); #endif -#ifdef OSD +#ifdef USE_OSD setTaskEnabled(TASK_OSD, feature(FEATURE_OSD)); #endif #ifdef USE_BST @@ -326,7 +326,7 @@ void fcTasksInit(void) #ifdef USE_ESC_SENSOR setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR)); #endif -#ifdef CMS +#ifdef USE_CMS #ifdef USE_MSP_DISPLAYPORT setTaskEnabled(TASK_CMS, true); #else @@ -463,7 +463,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef GPS +#ifdef USE_GPS [TASK_GPS] = { .taskName = "GPS", .taskFunc = gpsUpdate, @@ -472,7 +472,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef MAG +#ifdef USE_MAG [TASK_COMPASS] = { .taskName = "COMPASS", .taskFunc = taskUpdateCompass, @@ -481,7 +481,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef BARO +#ifdef USE_BARO [TASK_BARO] = { .taskName = "BARO", .taskFunc = taskUpdateBaro, @@ -490,7 +490,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef SONAR +#ifdef USE_SONAR [TASK_SONAR] = { .taskName = "SONAR", .taskFunc = sonarUpdate, @@ -499,7 +499,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) [TASK_ALTITUDE] = { .taskName = "ALTITUDE", .taskFunc = taskCalculateAltitude, @@ -517,7 +517,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef OSD +#ifdef USE_OSD [TASK_OSD] = { .taskName = "OSD", .taskFunc = osdUpdate, @@ -562,7 +562,7 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef CMS +#ifdef USE_CMS [TASK_CMS] = { .taskName = "CMS", .taskFunc = cmsHandler, diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 8f58e13252..ddfcb04ec1 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -141,7 +141,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus) static uint8_t rcDisarmTicks; static bool doNotRepeat; -#ifdef CMS +#ifdef USE_CMS if (cmsInMenu) { return; } @@ -224,13 +224,13 @@ void processRcStickPositions(throttleStatus_e throttleStatus) // GYRO calibration gyroStartCalibration(false); -#ifdef GPS +#ifdef USE_GPS if (feature(FEATURE_GPS)) { GPS_reset_home_position(); } #endif -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) baroSetCalibrationCycles(10); // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking) #endif diff --git a/src/main/fc/runtime_config.c b/src/main/fc/runtime_config.c index c8bae0d854..07aa8e92a4 100644 --- a/src/main/fc/runtime_config.c +++ b/src/main/fc/runtime_config.c @@ -29,7 +29,7 @@ uint16_t flightModeFlags = 0; static uint32_t enabledSensors = 0; -#if defined(OSD) || !defined(MINIMAL_CLI) +#if defined(USE_OSD) || !defined(MINIMAL_CLI) const char *armingDisableFlagNames[]= { "NOGYRO", "FAILSAFE", "RXLOSS", "BADRX", "BOXFAILSAFE", "THROTTLE", "ANGLE", "BOOTGRACE", "NOPREARM", "LOAD", diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 3fb13b8c3f..9bd62ad2fb 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -56,7 +56,7 @@ typedef enum { #define NUM_ARMING_DISABLE_FLAGS 17 -#if defined(OSD) || !defined(MINIMAL_CLI) +#if defined(USE_OSD) || !defined(MINIMAL_CLI) extern const char *armingDisableFlagNames[NUM_ARMING_DISABLE_FLAGS]; #endif diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index d2e11ba12d..b7a836f6ff 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -97,13 +97,13 @@ const char * const lookupTableGyroHardware[] = { "BMI160", "FAKE" }; -#if defined(USE_SENSOR_NAMES) || defined(BARO) +#if defined(USE_SENSOR_NAMES) || defined(USE_BARO) // sync with baroSensor_e const char * const lookupTableBaroHardware[] = { "AUTO", "NONE", "BMP085", "MS5611", "BMP280" }; #endif -#if defined(USE_SENSOR_NAMES) || defined(MAG) +#if defined(USE_SENSOR_NAMES) || defined(USE_MAG) // sync with magSensor_e const char * const lookupTableMagHardware[] = { "AUTO", "NONE", "HMC5883", "AK8975", "AK8963" @@ -134,7 +134,7 @@ static const char * const lookupTableAlignment[] = { "CW270FLIP" }; -#ifdef GPS +#ifdef USE_GPS static const char * const lookupTableGPSProvider[] = { "NMEA", "UBLOX" }; @@ -158,7 +158,7 @@ static const char * const lookupTableGimbalMode[] = { }; #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX static const char * const lookupTableBlackboxDevice[] = { "NONE", "SPIFLASH", "SDCARD", "SERIAL" }; @@ -208,7 +208,7 @@ static const char * const lookupTableGyroLpf[] = { "EXPERIMENTAL" }; -#ifdef OSD +#ifdef USE_OSD static const char * const lookupTableOsdType[] = { "AUTO", "PAL", @@ -265,11 +265,11 @@ const lookupTableEntry_t lookupTables[] = { { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) }, { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) }, { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) }, -#ifdef GPS +#ifdef USE_GPS { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) }, { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) }, #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) }, #endif { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) }, @@ -286,10 +286,10 @@ const lookupTableEntry_t lookupTables[] = { { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) }, { lookupTableGyroHardware, sizeof(lookupTableGyroHardware) / sizeof(char *) }, { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) }, -#ifdef BARO +#ifdef USE_BARO { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) }, #endif -#ifdef MAG +#ifdef USE_MAG { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) }, #endif { debugModeNames, sizeof(debugModeNames) / sizeof(char *) }, @@ -300,7 +300,7 @@ const lookupTableEntry_t lookupTables[] = { { lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) }, { lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) }, { lookupTableCrashRecovery, sizeof(lookupTableCrashRecovery) / sizeof(char *) }, -#ifdef OSD +#ifdef USE_OSD { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) }, #endif #ifdef USE_CAMERA_CONTROL @@ -347,7 +347,7 @@ const clivalue_t valueTable[] = { { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.roll) }, // PG_COMPASS_CONFIG -#ifdef MAG +#ifdef USE_MAG { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_align) }, { "mag_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_bustype) }, { "mag_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_i2c_device) }, @@ -361,7 +361,7 @@ const clivalue_t valueTable[] = { #endif // PG_BAROMETER_CONFIG -#ifdef BARO +#ifdef USE_BARO { "baro_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_bustype) }, { "baro_spi_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_device) }, { "baro_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_device) }, @@ -407,7 +407,7 @@ const clivalue_t valueTable[] = { #endif // PG_BLACKBOX_CONFIG -#ifdef BLACKBOX +#ifdef USE_BLACKBOX { "blackbox_p_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, p_denom) }, { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) }, { "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) }, @@ -537,7 +537,7 @@ const clivalue_t valueTable[] = { // PG_GPS_CONFIG -#ifdef GPS +#ifdef USE_GPS { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) }, { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) }, { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) }, @@ -545,7 +545,7 @@ const clivalue_t valueTable[] = { #endif // PG_NAVIGATION_CONFIG -#ifdef GPS +#ifdef USE_GPS { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, gps_wp_radius) }, { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_controls_heading) }, { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_min) }, @@ -554,7 +554,7 @@ const clivalue_t valueTable[] = { #endif // PG_AIRPLANE_CONFIG -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) { "fixedwing_althold_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_reversed) }, #endif @@ -623,7 +623,7 @@ const clivalue_t valueTable[] = { { "horizon_tilt_effect", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 250 }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_effect) }, { "horizon_tilt_expert_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_expert_mode) }, -#ifdef GPS +#ifdef USE_GPS { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].P) }, { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].I) }, { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].D) }, @@ -641,7 +641,7 @@ const clivalue_t valueTable[] = { { "tlm_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inverted) }, { "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) }, #if defined(TELEMETRY_FRSKY) -#if defined(GPS) +#if defined(USE_GPS) { "frsky_default_lat", VAR_INT16 | MASTER_VALUE, .config.minmax = { -9000, 9000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) }, { "frsky_default_long", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) }, { "frsky_gps_format", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_coordinate_format) }, @@ -667,7 +667,7 @@ const clivalue_t valueTable[] = { #endif // PG_OSD_CONFIG -#ifdef OSD +#ifdef USE_OSD { "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_OSD_CONFIG, offsetof(osdConfig_t, units) }, { "osd_warnings", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings) }, diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index 7283bb4f27..730c2d1c9f 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -26,11 +26,11 @@ typedef enum { TABLE_OFF_ON = 0, TABLE_UNIT, TABLE_ALIGNMENT, -#ifdef GPS +#ifdef USE_GPS TABLE_GPS_PROVIDER, TABLE_GPS_SBAS_MODE, #endif -#ifdef BLACKBOX +#ifdef USE_BLACKBOX TABLE_BLACKBOX_DEVICE, #endif TABLE_CURRENT_METER, @@ -47,10 +47,10 @@ typedef enum { TABLE_GYRO_LPF, TABLE_GYRO_HARDWARE, TABLE_ACC_HARDWARE, -#ifdef BARO +#ifdef USE_BARO TABLE_BARO_HARDWARE, #endif -#ifdef MAG +#ifdef USE_MAG TABLE_MAG_HARDWARE, #endif TABLE_DEBUG, @@ -61,7 +61,7 @@ typedef enum { TABLE_LOWPASS_TYPE, TABLE_FAILSAFE, TABLE_CRASH_RECOVERY, -#ifdef OSD +#ifdef USE_OSD TABLE_OSD, #endif #ifdef USE_CAMERA_CONTROL diff --git a/src/main/flight/altitude.c b/src/main/flight/altitude.c index 7ae6f62496..2ddb331441 100644 --- a/src/main/flight/altitude.c +++ b/src/main/flight/altitude.c @@ -52,7 +52,7 @@ static int32_t estimatedVario = 0; // variometer in cm/s static int32_t estimatedAltitude = 0; // in cm -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) enum { DEBUG_ALTITUDE_ACC, @@ -216,7 +216,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs) static float accAlt = 0.0f; int32_t baroAlt = 0; -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { if (!isBaroCalibrationComplete()) { performBaroCalibrationCycle(); @@ -229,7 +229,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs) } #endif -#ifdef SONAR +#ifdef USE_SONAR if (sensors(SENSOR_SONAR)) { int32_t sonarAlt = sonarCalculateAltitude(sonarRead(), getCosTiltAngle()); if (sonarAlt > 0 && sonarAlt >= sonarCfAltCm && sonarAlt <= sonarMaxAltWithTiltCm) { @@ -242,7 +242,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs) #endif float accZ_tmp = 0; -#ifdef ACC +#ifdef USE_ACC if (sensors(SENSOR_ACC)) { const float dt = accTimeSum * 1e-6f; // delta acc reading time in seconds @@ -267,7 +267,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs) imuResetAccelerationSum(); int32_t baroVel = 0; -#ifdef BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { if (!isBaroCalibrationComplete()) { return; @@ -294,7 +294,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs) altHoldThrottleAdjustment = calculateAltHoldThrottleAdjustment(vel_tmp, accZ_tmp, accZ_old); accZ_old = accZ_tmp; } -#endif // defined(BARO) || defined(SONAR) +#endif // defined(USE_BARO) || defined(USE_SONAR) int32_t getEstimatedAltitude(void) { diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index bd4479add0..851c083e06 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -423,7 +423,7 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs) if (sensors(SENSOR_MAG) && isMagnetometerHealthy()) { useMag = true; } -#if defined(GPS) +#if defined(USE_GPS) else if (STATE(FIXED_WING) && sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5 && gpsSol.groundSpeed >= 300) { // In case of a fixed-wing aircraft we can use GPS course over ground to correct heading rawYawError = DECIDEGREES_TO_RADIANS(attitude.values.yaw - gpsSol.groundCourse); diff --git a/src/main/flight/navigation.c b/src/main/flight/navigation.c index d107939d0e..7f6f98e59e 100644 --- a/src/main/flight/navigation.c +++ b/src/main/flight/navigation.c @@ -22,7 +22,7 @@ #include "platform.h" -#ifdef GPS +#ifdef USE_GPS #include "build/debug.h" diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index c8ee291b4d..3b87ab358a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -371,7 +371,7 @@ static float pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPit // calculate error angle and limit the angle to the max inclination // rcDeflection is in range [-1.0, 1.0] float angle = pidProfile->levelAngleLimit * getRcDeflection(axis); -#ifdef GPS +#ifdef USE_GPS angle += GPS_angle[axis]; #endif angle = constrainf(angle, -pidProfile->levelAngleLimit, pidProfile->levelAngleLimit); diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index d59570d378..549af0bb0c 100755 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -39,7 +39,7 @@ #include "io/statusindicator.h" #include "io/vtx_control.h" -#ifdef GPS +#ifdef USE_GPS #include "io/gps.h" #endif @@ -331,7 +331,7 @@ void beeperWarningBeeps(uint8_t beepCount) beeper(BEEPER_MULTI_BEEPS); } -#ifdef GPS +#ifdef USE_GPS static void beeperGpsStatus(void) { if (!(getBeeperOffMask() & (1 << (BEEPER_GPS_STATUS - 1)))) { @@ -361,7 +361,7 @@ void beeperUpdate(timeUs_t currentTimeUs) // If beeper option from AUX switch has been selected if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { beeper(BEEPER_RX_SET); -#ifdef GPS +#ifdef USE_GPS } else if (feature(FEATURE_GPS) && IS_RC_MODE_ACTIVE(BOXBEEPGPSCOUNT)) { beeperGpsStatus(); #endif diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c index 4d34a025a2..ba6bd94371 100644 --- a/src/main/io/dashboard.c +++ b/src/main/io/dashboard.c @@ -148,7 +148,7 @@ static void padLineBuffer(void) lineBuffer[length] = 0; } -#ifdef GPS +#ifdef USE_GPS static void padHalfLineBuffer(void) { uint8_t halfLineIndex = sizeof(lineBuffer) / 2; @@ -345,7 +345,7 @@ static void showProfilePage(void) #define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0])) #define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2) -#ifdef GPS +#ifdef USE_GPS static void showGpsPage(void) { if (!feature(FEATURE_GPS)) { @@ -489,7 +489,7 @@ static void showSensorsPage(void) i2c_OLED_send_string(bus, lineBuffer); } -#ifdef MAG +#ifdef USE_MAG if (sensors(SENSOR_MAG)) { tfp_sprintf(lineBuffer, format, "MAG", mag.magADC[X], mag.magADC[Y], mag.magADC[Z]); padLineBuffer(); @@ -575,7 +575,7 @@ static const pageEntry_t pages[PAGE_COUNT] = { { PAGE_WELCOME, FC_FIRMWARE_NAME, showWelcomePage, PAGE_FLAGS_SKIP_CYCLING }, { PAGE_ARMED, "ARMED", showArmedPage, PAGE_FLAGS_SKIP_CYCLING }, { PAGE_PROFILE, "PROFILE", showProfilePage, PAGE_FLAGS_NONE }, -#ifdef GPS +#ifdef USE_GPS { PAGE_GPS, "GPS", showGpsPage, PAGE_FLAGS_NONE }, #endif { PAGE_RX, "RX", showRxPage, PAGE_FLAGS_NONE }, @@ -605,7 +605,7 @@ void dashboardUpdate(timeUs_t currentTimeUs) { static uint8_t previousArmedState = 0; -#ifdef CMS +#ifdef USE_CMS if (displayIsGrabbed(displayPort)) { return; } @@ -686,7 +686,7 @@ void dashboardInit(void) delay(200); displayPort = displayPortOledInit(bus); -#if defined(CMS) +#if defined(USE_CMS) if (dashboardPresent) { cmsDisplayPortRegister(displayPort); } diff --git a/src/main/io/dashboard.h b/src/main/io/dashboard.h index becc55d402..8ea6310769 100644 --- a/src/main/io/dashboard.h +++ b/src/main/io/dashboard.h @@ -48,7 +48,7 @@ typedef enum { #ifndef SKIP_TASK_STATISTICS PAGE_TASKS, #endif -#ifdef GPS +#ifdef USE_GPS PAGE_GPS, #endif #ifdef ENABLE_DEBUG_DASHBOARD_PAGE diff --git a/src/main/io/displayport_max7456.c b/src/main/io/displayport_max7456.c index bd5afd4e56..05d40ca3a7 100644 --- a/src/main/io/displayport_max7456.c +++ b/src/main/io/displayport_max7456.c @@ -54,7 +54,7 @@ static int grab(displayPort_t *displayPort) { // FIXME this should probably not have a dependency on the OSD or OSD slave code UNUSED(displayPort); -#ifdef OSD +#ifdef USE_OSD osdResetAlarms(); resumeRefreshAt = 0; #endif diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 4c4c51b10e..b52266b2b7 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -24,7 +24,7 @@ #include "platform.h" -#ifdef GPS +#ifdef USE_GPS #include "build/build_config.h" #include "build/debug.h" diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 47c73b3713..4d543921cb 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -430,10 +430,10 @@ static const struct { uint8_t ledMode; } flightModeToLed[] = { {HEADFREE_MODE, LED_MODE_HEADFREE}, -#ifdef MAG +#ifdef USE_MAG {MAG_MODE, LED_MODE_MAG}, #endif -#ifdef BARO +#ifdef USE_BARO {BARO_MODE, LED_MODE_BARO}, #endif {HORIZON_MODE, LED_MODE_HORIZON}, @@ -735,7 +735,7 @@ static void applyLedRssiLayer(bool updateNow, timeUs_t *timer) } } -#ifdef GPS +#ifdef USE_GPS static void applyLedGpsLayer(bool updateNow, timeUs_t *timer) { @@ -996,7 +996,7 @@ typedef enum { timLarson, timBattery, timRssi, -#ifdef GPS +#ifdef USE_GPS timGps, #endif timWarning, @@ -1025,7 +1025,7 @@ static applyLayerFn_timed* layerTable[] = { [timLarson] = &applyLarsonScannerLayer, [timBattery] = &applyLedBatteryLayer, [timRssi] = &applyLedRssiLayer, -#ifdef GPS +#ifdef USE_GPS [timGps] = &applyLedGpsLayer, #endif [timWarning] = &applyLedWarningLayer, diff --git a/src/main/io/osd.c b/src/main/io/osd.c index e2189872a9..ab3233a2f3 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -31,7 +31,7 @@ #include "platform.h" -#ifdef OSD +#ifdef USE_OSD #include "blackbox/blackbox.h" #include "blackbox/blackbox_io.h" @@ -346,7 +346,7 @@ static void osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%4d%c", getMAhDrawn(), SYM_MAH); break; -#ifdef GPS +#ifdef USE_GPS case OSD_GPS_SATS: tfp_sprintf(buff, "%c%c%d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat); break; @@ -769,7 +769,7 @@ static void osdDrawElements(void) osdDrawSingleElement(OSD_NUMERICAL_VARIO); osdDrawSingleElement(OSD_COMPASS_BAR); -#ifdef GPS +#ifdef USE_GPS if (sensors(SENSOR_GPS)) { osdDrawSingleElement(OSD_GPS_SATS); osdDrawSingleElement(OSD_GPS_SPEED); @@ -847,7 +847,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse) BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31)); osdDisplayPort = osdDisplayPortToUse; -#ifdef CMS +#ifdef USE_CMS cmsDisplayPortRegister(osdDisplayPort); #endif @@ -862,7 +862,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse) char string_buffer[30]; tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING); displayWrite(osdDisplayPort, 20, 6, string_buffer); -#ifdef CMS +#ifdef USE_CMS displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1); displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2); displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3); @@ -952,7 +952,7 @@ static void osdResetStats(void) static void osdUpdateStats(void) { int16_t value = 0; -#ifdef GPS +#ifdef USE_GPS value = CM_S_TO_KM_H(gpsSol.groundSpeed); #endif if (stats.max_speed < value) @@ -971,14 +971,14 @@ static void osdUpdateStats(void) if (stats.max_altitude < getEstimatedAltitude()) stats.max_altitude = getEstimatedAltitude(); -#ifdef GPS +#ifdef USE_GPS if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && (stats.max_distance < GPS_distanceToHome)) { stats.max_distance = GPS_distanceToHome; } #endif } -#ifdef BLACKBOX +#ifdef USE_BLACKBOX static void osdGetBlackboxStatusString(char * buff) { bool storageDeviceIsWorking = false; @@ -1101,7 +1101,7 @@ static void osdShowStats(void) osdDisplayStatisticLabel(top++, "MAX ALTITUDE", buff); } -#ifdef BLACKBOX +#ifdef USE_BLACKBOX if (osdConfig()->enabled_stats[OSD_STAT_BLACKBOX] && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) { osdGetBlackboxStatusString(buff); osdDisplayStatisticLabel(top++, "BLACKBOX", buff); @@ -1175,7 +1175,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs) } #endif -#ifdef CMS +#ifdef USE_CMS if (!displayIsGrabbed(osdDisplayPort)) { osdUpdateAlarms(); osdDrawElements(); @@ -1230,7 +1230,7 @@ void osdUpdate(timeUs_t currentTimeUs) displayDrawScreen(osdDisplayPort); } -#ifdef CMS +#ifdef USE_CMS // do not allow ARM if we are in menu if (displayIsGrabbed(osdDisplayPort)) { setArmingDisabled(ARMING_DISABLED_OSD_MENU); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index f1c56b340b..768bd09019 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -17,7 +17,7 @@ #pragma once -#ifdef OSD +#ifdef USE_OSD #include "common/time.h" #include "config/parameter_group.h" diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index 73633e2f61..241ecdb78f 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -195,7 +195,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); -#ifdef CMS +#ifdef USE_CMS if (cmsInMenu) { return; } diff --git a/src/main/io/serial.c b/src/main/io/serial.c index a6f29a65a7..64d3e26e1e 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -514,7 +514,7 @@ void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar) } } -#if defined(GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH) +#if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH) // Default data consumer for serialPassThrough. static void nopConsumer(uint8_t data) { diff --git a/src/main/io/vtx_rtc6705.c b/src/main/io/vtx_rtc6705.c index c786772c70..66bf5e78a8 100644 --- a/src/main/io/vtx_rtc6705.c +++ b/src/main/io/vtx_rtc6705.c @@ -52,7 +52,7 @@ bool canUpdateVTX(void); #define WAIT_FOR_VTX while (!canUpdateVTX()) {} -#if defined(CMS) || defined(VTX_COMMON) +#if defined(USE_CMS) || defined(VTX_COMMON) const char * const rtc6705PowerNames[VTX_RTC6705_POWER_COUNT] = { "---", "25 ", "200", }; diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 9d1c1caf74..dc8d2a663f 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -64,7 +64,7 @@ serialPort_t *debugSerialPort = NULL; static serialPort_t *smartAudioSerialPort = NULL; -#if defined(CMS) || defined(VTX_COMMON) +#if defined(USE_CMS) || defined(VTX_COMMON) static const char * const saPowerNames[VTX_SMARTAUDIO_POWER_COUNT+1] = { "---", "25 ", "200", "500", "800", }; @@ -349,7 +349,7 @@ static void saProcessResponse(uint8_t *buf, int len) // Todo: Update states in saVtxDevice? #endif -#ifdef CMS +#ifdef USE_CMS // Export current device status for CMS saCmsUpdate(); saUpdateStatusString(); diff --git a/src/main/io/vtx_smartaudio.h b/src/main/io/vtx_smartaudio.h index 6a862cb0ea..c7fba6c15c 100644 --- a/src/main/io/vtx_smartaudio.h +++ b/src/main/io/vtx_smartaudio.h @@ -112,7 +112,7 @@ extern serialPort_t *debugSerialPort; #endif // SMARTAUDIO_DPRINTF #if 0 -#ifdef CMS +#ifdef USE_CMS uint16_t smartAudioSmartbaud; diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 520c7dd3e9..e1e13c33e7 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -41,7 +41,7 @@ #include "io/vtx_control.h" #include "io/vtx_string.h" -#if defined(CMS) || defined(VTX_COMMON) +#if defined(USE_CMS) || defined(VTX_COMMON) const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = { 25, 100, 200, 400, 600 }; @@ -519,7 +519,7 @@ void vtxTrampProcess(uint32_t currentTimeUs) debug[3] = 0; #endif -#ifdef CMS +#ifdef USE_CMS trampCmsUpdateStatusString(); #endif } diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 110e7d3514..e4d6d540d9 100644 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -62,19 +62,19 @@ typedef enum { #ifdef BEEPER TASK_BEEPER, #endif -#ifdef GPS +#ifdef USE_GPS TASK_GPS, #endif -#ifdef MAG +#ifdef USE_MAG TASK_COMPASS, #endif -#ifdef BARO +#ifdef USE_BARO TASK_BARO, #endif -#ifdef SONAR +#ifdef USE_SONAR TASK_SONAR, #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) TASK_ALTITUDE, #endif #ifdef USE_DASHBOARD @@ -92,7 +92,7 @@ typedef enum { #ifdef STACK_CHECK TASK_STACK_CHECK, #endif -#ifdef OSD +#ifdef USE_OSD TASK_OSD, #endif #ifdef USE_OSD_SLAVE @@ -104,7 +104,7 @@ typedef enum { #ifdef USE_ESC_SENSOR TASK_ESC_SENSOR, #endif -#ifdef CMS +#ifdef USE_CMS TASK_CMS, #endif #ifdef VTX_CONTROL diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 37d76ce8c3..921e7eaf23 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -111,7 +111,7 @@ void pgResetFn_barometerConfig(barometerConfig_t *barometerConfig) #endif } -#ifdef BARO +#ifdef USE_BARO static uint16_t calibratingB = 0; // baro calibration = get new ground pressure value static int32_t baroPressure = 0; diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 88d91091fb..57114d1ca7 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -106,7 +106,7 @@ void pgResetFn_compassConfig(compassConfig_t *compassConfig) compassConfig->interruptTag = COMPASS_INTERRUPT_TAG; } -#if defined(MAG) +#if defined(USE_MAG) static int16_t magADCRaw[XYZ_AXIS_COUNT]; static uint8_t magInit = 0; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 4a59bf88f4..c5cecf4d6a 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -41,7 +41,7 @@ uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; -#ifdef SONAR +#ifdef USE_SONAR static bool sonarDetect(void) { if (feature(FEATURE_SONAR)) { @@ -65,15 +65,15 @@ bool sensorsAutodetect(void) accInit(gyro.targetLooptime); } -#ifdef MAG +#ifdef USE_MAG compassInit(); #endif -#ifdef BARO +#ifdef USE_BARO baroDetect(&baro.dev, barometerConfig()->baro_hardware); #endif -#ifdef SONAR +#ifdef USE_SONAR if (sonarDetect()) { sonarInit(sonarConfig()); } diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 7cc96fde75..6f90170c27 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -21,7 +21,7 @@ #include "platform.h" -#ifdef SONAR +#ifdef USE_SONAR #include "build/build_config.h" diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 1d441a5c10..6af85e3e7f 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -31,8 +31,8 @@ #define USE_MPU_DATA_READY_SIGNAL //#define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO -#define ACC +#define USE_GYRO +#define USE_ACC #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW180_DEG @@ -48,10 +48,10 @@ #define MPU6000_CS_PIN PB12 #define MPU6000_SPI_INSTANCE SPI2 -//#define BARO +//#define USE_BARO //#define USE_BARO_MS5611 -//#define MAG +//#define USE_MAG //#define USE_MAG_HMC5883 #define USE_VCP diff --git a/src/main/target/AIRHEROF3/target.h b/src/main/target/AIRHEROF3/target.h index 56999cec8e..ed77d40798 100644 --- a/src/main/target/AIRHEROF3/target.h +++ b/src/main/target/AIRHEROF3/target.h @@ -39,15 +39,15 @@ #define MPU6500_CS_PIN PB12 #define MPU6500_SPI_INSTANCE SPI2 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI2 diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h index 53a411a08b..98e47b0f77 100644 --- a/src/main/target/ALIENFLIGHTF1/target.h +++ b/src/main/target/ALIENFLIGHTF1/target.h @@ -32,12 +32,12 @@ #define USE_MPU_DATA_READY_SIGNAL //#define DEBUG_MPU_DATA_READY_INTERRUPT -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW0_DEG diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index c050bd03e4..3d01bee605 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -42,14 +42,14 @@ #define USE_MPU_DATA_READY_SIGNAL // Using MPU6050 for the moment. -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6050_ALIGN CW270_DEG #define GYRO_MPU6500_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define USE_ACC_SPI_MPU6500 @@ -57,11 +57,11 @@ #define ACC_MPU6500_ALIGN CW270_DEG // No baro support. -//#define BARO +//#define USE_BARO //#define USE_BARO_MS5611 // option to use MPU9150 or MPU9250 integrated AK89xx Mag -#define MAG +#define USE_MAG #define USE_MAG_AK8963 #define MAG_AK8963_ALIGN CW0_DEG_FLIP diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index f683ef61eb..57fde012c0 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -43,22 +43,22 @@ #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define USE_MAG_AK8963 #define MAG_HMC5883_ALIGN CW180_DEG #define MAG_AK8963_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP280 diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 79568a547c..d14d5231ac 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -41,15 +41,15 @@ #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define USE_MAG_SPI_HMC5883 #define USE_MAG_AK8963 @@ -64,7 +64,7 @@ #define MAG_HMC5883_ALIGN CW180_DEG #define MAG_AK8963_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_SPI_MS5611 #define USE_BARO_BMP280 diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h index 0777d9fab2..7088c7c4c7 100644 --- a/src/main/target/ALIENWHOOP/target.h +++ b/src/main/target/ALIENWHOOP/target.h @@ -105,7 +105,7 @@ #endif /* OSD MAX7456E */ -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 @@ -124,17 +124,17 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW // MAG -#define MAG +#define USE_MAG #define USE_MAG_AK8963 #define MAG_AK8963_ALIGN CW0_DEG #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH // GYRO -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW0_DEG // ACC -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG @@ -142,7 +142,7 @@ * TODO: not implemented on V1 or V2 pcb */ #if defined(BREADBOARD) -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI3 @@ -211,7 +211,7 @@ /* OLED Support */ #if defined(BREADBOARD) -#define CMS +#define USE_CMS #define USE_I2C #define USE_I2C_DEVICE_1 #define I2C_DEVICE (I2CDEV_1) diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index a7a6d49278..e4b41c7f48 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -30,11 +30,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG @@ -43,14 +43,14 @@ #define MPU_INT_EXTI PC4 #define USE_EXTI -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_I2C_INSTANCE (I2CDEV_2) //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP //#define MAG_HMC5883_ALIGN CW90_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP280 #define BARO_I2C_INSTANCE (I2CDEV_2) @@ -120,7 +120,7 @@ #define SPI4_MISO_PIN PE13 #define SPI4_MOSI_PIN PE14 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/ANYFCM7/target.h b/src/main/target/ANYFCM7/target.h index 0184a82bc7..80816074b0 100644 --- a/src/main/target/ANYFCM7/target.h +++ b/src/main/target/ANYFCM7/target.h @@ -32,11 +32,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG @@ -45,13 +45,13 @@ #define MPU_INT_EXTI PC4 #define USE_EXTI -#define MAG +#define USE_MAG //#define USE_MAG_HMC5883 //#define HMC5883_BUS I2C_DEVICE_EXT //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP //#define MAG_HMC5883_ALIGN CW90_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USABLE_TIMER_CHANNEL_COUNT 16 @@ -117,7 +117,7 @@ #define USE_FLASH_M25P16 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/BEEBRAIN_V2F/target.h b/src/main/target/BEEBRAIN_V2F/target.h index 71724ef58d..b3cbcd3623 100755 --- a/src/main/target/BEEBRAIN_V2F/target.h +++ b/src/main/target/BEEBRAIN_V2F/target.h @@ -31,11 +31,11 @@ #define MPU_INT_EXTI PB6 #define USE_MPU_DATA_READY_SIGNAL -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG @@ -76,7 +76,7 @@ #define MPU6500_CS_PIN PA15 #define MPU6500_SPI_INSTANCE SPI3 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 #define MAX7456_SPI_CS_PIN PA4 diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index de4656d396..5865c38929 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -35,18 +35,18 @@ #define ICM20689_CS_PIN SPI1_NSS_PIN #define ICM20689_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index bb8389396b..a45cc4c3dd 100644 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -30,11 +30,11 @@ #define MPU6000_CS_PIN PA15 #define MPU6000_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG @@ -87,7 +87,7 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define OSD +#define USE_OSD // include the max7456 driver #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h index 054246b87a..073365d1e9 100755 --- a/src/main/target/BETAFLIGHTF4/target.h +++ b/src/main/target/BETAFLIGHTF4/target.h @@ -33,11 +33,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG @@ -48,13 +48,13 @@ #define MPU_INT_EXTI PC4 #define USE_MPU_DATA_READY_SIGNAL -#define BARO +#define USE_BARO #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI2 #define BMP280_CS_PIN PB3 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PB12 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index e31e2c8734..c6f6b2c622 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -50,22 +50,22 @@ #define MPU6500_CS_PIN PC4 #define MPU6500_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW0_DEG -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 //#define USE_MAG_AK8963 #define HMC5883_I2C_INSTANCE I2CDEV_1 -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define MS5611_I2C_INSTANCE I2CDEV_1 diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 4fed0d38e3..d9aaf135ae 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -46,11 +46,11 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG @@ -61,13 +61,13 @@ //#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11 // External I2C BARO -//#define BARO +//#define USE_BARO //#define USE_BARO_MS5611 //#define USE_BARO_BMP085 //#define USE_BARO_BMP280 // External I2C MAG -//#define MAG +//#define USE_MAG //#define USE_MAG_HMC5883 #define USE_VCP @@ -97,7 +97,7 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -//#define SONAR +//#define USE_SONAR //#define SONAR_ECHO_PIN PB0 //#define SONAR_TRIGGER_PIN PB5 diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index a59e0df57b..dcac210ff2 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -63,7 +63,7 @@ //#define M25P16_CS_PIN GPIO_Pin_12 //#define M25P16_SPI_INSTANCE SPI2 -#define GYRO +#define USE_GYRO #define USE_GYRO_L3GD20 #define USE_GYRO_MPU6050 @@ -75,7 +75,7 @@ #define GYRO_L3GD20_ALIGN CW270_DEG #define GYRO_MPU6050_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define USE_ACC_LSM303DLHC #define LSM303DLHC_I2C I2C1 @@ -87,10 +87,10 @@ #define ACC_MPU6050_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define MAG_AK8975_ALIGN CW90_DEG_FLIP diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index a49c5f149b..c28b4396b7 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -27,13 +27,13 @@ #undef BEEPER -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 -//#define MAG +//#define USE_MAG //#define USE_MAG_HMC5883 #define BRUSHED_MOTORS diff --git a/src/main/target/CLRACINGF4/target.h b/src/main/target/CLRACINGF4/target.h index 2956a27761..b1a8cdaf39 100644 --- a/src/main/target/CLRACINGF4/target.h +++ b/src/main/target/CLRACINGF4/target.h @@ -40,9 +40,9 @@ // MPU 6000 #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW0_DEG #define ACC_MPU6000_ALIGN CW0_DEG @@ -59,7 +59,7 @@ #define MPU6500_SPI_INSTANCE SPI1 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 diff --git a/src/main/target/CLRACINGF7/target.h b/src/main/target/CLRACINGF7/target.h index a128ad04aa..ff196d889c 100644 --- a/src/main/target/CLRACINGF7/target.h +++ b/src/main/target/CLRACINGF7/target.h @@ -33,17 +33,17 @@ //ICM20689 #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW0_DEG //MPU-6000 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW0_DEG @@ -62,7 +62,7 @@ #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_INSTANCE SPI1 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 diff --git a/src/main/target/COLIBRI/target.h b/src/main/target/COLIBRI/target.h index 76790b6a56..53bb5047c7 100644 --- a/src/main/target/COLIBRI/target.h +++ b/src/main/target/COLIBRI/target.h @@ -36,11 +36,11 @@ #define MPU6000_CS_PIN PC4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG_FLIP -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG_FLIP @@ -49,7 +49,7 @@ #define MPU_INT_EXTI PC0 #define USE_MPU_DATA_READY_SIGNAL -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG_FLIP @@ -57,7 +57,7 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define M25P16_CS_PIN PB12 diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index 7ac9476aa0..b5b11710bf 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -374,7 +374,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest) bstWrite16(failsafeConfig()->failsafe_throttle); -#ifdef GPS +#ifdef USE_GPS bstWrite8(gpsConfig()->provider); // gps_type bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t bstWrite8(gpsConfig()->sbasMode); // gps_ubx_sbas @@ -501,7 +501,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand) failsafeConfigMutable()->failsafe_throttle = bstRead16(); -#ifdef GPS +#ifdef USE_GPS gpsConfigMutable()->provider = bstRead8(); // gps_type bstRead8(); // gps_baudrate gpsConfigMutable()->sbasMode = bstRead8(); // gps_ubx_sbas @@ -723,7 +723,7 @@ void taskBstMasterProcess(timeUs_t currentTimeUs) sendCounter = 0; next20hzUpdateAt_1 = currentTimeUs + UPDATE_AT_20HZ; } -#ifdef GPS +#ifdef USE_GPS if (sensors(SENSOR_GPS) && !bstWriteBusy()) writeGpsPositionPrameToBST(); #endif @@ -762,7 +762,7 @@ static void bstMasterWrite16(uint16_t data) /*************************************************************************************************/ #define PUBLIC_ADDRESS 0x00 -#ifdef GPS +#ifdef USE_GPS static void bstMasterWrite32(uint32_t data) { bstMasterWrite16((uint8_t)(data >> 16)); @@ -775,7 +775,7 @@ static uint16_t alt = 0; static uint8_t numOfSat = 0; #endif -#ifdef GPS +#ifdef USE_GPS bool writeGpsPositionPrameToBST(void) { if ((lat != gpsSol.llh.lat) || (lon != gpsSol.llh.lon) || (alt != gpsSol.llh.alt) || (numOfSat != gpsSol.numSat)) { diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 84ec4dadce..2c307343c7 100644 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -53,24 +53,24 @@ #define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define USE_MAG_AK8963 #define USE_MAG_AK8975 diff --git a/src/main/target/CRAZYFLIE2/target.h b/src/main/target/CRAZYFLIE2/target.h index 2a45adf722..6fac2460f5 100644 --- a/src/main/target/CRAZYFLIE2/target.h +++ b/src/main/target/CRAZYFLIE2/target.h @@ -83,15 +83,15 @@ // address is 0x69 instead of the default 0x68 #define MPU_ADDRESS 0x69 -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define MAG +#define USE_MAG #define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus #define USE_MAG_AK8963 #define MAG_AK8963_ALIGN CW270_DEG diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 16fb58f349..16fd7ff9a3 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -69,7 +69,7 @@ #define M25P16_CS_PIN PC15 #define M25P16_SPI_INSTANCE SPI2 -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG @@ -77,14 +77,14 @@ #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 diff --git a/src/main/target/EACHIF3/target.h b/src/main/target/EACHIF3/target.h index 6c33350e5d..043dff7b9d 100644 --- a/src/main/target/EACHIF3/target.h +++ b/src/main/target/EACHIF3/target.h @@ -39,11 +39,11 @@ #define MPU6500_CS_PIN PA5 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW90_DEG @@ -70,7 +70,7 @@ #define I2C2_SCL PA9 -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_MS5611 @@ -102,7 +102,7 @@ #undef BEEPER -#define BLACKBOX +#define USE_BLACKBOX #define LED_STRIP #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define BRUSHED_MOTORS diff --git a/src/main/target/ELLE0/target.h b/src/main/target/ELLE0/target.h index 9ba906cc4f..63d5bf8c99 100644 --- a/src/main/target/ELLE0/target.h +++ b/src/main/target/ELLE0/target.h @@ -37,18 +37,18 @@ #define MPU6500_SPI_INSTANCE SPI2 // Using MPU6050 for the moment. -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -//#define BARO +//#define USE_BARO //#define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_AK8963 #define MAG_AK8963_ALIGN CW0_DEG_FLIP diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index 26472bd845..0773156299 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -38,19 +38,19 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW90_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW90_DEG -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW90_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_SDCARD diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h index c23c4d010d..efcfbf0c89 100644 --- a/src/main/target/FF_FORTINIF4/target.h +++ b/src/main/target/FF_FORTINIF4/target.h @@ -53,7 +53,7 @@ #define ICM20689_CS_PIN PA8 #define ICM20689_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW180_DEG @@ -66,7 +66,7 @@ #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW180_DEG @@ -87,7 +87,7 @@ /*---------------------------------*/ /*-------------OSD-----------------*/ -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PB3 @@ -119,7 +119,7 @@ #define SERIAL_PORT_COUNT 5 //SPECKTRUM BIND -#define CMS +#define USE_CMS #define USE_MSP_DISPLAYPORT /*---------------------------------*/ diff --git a/src/main/target/FF_PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h index 491dac3c21..87efb95993 100644 --- a/src/main/target/FF_PIKOBLX/target.h +++ b/src/main/target/FF_PIKOBLX/target.h @@ -43,11 +43,11 @@ #define MPU_INT_EXTI PA15 #define USE_MPU_DATA_READY_SIGNAL -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG diff --git a/src/main/target/FF_PIKOF4/target.h b/src/main/target/FF_PIKOF4/target.h index 92815e0ccb..5628effcab 100644 --- a/src/main/target/FF_PIKOF4/target.h +++ b/src/main/target/FF_PIKOF4/target.h @@ -47,7 +47,7 @@ #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW180_DEG @@ -60,7 +60,7 @@ #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW180_DEG @@ -100,7 +100,7 @@ #define SERIAL_PORT_COUNT 4 -#define CMS +#define USE_CMS #define USE_MSP_DISPLAYPORT /*---------------------------------*/ diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h index e9d1985736..e8bca28d98 100644 --- a/src/main/target/FISHDRONEF4/target.h +++ b/src/main/target/FISHDRONEF4/target.h @@ -40,11 +40,11 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW90_DEG @@ -80,7 +80,7 @@ #define SPI2_MISO_PIN PC2 #define SPI2_MOSI_PIN PC3 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN SPI2_NSS_PIN diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h index 8951030623..71c4fadade 100644 --- a/src/main/target/FRSKYF3/target.h +++ b/src/main/target/FRSKYF3/target.h @@ -36,19 +36,19 @@ #ifdef MYMPU6000 #define MPU6000_SPI_INSTANCE SPI2 #define MPU6000_CS_PIN PB12 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG #else -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG #endif @@ -80,7 +80,7 @@ #define USE_ESCSERIAL #define ESCSERIAL_TIMER_TX_PIN PB9 // (HARDARE=0) #define USE_SPI -#define OSD +#define USE_OSD // include the max7456 driver #define USE_MAX7456 diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 5ccead6219..d5cd4e53f9 100644 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -28,10 +28,10 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG @@ -41,13 +41,13 @@ #define MPU_INT_EXTI PC4 #define USE_MPU_DATA_READY_SIGNAL -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI3 #define BMP280_CS_PIN PB3 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 97de72a8d0..45f26006be 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -47,7 +47,7 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW180_DEG @@ -58,7 +58,7 @@ #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW180_DEG @@ -79,7 +79,7 @@ #define SPI2_MOSI_PIN PB15 #ifdef FURYF3OSD - #define OSD + #define USE_OSD // include the max7456 driver #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 @@ -120,7 +120,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT - #define BARO + #define USE_BARO #define USE_BARO_MS5611 #endif @@ -143,7 +143,7 @@ #define SOFTSERIAL1_RX_PIN PB0 #define SOFTSERIAL1_TX_PIN PB1 -#define SONAR +#define USE_SONAR #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 58c518c46d..03b3a5d7b7 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -47,7 +47,7 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW180_DEG @@ -60,7 +60,7 @@ #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW180_DEG @@ -72,7 +72,7 @@ #define ACC_MPU6500_ALIGN CW180_DEG #ifdef FURYF4OSD - #define OSD + #define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PB12 @@ -85,7 +85,7 @@ #else - #define BARO + #define USE_BARO #define USE_BARO_MS5611 #define MS5611_I2C_INSTANCE I2CDEV_1 diff --git a/src/main/target/FURYF7/target.h b/src/main/target/FURYF7/target.h index 8e004ed770..c85e59181c 100644 --- a/src/main/target/FURYF7/target.h +++ b/src/main/target/FURYF7/target.h @@ -34,15 +34,15 @@ #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW180_DEG -//#define BARO +//#define USE_BARO //#define USE_BARO_MS5611 //#define MS5611_I2C_INSTANCE I2CDEV_1 diff --git a/src/main/target/IMPULSERCF3/target.h b/src/main/target/IMPULSERCF3/target.h index b8776979ca..9ccd09c17c 100644 --- a/src/main/target/IMPULSERCF3/target.h +++ b/src/main/target/IMPULSERCF3/target.h @@ -32,11 +32,11 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW0_DEG @@ -79,7 +79,7 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 #define MAX7456_SPI_CS_PIN PA3 diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 0112c6477e..e39b868b88 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -28,15 +28,15 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP085 #define USE_FLASHFS diff --git a/src/main/target/ISHAPEDF3/target.h b/src/main/target/ISHAPEDF3/target.h index 10549e06aa..009fd3586e 100644 --- a/src/main/target/ISHAPEDF3/target.h +++ b/src/main/target/ISHAPEDF3/target.h @@ -35,21 +35,21 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 //#define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 //#define USE_ACC_SPI_MPU6500 -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_FLASHFS #define USE_FLASH_M25P16 -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index 67c4a42dd1..afdd6f80de 100644 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -44,11 +44,11 @@ #define ICM20689_CS_PIN PC4 #define ICM20689_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW270_DEG @@ -65,12 +65,12 @@ #define USE_MAG_HMC5883 //External, connect to I2C1 #define MAG_HMC5883_ALIGN CW180_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 //External, connect to I2C1 #define USE_BARO_BMP280 //onboard #endif -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PB14 diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 8913109244..992f4c1589 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -25,8 +25,8 @@ #define BEEPER PD15 #define BEEPER_INVERTED -#define ACC -#define GYRO +#define USE_ACC +#define USE_GYRO #define USE_DUAL_GYRO // ICM-20689 @@ -118,7 +118,7 @@ #define SPI4_MOSI_PIN PE6 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN SPI2_NSS_PIN @@ -150,11 +150,11 @@ #define I2C1_SCL PB6 #define I2C1_SDA PB7 -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define BARO_I2C_INSTANCE I2C_DEVICE -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_I2C_INSTANCE I2C_DEVICE diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 8c7512be95..cdf21eb807 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -41,20 +41,20 @@ #ifdef KISSCC #define TARGET_CONFIG -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW90_DEG #undef LED_STRIP #else -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW180_DEG #endif diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index 4f527d3652..5785f4c13b 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -51,7 +51,7 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG @@ -62,7 +62,7 @@ #define ACC_MPU6000_ALIGN CW180_DEG #if defined(KIWIF4) || defined(KIWIF4V2) -#define OSD +#define USE_OSD #define USE_MAX7456 #endif @@ -189,5 +189,5 @@ #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) -#define CMS +#define USE_CMS #define USE_MSP_DISPLAYPORT diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h index 996247657d..7c28cbdd59 100755 --- a/src/main/target/KROOZX/target.h +++ b/src/main/target/KROOZX/target.h @@ -43,20 +43,20 @@ #define USE_MPU_DATA_READY_SIGNAL #define MPU_INT_EXTI PA4 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW180_DEG #define MAG_I2C_INSTANCE I2CDEV_1 -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_SDCARD @@ -72,7 +72,7 @@ #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CHANNEL DMA_Channel_0 -#define OSD +#define USE_OSD #ifdef USE_MSP_DISPLAYPORT #undef USE_MSP_DISPLAYPORT #endif diff --git a/src/main/target/LUMBAF3/target.h b/src/main/target/LUMBAF3/target.h index 8cfd7a5e8e..d8da3b6d3f 100644 --- a/src/main/target/LUMBAF3/target.h +++ b/src/main/target/LUMBAF3/target.h @@ -41,11 +41,11 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW90_DEG diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index decba5c1dd..0f05d166f4 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -90,7 +90,7 @@ #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #ifdef LUXV2_RACE #define USE_GYRO_MPU6000 #define USE_GYRO_SPI_MPU6000 @@ -101,7 +101,7 @@ #define GYRO_MPU6500_ALIGN CW270_DEG #endif -#define ACC +#define USE_ACC #ifdef LUXV2_RACE #define USE_ACC_MPU6000 #define USE_ACC_SPI_MPU6000 diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index 9651ef7ed0..e8ca228945 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -43,11 +43,11 @@ #define MPU_INT_EXTI PC3 #define USE_MPU_DATA_READY_SIGNAL -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG @@ -69,7 +69,7 @@ #define BARO_I2C_INSTANCE (I2CDEV_1) #endif -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 @@ -102,7 +102,7 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PB10 diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 61cb93fe26..ce0668a130 100644 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -42,11 +42,11 @@ #define MPU_INT_EXTI PC3 #define USE_MPU_DATA_READY_SIGNAL -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW90_DEG @@ -81,7 +81,7 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PB10 diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h index ab0db600f1..47e967dad4 100644 --- a/src/main/target/MICROSCISKY/target.h +++ b/src/main/target/MICROSCISKY/target.h @@ -45,20 +45,20 @@ #define USE_SPI #define USE_SPI_DEVICE_2 -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP085 #define USE_BARO_BMP280 -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW180_DEG diff --git a/src/main/target/MIDELICF3/target.h b/src/main/target/MIDELICF3/target.h index c372c7b01a..99a69a231d 100644 --- a/src/main/target/MIDELICF3/target.h +++ b/src/main/target/MIDELICF3/target.h @@ -23,11 +23,11 @@ #define BEEPER PC14 -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 68f4249093..4f0ab550cc 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -34,8 +34,8 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO -#define ACC +#define USE_GYRO +#define USE_ACC #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW180_DEG diff --git a/src/main/target/MOTOLABF4/target.h b/src/main/target/MOTOLABF4/target.h index 7a31c739ae..dbe45e0302 100644 --- a/src/main/target/MOTOLABF4/target.h +++ b/src/main/target/MOTOLABF4/target.h @@ -39,11 +39,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG @@ -59,7 +59,7 @@ #define SPI3_SCK_PIN PC10 #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN SPI3_NSS_PIN diff --git a/src/main/target/MULTIFLITEPICO/target.h b/src/main/target/MULTIFLITEPICO/target.h index f7d4feb663..8fa4fdca8e 100644 --- a/src/main/target/MULTIFLITEPICO/target.h +++ b/src/main/target/MULTIFLITEPICO/target.h @@ -32,20 +32,20 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW90_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP085 #define USE_BARO_BMP280 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG @@ -57,7 +57,7 @@ //#define USE_FLASHFS //#define USE_FLASH_M25P16 -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 28f2d9c452..e74d856598 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -76,7 +76,7 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050 #define USE_GYRO_MPU6500 @@ -86,7 +86,7 @@ #define GYRO_MPU6050_ALIGN CW0_DEG #define GYRO_MPU6500_ALIGN CW0_DEG -#define ACC +#define USE_ACC #define USE_ACC_ADXL345 #define USE_ACC_BMA280 #define USE_ACC_MMA8452 @@ -100,17 +100,17 @@ #define ACC_BMA280_ALIGN CW0_DEG #define ACC_MPU6500_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 // needed for Flip32 board #define USE_BARO_BMP280 /* -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW180_DEG */ -//#define SONAR +//#define USE_SONAR //#define SONAR_TRIGGER_PIN PB0 //#define SONAR_ECHO_PIN PB1 //#define SONAR_TRIGGER_PIN_PWM PB8 diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h index 5de8a0b381..3fa33e37b7 100644 --- a/src/main/target/NERO/target.h +++ b/src/main/target/NERO/target.h @@ -40,12 +40,12 @@ #define MPU6500_CS_PIN PC4 #define MPU6500_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW0_DEG diff --git a/src/main/target/NUCLEOF7/target.h b/src/main/target/NUCLEOF7/target.h index 0fff1d2d87..b2e2b03446 100644 --- a/src/main/target/NUCLEOF7/target.h +++ b/src/main/target/NUCLEOF7/target.h @@ -27,12 +27,12 @@ #define BEEPER PA0 #define BEEPER_INVERTED -#define ACC +#define USE_ACC #define USE_FAKE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_FAKE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG @@ -42,12 +42,12 @@ #define MPU_INT_EXTI PB15 #define USE_EXTI -#define MAG +#define USE_MAG #define USE_FAKE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG_FLIP -#define BARO +#define USE_BARO #define USE_FAKE_BARO #define USE_BARO_MS5611 diff --git a/src/main/target/NUCLEOF722/target.h b/src/main/target/NUCLEOF722/target.h index 4e5667d811..7df9050c64 100644 --- a/src/main/target/NUCLEOF722/target.h +++ b/src/main/target/NUCLEOF722/target.h @@ -29,12 +29,12 @@ #define BEEPER PA0 #define BEEPER_INVERTED -#define ACC +#define USE_ACC #define USE_FAKE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_FAKE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG @@ -44,12 +44,12 @@ #define MPU_INT_EXTI PB15 #define USE_EXTI -#define MAG +#define USE_MAG #define USE_FAKE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG_FLIP -#define BARO +#define USE_BARO #define USE_FAKE_BARO #define USE_BARO_MS5611 diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 0f27d2d836..9e6ef8fe7f 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -39,22 +39,22 @@ #define MPU6000_SPI_INSTANCE SPI1 #define MPU6000_CS_PIN PA4 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW90_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW90_DEG #define BMP280_SPI_INSTANCE SPI1 #define BMP280_CS_PIN PA13 -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 -//#define SONAR +//#define USE_SONAR //#define SONAR_ECHO_PIN PB1 //#define SONAR_TRIGGER_PIN PB0 @@ -98,7 +98,7 @@ // OSD define info: // feature name (includes source) -> MAX_OSD, used in target.mk // include the osd code -#define OSD +#define USE_OSD // include the max7456 driver #define USE_MAX7456 diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index acb251b517..a5420c00a6 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -58,10 +58,10 @@ #define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO XXX this is not used --- remove it at the next major release #endif -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define MPU6000_CS_PIN PA4 @@ -95,14 +95,14 @@ #define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN #endif -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW90_DEG //#define USE_MAG_NAZA // Delete this on next major release //#define MAG_NAZA_ALIGN CW180_DEG_FLIP // Ditto -#define BARO +#define USE_BARO #if defined(OMNIBUSF4SD) #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI3 @@ -119,7 +119,7 @@ #define DEFAULT_BARO_BMP280 #endif -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 @@ -226,7 +226,7 @@ #define TRANSPONDER -#define SONAR +#define USE_SONAR #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index c09cce08e4..b0ef14c996 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -30,8 +30,8 @@ #define BEEPER PD15 #define BEEPER_INVERTED -#define ACC -#define GYRO +#define USE_ACC +#define USE_GYRO #define USE_DUAL_GYRO // ICM-20608-G @@ -136,7 +136,7 @@ #define SPI4_MOSI_PIN PE6 -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN SPI2_NSS_PIN @@ -168,13 +168,13 @@ #define I2C2_SCL NONE // PB10 (UART3_TX) #define I2C2_SDA NONE // PB11 (UART3_RX) -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI1 #define BMP280_CS_PIN PA1 -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define SENSORS_SET (SENSOR_ACC | SENSOR_BARO) diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h index a8e8bbd78d..484069f8f7 100644 --- a/src/main/target/RACEBASE/target.h +++ b/src/main/target/RACEBASE/target.h @@ -39,10 +39,10 @@ #define MPU6000_CS_PIN PB5 #define MPU6000_SPI_INSTANCE SPI2 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW90_DEG @@ -99,7 +99,7 @@ #define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PA6 -#define OSD +#define USE_OSD #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h index 01659299ba..ca1deff29d 100644 --- a/src/main/target/RCEXPLORERF3/target.h +++ b/src/main/target/RCEXPLORERF3/target.h @@ -31,28 +31,28 @@ #define USE_MPU_DATA_READY_SIGNAL #define MPU_INT_EXTI PA15 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define USE_ACC_SPI_MPU6000 #define MPU6000_CS_PIN PB12 #define MPU6000_SPI_INSTANCE SPI2 -#define ACC +#define USE_ACC #define ACC_MPU6000_ALIGN CW180_DEG #define GYRO_MPU6000_ALIGN CW180_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 // External #define MAG_AK8975_ALIGN CW180_DEG -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PA6 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) #define SONAR_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index df4f35e94b..28ab4c0a5d 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -82,8 +82,8 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define GYRO -#define ACC +#define USE_GYRO +#define USE_ACC #ifdef AIRBOTF4SD #undef MPU6000_CS_PIN @@ -137,11 +137,11 @@ #define USE_MPU_DATA_READY_SIGNAL // Configure MAG and BARO unconditionally. -#define MAG +#define USE_MAG #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW90_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP085 #define USE_BARO_BMP280 diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index ca8711f432..16c23de062 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -31,17 +31,17 @@ #define MPU6500_CS_PIN PB12 #define MPU6500_SPI_INSTANCE SPI2 -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 // MPU6500 interrupts diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index ee3cc772b3..749b78807d 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -43,11 +43,11 @@ #define SPI2_MOSI_PIN PB15 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 2f77e9031e..1e0da97daf 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -29,11 +29,11 @@ #define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW0_DEG_FLIP -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW0_DEG_FLIP diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index dfa05e6a14..1e804a25cd 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -28,12 +28,12 @@ #define MPU_INT_EXTI PA8 #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 @@ -143,7 +143,7 @@ //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define OSD +#define USE_OSD #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index e5ccbc57e0..39dcf479ee 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -49,16 +49,16 @@ #define USE_FAKE_LED -#define ACC +#define USE_ACC #define USE_FAKE_ACC -#define GYRO +#define USE_GYRO #define USE_FAKE_GYRO -#define MAG +#define USE_MAG #define USE_FAKE_MAG -#define BARO +#define USE_BARO #define USE_FAKE_BARO #define USABLE_TIMER_CHANNEL_COUNT 0 @@ -103,7 +103,7 @@ #undef TELEMETRY_SMARTPORT #undef TELEMETRY_MAVLINK #undef USE_RESOURCE_MGMT -#undef CMS +#undef USE_CMS #undef TELEMETRY_CRSF #undef TELEMETRY_IBUS #undef TELEMETRY_JETIEXBUS diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 4de37b1d76..38b9502491 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -33,19 +33,19 @@ #define USE_MPU_DATA_READY_SIGNAL // MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component. -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6050 #define ACC_MPU6050_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define USE_BARO_BMP280 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define MAG_AK8975_ALIGN CW180_DEG_FLIP @@ -90,7 +90,7 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -//#define SONAR +//#define USE_SONAR //#define SONAR_ECHO_PIN PB1 //#define SONAR_TRIGGER_PIN PA2 diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h index 854333d684..13520a2334 100644 --- a/src/main/target/SPARKY2/target.h +++ b/src/main/target/SPARKY2/target.h @@ -44,22 +44,22 @@ #define MPU9250_CS_PIN PC4 #define MPU9250_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU9250 #define ACC_MPU9250_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU9250 #define GYRO_MPU9250_ALIGN CW270_DEG -#define MAG +#define USE_MAG //#define USE_MAG_HMC5883 #define USE_MAG_AK8963 //#define MAG_HMC5883_ALIGN CW180_DEG #define MAG_AK8963_ALIGN CW270_DEG -#define BARO +#define USE_BARO #define USE_BARO_MS5611 //#define USE_BARO_BMP280 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index bf7030432d..40dc21da33 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -45,11 +45,11 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO +#define USE_GYRO -#define ACC +#define USE_ACC -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #if defined(FLIP32F3OSD) @@ -60,12 +60,12 @@ #define ACC_MPU6500_ALIGN CW270_DEG #elif defined(ZCOREF3) -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW180_DEG -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG @@ -89,7 +89,7 @@ #endif #if defined(FLIP32F3OSD) -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 @@ -102,14 +102,14 @@ #else //SPRACINGF3 -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 #define USE_BARO_MS5611 #define USE_BARO_BMP085 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG @@ -170,7 +170,7 @@ #define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PB2 -#define OSD +#define USE_OSD #define USE_OSD_OVER_MSP_DISPLAYPORT #define USE_SLOW_MSP_DISPLAYPORT_RATE_WHEN_UNARMED diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 0832f1b996..7afc98c442 100644 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -64,25 +64,25 @@ #define USE_ESC_SENSOR -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG #define GYRO_MPU6500_ALIGN CW180_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 -#define MAG +#define USE_MAG #define USE_MAG_AK8963 //#define USE_MAG_HMC5883 // External #define MAG_AK8963_ALIGN CW90_DEG_FLIP -//#define SONAR +//#define USE_SONAR #define USE_VCP #define USE_UART1 @@ -163,7 +163,7 @@ #define CURRENT_METER_ADC_PIN PA5 #endif -#define OSD +#define USE_OSD #define DISABLE_EXTENDED_CMS_OSD_MENU #define USE_OSD_OVER_MSP_DISPLAYPORT #define USE_MSP_CURRENT_METER diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 71474d0c97..563fa58e19 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -43,8 +43,8 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define GYRO -#define ACC +#define USE_GYRO +#define USE_ACC #ifdef TINYBEEF3 @@ -64,17 +64,17 @@ #define USE_ACC_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 -#define MAG +#define USE_MAG #define USE_MPU9250_MAG // Enables bypass configuration #define USE_MAG_AK8975 #define USE_MAG_HMC5883 // External #define MAG_AK8975_ALIGN CW90_DEG_FLIP #endif -//#define SONAR +//#define USE_SONAR //#define SONAR_ECHO_PIN PB1 //#define SONAR_TRIGGER_PIN PB0 diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h index 7f0f9a3887..ce29e12587 100644 --- a/src/main/target/SPRACINGF3NEO/target.h +++ b/src/main/target/SPRACINGF3NEO/target.h @@ -36,10 +36,10 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG @@ -159,7 +159,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define OSD +#define USE_OSD #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP) diff --git a/src/main/target/SPRACINGF3OSD/target.h b/src/main/target/SPRACINGF3OSD/target.h index c532c98cf2..a7b5831edf 100644 --- a/src/main/target/SPRACINGF3OSD/target.h +++ b/src/main/target/SPRACINGF3OSD/target.h @@ -27,10 +27,10 @@ #define USE_EXTI -#define GYRO +#define USE_GYRO #define USE_FAKE_GYRO -#define ACC +#define USE_ACC #define USE_FAKE_ACC #define REMAP_TIM16_DMA diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index cf944f207f..3f2cd856f0 100644 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -42,20 +42,20 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG #define GYRO_MPU6500_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 @@ -159,7 +159,7 @@ #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define OSD +#define USE_OSD #define USE_OSD_OVER_MSP_DISPLAYPORT #define USE_MSP_CURRENT_METER diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h index b16a7ad680..bef03d20d1 100644 --- a/src/main/target/SPRACINGF4NEO/target.h +++ b/src/main/target/SPRACINGF4NEO/target.h @@ -57,20 +57,20 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW0_DEG #define GYRO_MPU6500_ALIGN CW0_DEG -#define BARO +#define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_MS5611 -#define MAG +#define USE_MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 @@ -145,7 +145,7 @@ #define USE_RTC6705_CLK_HACK #define RTC6705_CLK_PIN SPI3_SCK_PIN -#define OSD +#define USE_OSD // Bus Switched Device, Device A. #define USE_MAX7456 diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 3ac5773145..cdd6f25b23 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -75,7 +75,7 @@ // PB13 SPI2_SCK // PB12 SPI2_NSS -#define GYRO +#define USE_GYRO #define USE_FAKE_GYRO #define USE_GYRO_L3GD20 #define L3GD20_SPI SPI1 @@ -107,7 +107,7 @@ #define USE_EXTI #endif -#define ACC +#define USE_ACC #define USE_FAKE_ACC #define USE_ACC_ADXL345 #define USE_ACC_BMA280 @@ -122,18 +122,18 @@ #define USE_ACC_SPI_MPU9250 #define ACC_MPU6500_ALIGN CW270_DEG_FLIP -#define BARO +#define USE_BARO #define USE_FAKE_BARO #define USE_BARO_BMP085 #define USE_BARO_BMP280 #define USE_BARO_MS5611 -//#define OSD +//#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN SPI2_NSS_PIN -//#define CMS +//#define USE_CMS //#define USE_SDCARD // @@ -151,7 +151,7 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define MAG +#define USE_MAG #define USE_FAKE_MAG #define USE_MAG_AK8963 #define USE_MAG_AK8975 @@ -195,7 +195,7 @@ #define USE_ESC_SENSOR -#define SONAR +#define USE_SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 diff --git a/src/main/target/TINYFISH/target.h b/src/main/target/TINYFISH/target.h index dd2706bffa..6fe5e184c2 100644 --- a/src/main/target/TINYFISH/target.h +++ b/src/main/target/TINYFISH/target.h @@ -36,11 +36,11 @@ #define MPU6000_SPI_INSTANCE SPI1 #define MPU6000_CS_PIN PA4 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW180_DEG_FLIP -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG_FLIP diff --git a/src/main/target/VRRACE/target.h b/src/main/target/VRRACE/target.h index eb7d84753b..1cdaf67874 100644 --- a/src/main/target/VRRACE/target.h +++ b/src/main/target/VRRACE/target.h @@ -31,11 +31,11 @@ #define MPU6500_CS_PIN PE10 #define MPU6500_SPI_INSTANCE SPI2 -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW270_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW270_DEG @@ -45,7 +45,7 @@ #define USE_MPU_DATA_READY_SIGNAL /* -#define BARO +#define USE_BARO #define USE_BARO_MS5611 #define MS5611_I2C_INSTANCE I2CDEV_1 diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index b4d17f43f5..7200c3d6ce 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -33,11 +33,11 @@ #define MPU6000_SPI_INSTANCE SPI1 -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG -#define ACC +#define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW270_DEG diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index 0d91ddf32c..f76cde3d2a 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -43,11 +43,11 @@ #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW90_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW90_DEG @@ -55,12 +55,12 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW90_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 #define GYRO_MPU6500_ALIGN CW90_DEG @@ -128,7 +128,7 @@ #define SPI3_MOSI_PIN PC12 // OSD -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 #define MAX7456_SPI_CS_PIN PA14 diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index 2e5ce83f04..0f05401fd1 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -40,11 +40,11 @@ #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_INSTANCE SPI1 -#define ACC +#define USE_ACC #define USE_ACC_SPI_ICM20689 #define ACC_ICM20689_ALIGN CW90_DEG -#define GYRO +#define USE_GYRO #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW90_DEG @@ -87,7 +87,7 @@ #define SPI3_MOSI_PIN PC12 // OSD -#define OSD +#define USE_OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 #define MAX7456_SPI_CS_PIN PA14 diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h index c801d79205..8a9ff70ed8 100644 --- a/src/main/target/common_fc_pre.h +++ b/src/main/target/common_fc_pre.h @@ -95,7 +95,7 @@ #endif #if (FLASH_SIZE > 64) -#define BLACKBOX +#define USE_BLACKBOX #define LED_STRIP #define TELEMETRY #define TELEMETRY_FRSKY @@ -107,7 +107,7 @@ #endif #if (FLASH_SIZE > 128) -#define CMS +#define USE_CMS #define TELEMETRY_CRSF #define TELEMETRY_IBUS #define TELEMETRY_JETIEXBUS @@ -141,7 +141,7 @@ #if (FLASH_SIZE > 256) // Temporarily moved GPS here because of overflowing flash size on F3 -#define GPS +#define USE_GPS #define USE_NAV #define USE_UNCOMMON_MIXERS #endif diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 7ca8263564..23abe9ad98 100644 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -370,7 +370,7 @@ static void processCrsf(void) crsfFrameFlightMode(dst); crsfFinalize(dst); } -#ifdef GPS +#ifdef USE_GPS if (currentSchedule & BV(CRSF_FRAME_GPS_INDEX)) { crsfInitializeFrame(dst); crsfFrameGps(dst); @@ -476,7 +476,7 @@ int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType) case CRSF_FRAMETYPE_FLIGHT_MODE: crsfFrameFlightMode(sbuf); break; -#if defined(GPS) +#if defined(USE_GPS) case CRSF_FRAMETYPE_GPS: crsfFrameGps(sbuf); break; diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 3f177009df..daa4945a66 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -197,7 +197,7 @@ static void sendTemperature1(void) #if defined(USE_ESC_SENSOR) escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED); serialize16(escData->dataAge < ESC_DATA_INVALID ? escData->temperature : 0); -#elif defined(BARO) +#elif defined(USE_BARO) serialize16((baro.baroTemperature + 50)/ 100); // Airmamaf #else serialize16(gyroGetTemperature() / 10); @@ -216,7 +216,7 @@ static void sendTime(void) serialize16(seconds % 60); } -#if defined(GPS) || defined(MAG) +#if defined(USE_GPS) || defined(USE_MAG) // Frsky pdf: dddmm.mmmm // .mmmm is returned in decimal fraction of minutes. static void GPStoDDDMM_MMMM(int32_t mwiigps, gpsCoordinateDDDMMmmmm_t *result) @@ -257,7 +257,7 @@ static void sendLatLong(int32_t coord[2]) serialize16(coord[LON] < 0 ? 'W' : 'E'); } -#if defined(GPS) +#if defined(USE_GPS) static void sendGpsAltitude(void) { uint16_t altitude = gpsSol.llh.alt; @@ -334,7 +334,7 @@ static void sendGPSLatLong(void) #endif #endif -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) /* * Send vertical speed for opentx. ID_VERT_SPEED * Unit is cm/s @@ -429,7 +429,7 @@ static void sendFuelLevel(void) } } -#if defined(MAG) +#if defined(USE_MAG) static void sendFakeLatLongThatAllowsHeadingDisplay(void) { // Heading is only displayed on OpenTX if non-zero lat/long is also sent @@ -545,7 +545,7 @@ void handleFrSkyTelemetry(timeUs_t currentTimeUs) sendAccel(); } -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) if (sensors(SENSOR_BARO | SENSOR_SONAR)) { // Sent every 125ms sendVario(); @@ -568,7 +568,7 @@ void handleFrSkyTelemetry(timeUs_t currentTimeUs) } #endif -#if defined(MAG) +#if defined(USE_MAG) if (sensors(SENSOR_MAG)) { // Sent every 500ms if ((cycleNum % 4) == 0) { @@ -592,7 +592,7 @@ void handleFrSkyTelemetry(timeUs_t currentTimeUs) } } -#if defined(GPS) +#if defined(USE_GPS) if (sensors(SENSOR_GPS)) { sendSpeed(); sendGpsAltitude(); @@ -600,7 +600,7 @@ void handleFrSkyTelemetry(timeUs_t currentTimeUs) sendGPSLatLong(); } else #endif -#if defined(MAG) +#if defined(USE_MAG) if (sensors(SENSOR_MAG)) { sendFakeLatLongThatAllowsHeadingDisplay(); } diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 89882cbe31..554f8bbedf 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -125,7 +125,7 @@ static void initialiseEAMMessage(HOTT_EAM_MSG_t *msg, size_t size) msg->stop_byte = 0x7D; } -#ifdef GPS +#ifdef USE_GPS typedef enum { GPS_FIX_CHAR_NONE = '-', GPS_FIX_CHAR_2D = '2', @@ -146,12 +146,12 @@ static void initialiseGPSMessage(HOTT_GPS_MSG_t *msg, size_t size) static void initialiseMessages(void) { initialiseEAMMessage(&hottEAMMessage, sizeof(hottEAMMessage)); -#ifdef GPS +#ifdef USE_GPS initialiseGPSMessage(&hottGPSMessage, sizeof(hottGPSMessage)); #endif } -#ifdef GPS +#ifdef USE_GPS void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude) { int16_t deg = latitude / GPS_DEGREES_DIVIDER; @@ -408,7 +408,7 @@ static inline void hottSendEAMResponse(void) static void hottPrepareMessages(void) { hottPrepareEAMResponse(&hottEAMMessage); -#ifdef GPS +#ifdef USE_GPS hottPrepareGPSResponse(&hottGPSMessage); #endif } @@ -423,7 +423,7 @@ static void processBinaryModeRequest(uint8_t address) #endif switch (address) { -#ifdef GPS +#ifdef USE_GPS case 0x8A: #ifdef HOTT_DEBUG hottGPSRequests++; @@ -444,7 +444,7 @@ static void processBinaryModeRequest(uint8_t address) #ifdef HOTT_DEBUG hottBinaryRequests++; debug[0] = hottBinaryRequests; -#ifdef GPS +#ifdef USE_GPS debug[1] = hottGPSRequests; #endif debug[2] = hottEAMRequests; diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 4292d386f9..f8502b341a 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -124,7 +124,7 @@ static void ltm_finalise(void) */ static void ltm_gframe(void) { -#if defined(GPS) +#if defined(USE_GPS) uint8_t gps_fix_type = 0; int32_t ltm_alt; @@ -143,7 +143,7 @@ static void ltm_gframe(void) ltm_serialise_32(gpsSol.llh.lon); ltm_serialise_8((uint8_t)(gpsSol.groundSpeed / 100)); -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) ltm_alt = (sensors(SENSOR_SONAR) || sensors(SENSOR_BARO)) ? getEstimatedAltitude() : gpsSol.llh.alt * 100; #else ltm_alt = gpsSol.llh.alt * 100; @@ -219,7 +219,7 @@ static void ltm_aframe(void) static void ltm_oframe(void) { ltm_initialise_packet('O'); -#if defined(GPS) +#if defined(USE_GPS) ltm_serialise_32(GPS_home[LAT]); ltm_serialise_32(GPS_home[LON]); #else diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index b84085477a..0626ced8b1 100755 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -273,7 +273,7 @@ void mavlinkSendRCChannelsAndRSSI(void) mavlinkSerialWrite(mavBuffer, msgLength); } -#if defined(GPS) +#if defined(USE_GPS) void mavlinkSendPosition(void) { uint16_t msgLength; @@ -329,7 +329,7 @@ void mavlinkSendPosition(void) // alt Altitude in 1E3 meters (millimeters) above MSL gpsSol.llh.alt * 1000, // relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) (sensors(SENSOR_SONAR) || sensors(SENSOR_BARO)) ? getEstimatedAltitude() * 10 : gpsSol.llh.alt * 1000, #else gpsSol.llh.alt * 1000, @@ -388,7 +388,7 @@ void mavlinkSendHUDAndHeartbeat(void) float mavAirSpeed = 0; float mavClimbRate = 0; -#if defined(GPS) +#if defined(USE_GPS) // use ground speed if source available if (sensors(SENSOR_GPS)) { mavGroundSpeed = gpsSol.groundSpeed / 100.0f; @@ -396,18 +396,18 @@ void mavlinkSendHUDAndHeartbeat(void) #endif // select best source for altitude -#if defined(BARO) || defined(SONAR) +#if defined(USE_BARO) || defined(USE_SONAR) if (sensors(SENSOR_SONAR) || sensors(SENSOR_BARO)) { // Baro or sonar generally is a better estimate of altitude than GPS MSL altitude mavAltitude = getEstimatedAltitude() / 100.0; } -#if defined(GPS) +#if defined(USE_GPS) else if (sensors(SENSOR_GPS)) { // No sonar or baro, just display altitude above MLS mavAltitude = gpsSol.llh.alt; } #endif -#elif defined(GPS) +#elif defined(USE_GPS) if (sensors(SENSOR_GPS)) { // No sonar or baro, just display altitude above MLS mavAltitude = gpsSol.llh.alt; @@ -524,7 +524,7 @@ void processMAVLinkTelemetry(void) mavlinkSendRCChannelsAndRSSI(); } -#ifdef GPS +#ifdef USE_GPS if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION)) { mavlinkSendPosition(); } diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 06a38553ba..0ba66be849 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -395,7 +395,7 @@ void handleSmartPortTelemetry(void) static uint8_t t2Cnt = 0; switch (id) { -#ifdef GPS +#ifdef USE_GPS case FSSP_DATAID_SPEED : if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) { //convert to knots: 1cm/s = 0.0194384449 knots @@ -439,7 +439,7 @@ void handleSmartPortTelemetry(void) break; //case FSSP_DATAID_ADC1 : //case FSSP_DATAID_ADC2 : -#ifdef GPS +#ifdef USE_GPS case FSSP_DATAID_LATLONG : if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) { uint32_t tmpui = 0; @@ -532,7 +532,7 @@ void handleSmartPortTelemetry(void) break; case FSSP_DATAID_T2 : if (sensors(SENSOR_GPS)) { -#ifdef GPS +#ifdef USE_GPS // provide GPS lock status smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + gpsSol.numSat); smartPortHasRequest = 0; @@ -572,7 +572,7 @@ void handleSmartPortTelemetry(void) smartPortHasRequest = 0; } break; -#ifdef GPS +#ifdef USE_GPS case FSSP_DATAID_GPS_ALT : if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) { smartPortSendPackage(id, gpsSol.llh.alt * 100); // given in 0.1m , requested in 10 = 1m (should be in mm, probably a bug in opentx, tested on 2.0.1.7) diff --git a/src/test/Makefile b/src/test/Makefile index 7af3a10c72..4ce72191d2 100644 --- a/src/test/Makefile +++ b/src/test/Makefile @@ -51,7 +51,6 @@ baro_bmp280_unittest_SRC := \ $(USER_DIR)/drivers/barometer/barometer_bmp280.c baro_bmp280_unittest_DEFINES := \ - USE_BARO \ USE_BARO_BMP280 \ USE_BARO_SPI_BMP280 @@ -59,7 +58,6 @@ baro_ms5611_unittest_SRC := \ $(USER_DIR)/drivers/barometer/barometer_ms5611.c baro_ms5611_unittest_DEFINES := \ - USE_BARO \ USE_BARO_MS5611 \ USE_BARO_SPI_MS5611 @@ -91,9 +89,9 @@ cli_unittest_SRC := \ $(USER_DIR)/common/typeconversion.c cli_unittest_DEFINES := \ + USE_OSD \ USE_CLI \ - SystemCoreClock=1000000 \ - OSD + SystemCoreClock=1000000 cms_unittest_SRC := \ $(USER_DIR)/cms/cms.c \ @@ -160,7 +158,7 @@ osd_unittest_SRC := \ $(USER_DIR)/fc/runtime_config.c osd_unittest_DEFINES := \ - OSD + USE_OSD parameter_groups_unittest_SRC := \ diff --git a/src/test/unit/altitude_hold_unittest.cc.txt b/src/test/unit/altitude_hold_unittest.cc.txt index 863b6b9cdd..089d5c7a78 100644 --- a/src/test/unit/altitude_hold_unittest.cc.txt +++ b/src/test/unit/altitude_hold_unittest.cc.txt @@ -22,7 +22,7 @@ //#define DEBUG_ALTITUDE_HOLD -#define BARO +#define USE_BARO extern "C" { #include "debug.h" diff --git a/src/test/unit/cms_unittest.cc b/src/test/unit/cms_unittest.cc index c133cde63c..470aab8949 100644 --- a/src/test/unit/cms_unittest.cc +++ b/src/test/unit/cms_unittest.cc @@ -23,7 +23,7 @@ #include -#define BARO +#define USE_BARO extern "C" { #include "platform.h" diff --git a/src/test/unit/maths_unittest.cc b/src/test/unit/maths_unittest.cc index e7a0efe121..b7d6cda4d0 100644 --- a/src/test/unit/maths_unittest.cc +++ b/src/test/unit/maths_unittest.cc @@ -22,7 +22,7 @@ #include -#define BARO +#define USE_BARO extern "C" { #include "common/maths.h" diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h index 29aa361bad..3fabf8a1d9 100644 --- a/src/test/unit/platform.h +++ b/src/test/unit/platform.h @@ -26,9 +26,9 @@ #define U_ID_2 2 #define MAX_PROFILE_COUNT 3 -#define MAG -#define BARO -#define GPS +#define USE_MAG +#define USE_BARO +#define USE_GPS #define USE_DASHBOARD #define TELEMETRY #define LED_STRIP diff --git a/src/test/unit/target.h b/src/test/unit/target.h index b9cc9faf7d..e68e10104b 100644 --- a/src/test/unit/target.h +++ b/src/test/unit/target.h @@ -20,14 +20,14 @@ #define SCHEDULER_DELAY_LIMIT 1 #define TASK_GYROPID_DESIRED_PERIOD 100 -#define CMS +#define USE_CMS #define CMS_MAX_DEVICE 4 #define USE_FAKE_GYRO #define BEEPER -#define BLACKBOX -#define MAG -#define BARO -#define GPS +#define USE_BLACKBOX +#define USE_MAG +#define USE_BARO +#define USE_GPS #define USE_DASHBOARD #define SERIAL_RX #define USE_RX_MSP