1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-22 15:55:40 +03:00

Prepend USE_ prefix to CPP directives for enabling features

Prepended to: 'ACC', 'GYRO', 'BARO', 'MAG', 'LED_STRIP',
'SPEKTRUM_BIND', 'SERIAL_RX', 'BLACKBOX', 'GPS', 'GPS_PROTO_UBLOX',
'TELEMETRY', 'TELEMETRY_LTM', 'TELEMETRY_FRSKY', 'CMS',
'GPS_PROTO_NMEA', 'GPS_PROTO_I2C_NAV', 'GPS_PROTO_NAZA',
'GPS_PROTO_UBLOX_NEO7PLUS', 'GPS_PROTO_MTK', 'TELEMETRY_HOTT',
'TELEMETRY_IBUS', 'TELEMETRY_MAVLINK', 'TELEMETRY_SMARTPORT',
'TELEMETRY_CRSF', 'PWM_DRIVER_PCA9685', 'PITOT', 'OSD',
This commit is contained in:
Alberto García Hierro 2017-12-03 20:54:49 +00:00
parent a5bee479be
commit 7a1491e158
124 changed files with 681 additions and 681 deletions

View file

@ -22,7 +22,7 @@
#include "platform.h"
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
#include "blackbox.h"
#include "blackbox_encoding.h"
@ -208,15 +208,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 PITOT
#ifdef USE_PITOT
{"AirSpeed", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_PITOT},
#endif
#ifdef USE_RANGEFINDER
@ -277,7 +277,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
#endif
};
#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)},
@ -350,13 +350,13 @@ typedef struct blackboxMainState_s {
uint16_t vbatLatest;
uint16_t amperageLatest;
#ifdef BARO
#ifdef USE_BARO
int32_t BaroAlt;
#endif
#ifdef PITOT
#ifdef USE_PITOT
int32_t airSpeed;
#endif
#ifdef MAG
#ifdef USE_MAG
int16_t magADC[XYZ_AXIS_COUNT];
#endif
#ifdef USE_RANGEFINDER
@ -484,21 +484,21 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
return pidBank()->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;
#endif
case FLIGHT_LOG_FIELD_CONDITION_PITOT:
#ifdef PITOT
#ifdef USE_PITOT
return sensors(SENSOR_PITOT);
#else
return false;
@ -630,19 +630,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 PITOT
#ifdef USE_PITOT
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_PITOT)) {
blackboxWriteSignedVB(blackboxCurrent->airSpeed);
}
@ -806,7 +806,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];
@ -814,13 +814,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 PITOT
#ifdef USE_PITOT
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_PITOT)) {
deltas[optionalFieldCount++] = blackboxCurrent->airSpeed - blackboxLast->airSpeed;
}
@ -1074,7 +1074,7 @@ void blackboxFinish(void)
}
}
#ifdef GPS
#ifdef USE_GPS
static void writeGPSHomeFrame(void)
{
blackboxWrite('H');
@ -1135,7 +1135,7 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
#ifdef MAG
#ifdef USE_MAG
blackboxCurrent->magADC[i] = mag.magADC[i];
#endif
}
@ -1161,11 +1161,11 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->vbatLatest = vbatLatestADC;
blackboxCurrent->amperageLatest = amperageLatestADC;
#ifdef BARO
#ifdef USE_BARO
blackboxCurrent->BaroAlt = baro.BaroAlt;
#endif
#ifdef PITOT
#ifdef USE_PITOT
blackboxCurrent->airSpeed = pitot.airSpeed;
#endif
@ -1578,7 +1578,7 @@ static void blackboxLogIteration(timeUs_t currentTimeUs)
loadMainState(currentTimeUs);
writeInterframe();
}
#ifdef GPS
#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
/*
* If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
@ -1645,7 +1645,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
@ -1653,7 +1653,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:
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAYLEN(blackboxGpsHFields),

View file

@ -21,7 +21,7 @@
#include "platform.h"
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
#include "blackbox_encoding.h"
#include "blackbox_io.h"

View file

@ -21,7 +21,7 @@
#include "platform.h"
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
#include "blackbox.h"
#include "blackbox_io.h"

View file

@ -31,7 +31,7 @@
#include "platform.h"
#ifdef CMS
#ifdef USE_CMS
#include "build/build_config.h"
#include "build/debug.h"
@ -328,7 +328,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;
@ -845,7 +845,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;

View file

@ -24,7 +24,7 @@
#include "platform.h"
#ifdef CMS
#ifdef USE_CMS
#include "blackbox/blackbox.h"

View file

@ -26,7 +26,7 @@
#include "platform.h"
#ifdef CMS
#ifdef USE_CMS
#include "build/version.h"
@ -114,7 +114,7 @@ static OSD_Entry menuFeaturesEntries[] =
{"VTX TR", OME_Submenu, cmsMenuChange, &cmsx_menuVtxTramp, 0},
#endif
#endif // VTX_CONTROL
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
#endif // LED_STRIP
{"BACK", OME_Back, NULL, NULL, 0},
@ -140,7 +140,7 @@ static OSD_Entry menuMainEntries[] =
{"PID TUNING", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
#ifdef OSD
#ifdef USE_OSD
{"SCR LAYOUT", OME_Submenu, cmsMenuChange, &cmsx_menuOsdLayout, 0},
{"ALARMS", OME_Submenu, cmsMenuChange, &cmsx_menuAlarms, 0},
#endif

View file

@ -24,7 +24,7 @@
#include "platform.h"
#ifdef CMS
#ifdef USE_CMS
#include "common/utils.h"

View file

@ -24,7 +24,7 @@
#include "build/version.h"
#ifdef CMS
#ifdef USE_CMS
#include "common/axis.h"
#include "io/gimbal.h"
@ -42,7 +42,7 @@
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
static bool cmsx_FeatureLedStrip_Enabled(bool *enabled)
{

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef CMS
#ifdef USE_CMS
#include "common/utils.h"

View file

@ -21,7 +21,7 @@
#include "platform.h"
#if defined(OSD) && defined(CMS)
#if defined(USE_OSD) && defined(USE_CMS)
#include "common/utils.h"
@ -90,7 +90,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
{"HOME DIR.", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HOME_DIR], 0},
{"HOME DIST.", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HOME_DIST], 0},
{"GPS SPEED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SPEED], 0},
@ -99,7 +99,7 @@ OSD_Entry menuOsdActiveElemsEntries[] =
{"GPS LON.", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LON], 0},
{"HEADING", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HEADING], 0},
#endif // GPS
#if defined(BARO) || defined(GPS)
#if defined(USE_BARO) || defined(USE_GPS)
{"VARIO", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_VARIO], 0},
{"VARIO NUM", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_VARIO_NUM], 0},
#endif // defined

View file

@ -29,7 +29,7 @@
#include "config/feature.h"
#ifdef CMS
#ifdef USE_CMS
#if defined(VTX) || defined(USE_RTC6705)

View file

@ -20,7 +20,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"

View file

@ -20,7 +20,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"

View file

@ -45,7 +45,7 @@ typedef enum
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
OME_Setting,
//wlasciwosci elementow
#ifdef OSD
#ifdef USE_OSD
OME_VISIBLE,
#endif
OME_TAB,

View file

@ -24,7 +24,7 @@
#include "common/string_light.h"
#ifdef GPS
#ifdef USE_GPS
#define DIGIT_TO_VAL(_x) (_x - '0')

View file

@ -30,7 +30,7 @@
#include <platform.h>
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
#include "build/build_config.h"

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
#include "common/color.h"
#include "light_ws2811strip.h"

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
#include "drivers/io.h"
#include "drivers/nvic.h"

View file

@ -181,16 +181,16 @@ static const char * const hardwareSensorStatusNames[] = {
static const char * const *sensorHardwareNames[] = {
gyroNames,
table_acc_hardware,
#ifdef BARO
#ifdef USE_BARO
table_baro_hardware,
#endif
#ifdef MAG
#ifdef USE_MAG
table_mag_hardware,
#endif
#ifdef USE_RANGEFINDER
table_rangefinder_hardware,
#endif
#ifdef PITOT
#ifdef USE_PITOT
table_pitot_hardware,
#endif
#ifdef USE_OPTICAL_FLOW
@ -1131,7 +1131,7 @@ static void cliRxRange(char *cmdline)
}
}
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
static void printLed(uint8_t dumpMask, const ledConfig_t *ledConfigs, const ledConfig_t *defaultLedConfigs)
{
const char *format = "led %u %s";
@ -1995,7 +1995,7 @@ static void cliExit(char *cmdline)
cliWriter = NULL;
}
#ifdef GPS
#ifdef USE_GPS
static void cliGpsPassthrough(char *cmdline)
{
UNUSED(cmdline);
@ -2607,7 +2607,7 @@ static void printConfig(const char *cmdline, bool doDiff)
cliPrintHashLine("serial");
printSerial(dumpMask, &serialConfig_Copy, serialConfig());
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
cliPrintHashLine("led");
printLed(dumpMask, ledStripConfig_Copy.ledConfigs, ledStripConfig()->ledConfigs);
@ -2705,7 +2705,7 @@ const clicmd_t cmdTable[] = {
#if defined(BOOTLOG)
CLI_COMMAND_DEF("bootlog", "show boot events", NULL, cliBootlog),
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
#endif
@ -2731,11 +2731,11 @@ 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),
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
#endif
CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap),

View file

@ -301,7 +301,7 @@ void validateAndFixConfig(void)
}
#endif
#if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
#if defined(USE_LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
if (featureConfigured(FEATURE_SOFTSERIAL) && featureConfigured(FEATURE_LED_STRIP)) {
const timerHardware_t *ledTimerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
if (ledTimerHardware != NULL) {
@ -422,7 +422,7 @@ void createDefaultConfig(void)
parseRcChannels("AETR1234");
#endif
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
#ifdef ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
featureSet(FEATURE_BLACKBOX);
#endif
@ -441,7 +441,7 @@ void resetConfigs(void)
createDefaultConfig();
setConfigProfile(getConfigProfile());
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
reevaluateLedConfig();
#endif
}

View file

@ -110,13 +110,13 @@ static disarmReason_t lastDisarmReason = DISARM_NONE;
bool isCalibrating(void)
{
#ifdef BARO
#ifdef USE_BARO
if (sensors(SENSOR_BARO) && !baroIsCalibrationComplete()) {
return true;
}
#endif
#ifdef PITOT
#ifdef USE_PITOT
if (sensors(SENSOR_PITOT) && !pitotIsCalibrationComplete()) {
return true;
}
@ -222,7 +222,7 @@ static void updateArmingStatus(void)
}
#endif
#if defined(MAG)
#if defined(USE_MAG)
/* CHECK: */
if (sensors(SENSOR_MAG) && !STATE(COMPASS_CALIBRATED)) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_COMPASS_NOT_CALIBRATED);
@ -325,7 +325,7 @@ void mwDisarm(disarmReason_t disarmReason)
lastDisarmReason = disarmReason;
DISABLE_ARMING_FLAG(ARMED);
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
blackboxFinish();
}
@ -367,7 +367,7 @@ void mwArm(void)
resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) {
@ -544,7 +544,7 @@ void processRx(timeUs_t currentTimeUs)
}
}
#if defined(MAG)
#if defined(USE_MAG)
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
if (IS_RC_MODE_ACTIVE(BOXHEADFREE)) {
if (!FLIGHT_MODE(HEADFREE_MODE)) {
@ -607,7 +607,7 @@ void processRx(timeUs_t currentTimeUs)
autotuneUpdateState();
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY)) {
if ((!telemetryConfig()->telemetry_switch && ARMING_FLAG(ARMED)) ||
(telemetryConfig()->telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
@ -817,7 +817,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
afatfs_poll();
#endif
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
if (!cliMode && feature(FEATURE_BLACKBOX)) {
blackboxUpdate(micros());
}

View file

@ -226,7 +226,7 @@ void init(void)
addBootlogEvent2(BOOT_EVENT_SYSTEM_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
#ifdef SPEKTRUM_BIND
#ifdef USE_SPEKTRUM_BIND
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
switch (rxConfig()->serialrx_provider) {
case SERIALRX_SPEKTRUM1024:
@ -460,7 +460,7 @@ void init(void)
adc_params.adcFunctionChannel[ADC_CURRENT] = adcChannelConfig()->adcFunctionChannel[ADC_CURRENT];
}
#if defined(PITOT) && defined(USE_PITOT_ADC)
#if defined(USE_PITOT) && defined(USE_PITOT_ADC)
if (pitotmeterConfig()->pitot_hardware == PITOT_ADC || pitotmeterConfig()->pitot_hardware == PITOT_AUTODETECT) {
adc_params.adcFunctionChannel[ADC_AIRSPEED] = adcChannelConfig()->adcFunctionChannel[ADC_AIRSPEED];
}
@ -470,7 +470,7 @@ void init(void)
#endif
/* Extra 500ms delay prior to initialising hardware if board is cold-booting */
#if defined(GPS) || defined(MAG)
#if defined(USE_GPS) || defined(USE_MAG)
if (!isMPUSoftReset()) {
addBootlogEvent2(BOOT_EVENT_EXTRA_BOOT_DELAY, BOOT_EVENT_FLAGS_NONE);
@ -490,7 +490,7 @@ void init(void)
initBoardAlignment();
#ifdef CMS
#ifdef USE_CMS
cmsInit();
#endif
@ -500,7 +500,7 @@ void init(void)
}
#endif
#ifdef GPS
#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
gpsPreInit();
}
@ -533,11 +533,11 @@ void init(void)
rxInit();
#if (defined(OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(CMS)))
#if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)))
displayPort_t *osdDisplayPort = NULL;
#endif
#ifdef OSD
#ifdef USE_OSD
if (feature(FEATURE_OSD)) {
#if defined(USE_MAX7456)
// If there is a max7456 chip for the OSD then use it
@ -552,7 +552,7 @@ void init(void)
}
#endif
#if defined(USE_MSP_DISPLAYPORT) && defined(CMS)
#if defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)
// If OSD is not active, then register MSP_DISPLAYPORT as a CMS device.
if (!osdDisplayPort) {
cmsDisplayPortRegister(displayPortMspInit());
@ -563,7 +563,7 @@ void init(void)
uavInterconnectBusInit();
#endif
#ifdef GPS
#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
gpsInit();
addBootlogEvent2(BOOT_EVENT_GPS_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
@ -575,7 +575,7 @@ void init(void)
navigationInit();
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
ledStripInit();
if (feature(FEATURE_LED_STRIP)) {
@ -584,7 +584,7 @@ void init(void)
}
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY)) {
telemetryInit();
addBootlogEvent2(BOOT_EVENT_TELEMETRY_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
@ -610,7 +610,7 @@ void init(void)
#ifdef SDCARD_DMA_CHANNEL_TX
#if defined(LED_STRIP) && defined(WS2811_DMA_CHANNEL)
#if defined(USE_LED_STRIP) && defined(WS2811_DMA_CHANNEL)
// Ensure the SPI Tx DMA doesn't overlap with the led strip
#if defined(STM32F4) || defined(STM32F7)
sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_STREAM;
@ -628,16 +628,16 @@ void init(void)
afatfs_init();
#endif
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
blackboxInit();
#endif
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
#ifdef BARO
#ifdef USE_BARO
baroStartCalibration();
#endif
#ifdef PITOT
#ifdef USE_PITOT
pitotStartCalibration();
#endif

View file

@ -470,7 +470,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU32(dst, 0);
sbufWriteU16(dst, 0);
#endif
#if defined(BARO)
#if defined(USE_BARO)
sbufWriteU32(dst, baroGetLatestAltitude());
#else
sbufWriteU32(dst, 0);
@ -577,7 +577,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, failsafeConfig()->failsafe_throttle);
#ifdef GPS
#ifdef USE_GPS
sbufWriteU8(dst, gpsConfig()->provider); // gps_type
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
sbufWriteU8(dst, gpsConfig()->sbasMode); // gps_ubx_sbas
@ -605,7 +605,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
break;
#ifdef GPS
#ifdef USE_GPS
case MSP_RAW_GPS:
sbufWriteU8(dst, gpsSol.fixType);
sbufWriteU8(dst, gpsSol.numSat);
@ -769,7 +769,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
break;
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
case MSP_LED_COLORS:
for (int i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
const hsvColor_t *color = &ledStripConfig()->colors[i];
@ -808,7 +808,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP_BLACKBOX_CONFIG:
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
sbufWriteU8(dst, 1); //Blackbox supported
sbufWriteU8(dst, blackboxConfig()->device);
sbufWriteU8(dst, blackboxConfig()->rate_num);
@ -826,7 +826,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP_OSD_CONFIG:
#ifdef OSD
#ifdef USE_OSD
sbufWriteU8(dst, 1); // OSD supported
// send video system (AUTO/PAL/NTSC)
#ifdef USE_MAX7456
@ -959,17 +959,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
case MSP_SENSOR_CONFIG:
sbufWriteU8(dst, accelerometerConfig()->acc_hardware);
#ifdef BARO
#ifdef USE_BARO
sbufWriteU8(dst, barometerConfig()->baro_hardware);
#else
sbufWriteU8(dst, 0);
#endif
#ifdef MAG
#ifdef USE_MAG
sbufWriteU8(dst, compassConfig()->mag_hardware);
#else
sbufWriteU8(dst, 0);
#endif
#ifdef PITOT
#ifdef USE_PITOT
sbufWriteU8(dst, pitotmeterConfig()->pitot_hardware);
#else
sbufWriteU8(dst, 0);
@ -1026,7 +1026,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif
case MSP_CALIBRATION_DATA:
#ifdef ACC
#ifdef USE_ACC
sbufWriteU16(dst, accelerometerConfig()->accZero.raw[X]);
sbufWriteU16(dst, accelerometerConfig()->accZero.raw[Y]);
sbufWriteU16(dst, accelerometerConfig()->accZero.raw[Z]);
@ -1042,7 +1042,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, 0);
#endif
#ifdef MAG
#ifdef USE_MAG
sbufWriteU16(dst, compassConfig()->magZero.raw[X]);
sbufWriteU16(dst, compassConfig()->magZero.raw[Y]);
sbufWriteU16(dst, compassConfig()->magZero.raw[Z]);
@ -1357,7 +1357,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
failsafeConfigMutable()->failsafe_throttle = sbufReadU16(src);
#ifdef GPS
#ifdef USE_GPS
gpsConfigMutable()->provider = sbufReadU8(src); // gps_type
sbufReadU8(src); // gps_baudrate
gpsConfigMutable()->sbasMode = sbufReadU8(src); // gps_ubx_sbas
@ -1370,7 +1370,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
rxConfigMutable()->rssi_channel = sbufReadU8(src);
sbufReadU8(src);
#ifdef MAG
#ifdef USE_MAG
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
#else
sbufReadU16(src);
@ -1449,7 +1449,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP_SET_SENSOR_ALIGNMENT:
gyroConfigMutable()->gyro_align = sbufReadU8(src);
accelerometerConfigMutable()->acc_align = sbufReadU8(src);
#ifdef MAG
#ifdef USE_MAG
compassConfigMutable()->mag_align = sbufReadU8(src);
#else
sbufReadU8(src);
@ -1532,17 +1532,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP_SET_SENSOR_CONFIG:
accelerometerConfigMutable()->acc_hardware = sbufReadU8(src);
#ifdef BARO
#ifdef USE_BARO
barometerConfigMutable()->baro_hardware = sbufReadU8(src);
#else
sbufReadU8(src);
#endif
#ifdef MAG
#ifdef USE_MAG
compassConfigMutable()->mag_hardware = sbufReadU8(src);
#else
sbufReadU8(src);
#endif
#ifdef PITOT
#ifdef USE_PITOT
pitotmeterConfigMutable()->pitot_hardware = sbufReadU8(src);
#else
sbufReadU8(src);
@ -1600,7 +1600,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
#endif
case MSP_SET_CALIBRATION_DATA:
#ifdef ACC
#ifdef USE_ACC
accelerometerConfigMutable()->accZero.raw[X] = sbufReadU16(src);
accelerometerConfigMutable()->accZero.raw[Y] = sbufReadU16(src);
accelerometerConfigMutable()->accZero.raw[Z] = sbufReadU16(src);
@ -1616,7 +1616,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif
#ifdef MAG
#ifdef USE_MAG
compassConfigMutable()->magZero.raw[X] = sbufReadU16(src);
compassConfigMutable()->magZero.raw[Y] = sbufReadU16(src);
compassConfigMutable()->magZero.raw[Z] = sbufReadU16(src);
@ -1664,7 +1664,7 @@ static mspResult_e mspFcProcessInCommand(uint16_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()) {
@ -1675,7 +1675,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
break;
#endif
#ifdef OSD
#ifdef USE_OSD
case MSP_SET_OSD_CONFIG:
{
const uint8_t addr = sbufReadU8(src);
@ -1767,7 +1767,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
break;
#endif
#ifdef GPS
#ifdef USE_GPS
case MSP_SET_RAW_GPS:
if (sbufReadU8(src)) {
ENABLE_STATE(GPS_FIX);
@ -1934,7 +1934,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
}
break;
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
case MSP_SET_LED_COLORS:
for (int i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
hsvColor_t *color = &ledStripConfigMutable()->colors[i];

View file

@ -170,7 +170,7 @@ void initActiveBoxIds(void)
if (feature(FEATURE_SERVO_TILT))
activeBoxIds[activeBoxIdCount++] = BOXCAMSTAB;
#ifdef GPS
#ifdef USE_GPS
if (sensors(SENSOR_BARO) || (STATE(FIXED_WING) && feature(FEATURE_GPS))) {
activeBoxIds[activeBoxIdCount++] = BOXNAVALTHOLD;
activeBoxIds[activeBoxIdCount++] = BOXSURFACE;
@ -205,7 +205,7 @@ void initActiveBoxIds(void)
activeBoxIds[activeBoxIdCount++] = BOXBEEPERON;
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
if (feature(FEATURE_LED_STRIP)) {
activeBoxIds[activeBoxIdCount++] = BOXLEDLOW;
}
@ -213,12 +213,12 @@ void initActiveBoxIds(void)
activeBoxIds[activeBoxIdCount++] = BOXOSD;
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY) && telemetryConfig()->telemetry_switch)
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
#endif
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
if (feature(FEATURE_BLACKBOX)){
activeBoxIds[activeBoxIdCount++] = BOXBLACKBOX;
}

View file

@ -123,7 +123,7 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
}
}
#ifdef GPS
#ifdef USE_GPS
void taskProcessGPS(timeUs_t currentTimeUs)
{
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
@ -139,7 +139,7 @@ void taskProcessGPS(timeUs_t currentTimeUs)
}
#endif
#ifdef MAG
#ifdef USE_MAG
void taskUpdateCompass(timeUs_t currentTimeUs)
{
if (sensors(SENSOR_MAG)) {
@ -148,7 +148,7 @@ void taskUpdateCompass(timeUs_t currentTimeUs)
}
#endif
#ifdef BARO
#ifdef USE_BARO
void taskUpdateBaro(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
@ -164,7 +164,7 @@ void taskUpdateBaro(timeUs_t currentTimeUs)
}
#endif
#ifdef PITOT
#ifdef USE_PITOT
void taskUpdatePitot(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
@ -220,7 +220,7 @@ void taskDashboardUpdate(timeUs_t currentTimeUs)
}
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
void taskTelemetry(timeUs_t currentTimeUs)
{
telemetryCheckState();
@ -231,7 +231,7 @@ void taskTelemetry(timeUs_t currentTimeUs)
}
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
void taskLedStrip(timeUs_t currentTimeUs)
{
if (feature(FEATURE_LED_STRIP)) {
@ -265,7 +265,7 @@ void taskAcc(timeUs_t currentTimeUs)
}
#endif
#ifdef OSD
#ifdef USE_OSD
void taskUpdateOsd(timeUs_t currentTimeUs)
{
if (feature(FEATURE_OSD)) {
@ -319,20 +319,20 @@ void fcTasksInit(void)
#endif
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
setTaskEnabled(TASK_RX, true);
#ifdef GPS
#ifdef USE_GPS
setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
#endif
#ifdef MAG
#ifdef USE_MAG
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
#if defined(USE_MAG_MPU9250)
// fixme temporary solution for AK6983 via slave I2C on MPU9250
rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
#endif
#endif
#ifdef BARO
#ifdef USE_BARO
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
#endif
#ifdef PITOT
#ifdef USE_PITOT
setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT));
#endif
#ifdef USE_RANGEFINDER
@ -341,10 +341,10 @@ void fcTasksInit(void)
#ifdef USE_DASHBOARD
setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD));
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
#endif
#ifdef STACK_CHECK
@ -353,10 +353,10 @@ void fcTasksInit(void)
#ifdef USE_PMW_SERVO_DRIVER
setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER));
#endif
#ifdef OSD
#ifdef USE_OSD
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
#endif
#ifdef CMS
#ifdef USE_CMS
#ifdef USE_MSP_DISPLAYPORT
setTaskEnabled(TASK_CMS, true);
#else
@ -462,7 +462,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_HIGH,
},
#ifdef GPS
#ifdef USE_GPS
[TASK_GPS] = {
.taskName = "GPS",
.taskFunc = taskProcessGPS,
@ -471,7 +471,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef MAG
#ifdef USE_MAG
[TASK_COMPASS] = {
.taskName = "COMPASS",
.taskFunc = taskUpdateCompass,
@ -480,7 +480,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef BARO
#ifdef USE_BARO
[TASK_BARO] = {
.taskName = "BARO",
.taskFunc = taskUpdateBaro,
@ -489,7 +489,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef PITOT
#ifdef USE_PITOT
[TASK_PITOT] = {
.taskName = "PITOT",
.taskFunc = taskUpdatePitot,
@ -516,7 +516,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
[TASK_TELEMETRY] = {
.taskName = "TELEMETRY",
.taskFunc = taskTelemetry,
@ -525,7 +525,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
[TASK_LEDSTRIP] = {
.taskName = "LEDSTRIP",
.taskFunc = taskLedStrip,
@ -552,7 +552,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef OSD
#ifdef USE_OSD
[TASK_OSD] = {
.taskName = "OSD",
.taskFunc = taskUpdateOsd,
@ -561,7 +561,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef CMS
#ifdef USE_CMS
[TASK_CMS] = {
.taskName = "CMS",
.taskFunc = cmsHandler,

View file

@ -221,7 +221,7 @@ groups:
- name: PG_COMPASS_CONFIG
type: compassConfig_t
headers: ["sensors/compass.h"]
condition: MAG
condition: USE_MAG
members:
- name: align_mag
field: mag_align
@ -256,7 +256,7 @@ groups:
- name: PG_BAROMETER_CONFIG
type: barometerConfig_t
headers: ["sensors/barometer.h"]
condition: BARO
condition: USE_BARO
members:
- name: baro_hardware
table: baro_hardware
@ -267,7 +267,7 @@ groups:
- name: PG_PITOTMETER_CONFIG
type: pitotmeterConfig_t
headers: ["sensors/pitotmeter.h"]
condition: PITOT
condition: USE_PITOT
members:
- name: pitot_hardware
table: pitot_hardware
@ -313,10 +313,10 @@ groups:
field: rcSmoothing
type: bool
- name: serialrx_provider
condition: SERIAL_RX
condition: USE_SERIAL_RX
table: serial_rx
- name: sbus_inversion
condition: SERIAL_RX
condition: USE_SERIAL_RX
type: bool
- name: rx_spi_protocol
condition: USE_RX_SPI
@ -329,7 +329,7 @@ groups:
min: 0
max: 8
- name: spektrum_sat_bind
condition: SPEKTRUM_BIND
condition: USE_SPEKTRUM_BIND
min: SPEKTRUM_SAT_BIND_DISABLED
max: SPEKTRUM_SAT_BIND_MAX
- name: rx_min_usec
@ -346,7 +346,7 @@ groups:
- name: PG_BLACKBOX_CONFIG
type: blackboxConfig_t
headers: ["blackbox/blackbox.h"]
condition: BLACKBOX
condition: USE_BLACKBOX
members:
- name: blackbox_rate_num
field: rate_num
@ -631,7 +631,7 @@ groups:
- name: PG_GPS_CONFIG
type: gpsConfig_t
condition: GPS
condition: USE_GPS
members:
- name: gps_provider
field: provider
@ -1217,7 +1217,7 @@ groups:
- name: PG_TELEMETRY_CONFIG
type: telemetryConfig_t
headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/frsky.h"]
condition: TELEMETRY
condition: USE_TELEMETRY
members:
- name: telemetry_switch
type: bool
@ -1250,11 +1250,11 @@ groups:
max: 120
- name: smartport_uart_unidir
field: smartportUartUnidirectional
condition: TELEMETRY_SMARTPORT
condition: USE_TELEMETRY_SMARTPORT
type: bool
- name: smartport_fuel_percent
field: smartportFuelPercent
condition: TELEMETRY_SMARTPORT
condition: USE_TELEMETRY_SMARTPORT
type: bool
- name: ibus_telemetry_type
field: ibusTelemetryType
@ -1262,7 +1262,7 @@ groups:
max: 255
- name: ltm_update_rate
field: ltmUpdateRate
condition: TELEMETRY_LTM
condition: USE_TELEMETRY_LTM
table: ltm_rates
- name: PG_ELERES_CONFIG
@ -1299,7 +1299,7 @@ groups:
- name: PG_LED_STRIP_CONFIG
type: ledStripConfig_t
headers: ["common/color.h", "io/ledstrip.h"]
condition: LED_STRIP
condition: USE_LED_STRIP
members:
- name: ledstrip_visual_beeper
type: bool
@ -1307,7 +1307,7 @@ groups:
- name: PG_OSD_CONFIG
type: osdConfig_t
headers: ["io/osd.h"]
condition: OSD
condition: USE_OSD
members:
- name: osd_video_system
field: video_system

View file

@ -184,7 +184,7 @@ static float invSqrt(float x)
return 1.0f / sqrtf(x);
}
#if defined(GPS) || defined(HIL)
#if defined(USE_GPS) || defined(HIL)
STATIC_UNIT_TESTED void imuComputeQuaternionFromRPY(int16_t initialRoll, int16_t initialPitch, int16_t initialYaw)
{
if (initialRoll > 1800) initialRoll -= 3600;
@ -253,7 +253,7 @@ static void imuCheckAndResetOrientationQuaternion(const float ax, const float ay
if (isNan || isZero || isInf) {
imuResetOrientationQuaternion(ax, ay, az);
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
blackboxLogEvent(FLIGHT_LOG_EVENT_IMU_FAILURE, NULL);
}
@ -444,7 +444,7 @@ static bool imuCanUseAccelerometerForCorrection(void)
static void imuCalculateEstimatedAttitude(float dT)
{
#if defined(MAG)
#if defined(USE_MAG)
const bool canUseMAG = sensors(SENSOR_MAG) && compassIsHealthy();
#else
const bool canUseMAG = false;
@ -456,7 +456,7 @@ static void imuCalculateEstimatedAttitude(float dT)
bool useMag = false;
bool useCOG = false;
#if defined(GPS)
#if defined(USE_GPS)
if (STATE(FIXED_WING)) {
bool canUseCOG = sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 6 && gpsSol.groundSpeed >= 300;

View file

@ -100,7 +100,7 @@ STATIC_FASTRAM pt1Filter_t headingHoldRateFilter;
STATIC_FASTRAM bool pidGainsUpdateRequired;
FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT];
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_D[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_Setpoint[FLIGHT_DYNAMICS_INDEX_COUNT];
#endif
@ -458,7 +458,7 @@ static void pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamic
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidProfile()->pidSumLimit, +pidProfile()->pidSumLimit);
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
axisPID_P[axis] = newPTerm;
axisPID_I[axis] = pidState->errorGyroIf;
axisPID_D[axis] = newFFTerm;
@ -524,7 +524,7 @@ static void pidApplyMulticopterRateController(pidState_t *pidState, flight_dynam
axisPID[axis] = newOutputLimited;
#ifdef BLACKBOX
#ifdef USE_BLACKBOX
axisPID_P[axis] = newPTerm;
axisPID_I[axis] = pidState->errorGyroIf;
axisPID_D[axis] = newDTerm;
@ -652,7 +652,7 @@ static void pidTurnAssistant(pidState_t *pidState)
// If we solve for yaw rate we get:
// yaw_rate = tan(roll_angle) * Gravity / forward_vel
#if defined(PITOT)
#if defined(USE_PITOT)
float airspeedForCoordinatedTurn = sensors(SENSOR_PITOT) ?
pitot.airSpeed :
pidProfile()->fixedWingReferenceAirspeed;

View file

@ -34,7 +34,7 @@
#include "io/statusindicator.h"
#ifdef GPS
#ifdef USE_GPS
#include "io/gps.h"
#endif
@ -280,7 +280,7 @@ void beeperConfirmationBeeps(uint8_t beepCount)
beeper(BEEPER_MULTI_BEEPS); //initiate sequence
}
#ifdef GPS
#ifdef USE_GPS
void beeperGpsStatus(void)
{
// if GPS fix then beep out number of satellites
@ -309,7 +309,7 @@ void beeperUpdate(timeUs_t currentTimeUs)
{
// If beeper option from AUX switch has been selected
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
#ifdef GPS
#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
beeperGpsStatus();
} else {

View file

@ -49,7 +49,7 @@
#include "io/dashboard.h"
#include "io/displayport_oled.h"
#ifdef GPS
#ifdef USE_GPS
#include "io/gps.h"
#endif
@ -198,7 +198,7 @@ static void padLineBufferToChar(uint8_t toChar)
lineBuffer[length] = 0;
}
#ifdef GPS
#ifdef USE_GPS
static void padLineBuffer(void)
{
padLineBufferToChar(sizeof(lineBuffer));
@ -375,7 +375,7 @@ static void showStatusPage(void)
drawHorizonalPercentageBar(10, capacityPercentage);
}
#ifdef GPS
#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
tfp_sprintf(lineBuffer, "Sats: %d", gpsSol.numSat);
padHalfLineBuffer();
@ -400,7 +400,7 @@ static void showStatusPage(void)
}
#endif
#ifdef MAG
#ifdef USE_MAG
if (sensors(SENSOR_MAG)) {
tfp_sprintf(lineBuffer, "HDG: %d", DECIDEGREES_TO_DEGREES(attitude.values.yaw));
padHalfLineBuffer();
@ -409,7 +409,7 @@ static void showStatusPage(void)
}
#endif
#ifdef BARO
#ifdef USE_BARO
if (sensors(SENSOR_BARO)) {
int32_t alt = baroCalculateAltitude();
tfp_sprintf(lineBuffer, "Alt: %d", alt / 100);
@ -433,7 +433,7 @@ void dashboardUpdate(timeUs_t currentTimeUs)
static uint8_t previousArmedState = 0;
bool pageChanging;
#ifdef CMS
#ifdef USE_CMS
static bool wasGrabbed = false;
if (displayIsGrabbed(displayPort)) {
wasGrabbed = true;
@ -535,7 +535,7 @@ void dashboardInit(void)
delay(200);
displayPort = displayPortOledInit();
#if defined(CMS)
#if defined(USE_CMS)
cmsDisplayPortRegister(displayPort);
#endif

View file

@ -24,7 +24,7 @@
#include "build/build_config.h"
#ifdef GPS
#ifdef USE_GPS
#include "build/debug.h"
@ -86,42 +86,42 @@ baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600,
static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
/* NMEA GPS */
#ifdef GPS_PROTO_NMEA
#ifdef USE_GPS_PROTO_NMEA
{ GPS_TYPE_SERIAL, MODE_RX, false, NULL, &gpsHandleNMEA },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },
#endif
/* UBLOX binary */
#ifdef GPS_PROTO_UBLOX
#ifdef USE_GPS_PROTO_UBLOX
{ GPS_TYPE_SERIAL, MODE_RXTX, false, NULL, &gpsHandleUBLOX },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },
#endif
/* MultiWii I2C-NAV module */
#ifdef GPS_PROTO_I2C_NAV
#ifdef USE_GPS_PROTO_I2C_NAV
{ GPS_TYPE_BUS, 0, false, &gpsDetectI2CNAV, &gpsHandleI2CNAV },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },
#endif
/* NAZA GPS module */
#ifdef GPS_PROTO_NAZA
#ifdef USE_GPS_PROTO_NAZA
{ GPS_TYPE_SERIAL, MODE_RX, true, NULL, &gpsHandleNAZA },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },
#endif
/* UBLOX7PLUS binary */
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
{ GPS_TYPE_SERIAL, MODE_RXTX, false, NULL, &gpsHandleUBLOX },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },
#endif
/* MTK GPS */
#ifdef GPS_PROTO_MTK
#ifdef USE_GPS_PROTO_MTK
{ GPS_TYPE_SERIAL, MODE_RXTX, false, NULL, &gpsHandleMTK },
#else
{ GPS_TYPE_NA, 0, false, NULL, NULL },

View file

@ -21,7 +21,7 @@
#include "platform.h"
#if defined(GPS) && defined(GPS_PROTO_I2C_NAV)
#if defined(USE_GPS) && defined(USE_GPS_PROTO_I2C_NAV)
#include "build/build_config.h"
#include "build/debug.h"

View file

@ -25,7 +25,7 @@
#include "build/build_config.h"
#if defined(GPS) && defined(GPS_PROTO_NAZA)
#if defined(USE_GPS) && defined(USE_GPS_PROTO_NAZA)
#include "build/debug.h"

View file

@ -23,8 +23,8 @@
#include "platform.h"
#if defined(GPS)
#if defined(GPS_PROTO_NMEA) || defined(GPS_PROTO_MTK)
#if defined(USE_GPS)
#if defined(USE_GPS_PROTO_NMEA) || defined(USE_GPS_PROTO_MTK)
#include "build/build_config.h"
#include "build/debug.h"
@ -280,7 +280,7 @@ static bool gpsReceiveData(void)
return hasNewData;
}
#ifdef GPS_PROTO_MTK
#ifdef USE_GPS_PROTO_MTK
static uint8_t *mtk_conf[] = {
(uint8_t *)"$PMTK251,57600*2C\r\n", //change baudrate to 57600
@ -333,7 +333,7 @@ static bool gpsInitialize(void)
static bool gpsChangeBaud(void)
{
#ifdef GPS_PROTO_MTK
#ifdef USE_GPS_PROTO_MTK
if ((gpsState.gpsConfig->autoBaud != GPS_AUTOBAUD_OFF) && (gpsState.autoBaudrateIndex < GPS_BAUDRATE_COUNT)) {
// Do the switch only if TX buffer is empty - make sure all init string was sent at the same baud
if (isSerialTransmitBufferEmpty(gpsState.gpsPort)) {

View file

@ -17,7 +17,7 @@
#pragma once
#ifdef GPS
#ifdef USE_GPS
#include "io/serial.h"

View file

@ -26,7 +26,7 @@
#include "build/build_config.h"
#if defined(GPS) && defined(GPS_PROTO_UBLOX)
#if defined(USE_GPS) && defined(USE_GPS_PROTO_UBLOX)
#include "build/debug.h"
@ -47,7 +47,7 @@
#include "io/gps.h"
#include "io/gps_private.h"
//#define GPS_PROTO_UBLOX_NEO7PLUS
//#define USE_GPS_PROTO_UBLOX_NEO7PLUS
#define GPS_VERSION_DETECTION_TIMEOUT_MS 300
#define MAX_UBLOX_PAYLOAD_SIZE 256
#define UBLOX_BUFFER_SIZE MAX_UBLOX_PAYLOAD_SIZE
@ -369,7 +369,7 @@ static void sendConfigMessageUBLOX(void)
//check ack/nack here
}
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
static void pollVersion(void)
{
send_buffer.message.header.msg_class = CLASS_MON;
@ -492,7 +492,7 @@ static bool gpsParceFrameUBLOX(void)
gpsSol.flags.validTime = 0;
}
break;
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
case MSG_PVT:
next_fix_type = gpsMapFixType(_buffer.pvt.fix_status & NAV_STATUS_FIX_VALID, _buffer.pvt.fix_type);
gpsSol.fixType = next_fix_type;
@ -675,7 +675,7 @@ static bool gpsConfigure(void)
break;
case 3: // Enable UBX messages
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
if ((gpsState.gpsConfig->provider == GPS_UBLOX) || (gpsState.hwVersion < 70000)) {
#endif
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1);
@ -684,7 +684,7 @@ static bool gpsConfigure(void)
configureMSG(MSG_CLASS_UBX, MSG_VELNED, 1);
configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0);
configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC,10);
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
configureMSG(MSG_CLASS_UBX, MSG_PVT, 0);
}
else if (gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
@ -701,11 +701,11 @@ static bool gpsConfigure(void)
break;
case 4: // Configure RATE
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
if ((gpsState.gpsConfig->provider == GPS_UBLOX) || (gpsState.hwVersion < 70000)) {
#endif
configureRATE(200); // 5Hz
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
}
else if (gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
configureRATE(100); // 10Hz
@ -730,7 +730,7 @@ static bool gpsConfigure(void)
static bool gpsCheckVersion(void)
{
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
#ifdef USE_GPS_PROTO_UBLOX_NEO7PLUS
if (gpsState.autoConfigStep == 0) {
pollVersion();
gpsState.autoConfigStep++;

View file

@ -23,7 +23,7 @@
#include <platform.h>
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
#include "build/build_config.h"
@ -443,7 +443,7 @@ static const struct {
} flightModeToLed[] = {
{HEADFREE_MODE, LED_MODE_HEADFREE},
{HEADING_MODE, LED_MODE_MAG},
#ifdef BARO
#ifdef USE_BARO
{NAV_ALTHOLD_MODE, LED_MODE_BARO},
#endif
{HORIZON_MODE, LED_MODE_HORIZON},
@ -636,7 +636,7 @@ static void applyLedRssiLayer(bool updateNow, timeUs_t *timer)
}
}
#ifdef GPS
#ifdef USE_GPS
static void applyLedGpsLayer(bool updateNow, timeUs_t *timer)
{
static uint8_t gpsFlashCounter = 0;
@ -898,7 +898,7 @@ typedef enum {
timLarson,
timBattery,
timRssi,
#ifdef GPS
#ifdef USE_GPS
timGps,
#endif
timWarning,
@ -924,7 +924,7 @@ static applyLayerFn_timed* layerTable[] = {
[timLarson] = &applyLarsonScannerLayer,
[timBattery] = &applyLedBatteryLayer,
[timRssi] = &applyLedRssiLayer,
#ifdef GPS
#ifdef USE_GPS
[timGps] = &applyLedGpsLayer,
#endif
[timWarning] = &applyLedWarningLayer,

View file

@ -30,7 +30,7 @@
#include "platform.h"
#ifdef OSD
#ifdef USE_OSD
#include "build/debug.h"
#include "build/version.h"
@ -725,7 +725,7 @@ static inline int32_t osdGetAltitude(void)
{
#if defined(NAV)
return getEstimatedActualPosition(Z);
#elif defined(BARO)
#elif defined(USE_BARO)
return baro.alt;
#else
return 0;
@ -750,7 +750,7 @@ static uint8_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *side
steps = offset / 20;
break;
case OSD_SIDEBAR_SCROLL_GROUND_SPEED:
#if defined(GPS)
#if defined(USE_GPS)
offset = gpsSol.groundSpeed;
#else
offset = 0;
@ -759,7 +759,7 @@ static uint8_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *side
steps = offset / 20;
break;
case OSD_SIDEBAR_SCROLL_HOME_DISTANCE:
#if defined(GPS)
#if defined(USE_GPS)
offset = GPS_distanceToHome;
#else
offset = 0;
@ -840,7 +840,7 @@ static bool osdDrawSingleElement(uint8_t item)
}
break;
#ifdef GPS
#ifdef USE_GPS
case OSD_GPS_SATS:
buff[0] = SYM_SAT_L;
buff[1] = SYM_SAT_R;
@ -1163,7 +1163,7 @@ static bool osdDrawSingleElement(uint8_t item)
return true;
}
#if defined(BARO) || defined(GPS)
#if defined(USE_BARO) || defined(USE_GPS)
case OSD_VARIO:
{
int16_t v = getEstimatedActualVelocity(Z) / 50; //50cm = 1 arrow
@ -1254,7 +1254,7 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_AIR_SPEED:
{
#ifdef PITOT
#ifdef USE_PITOT
buff[0] = SYM_AIR;
osdFormatVelocityStr(buff + 1, pitot.airSpeed);
#else
@ -1582,7 +1582,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
osdDisplayPort = osdDisplayPortToUse;
#ifdef CMS
#ifdef USE_CMS
cmsDisplayPortRegister(osdDisplayPort);
#endif
@ -1593,7 +1593,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
char string_buffer[30];
tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING);
displayWrite(osdDisplayPort, 5, 6, string_buffer);
#ifdef CMS
#ifdef USE_CMS
displayWrite(osdDisplayPort, 7, 7, CMS_STARTUP_HELP_TEXT1);
displayWrite(osdDisplayPort, 11, 8, CMS_STARTUP_HELP_TEXT2);
displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT3);
@ -1784,7 +1784,7 @@ static void osdRefresh(timeUs_t currentTimeUs)
return;
}
#ifdef CMS
#ifdef USE_CMS
if (!displayIsGrabbed(osdDisplayPort)) {
if (fullRedraw) {
displayClearScreen(osdDisplayPort);
@ -1828,7 +1828,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)) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU);

View file

@ -225,7 +225,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
#ifdef CMS
#ifdef USE_CMS
if (cmsInMenu) {
return;
}

View file

@ -52,7 +52,7 @@
#include "msp/msp_serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -286,7 +286,7 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
// MSP & telemetry
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
} else if (telemetryCheckRxPortShared(portConfig)) {
// serial RX & telemetry
#endif
@ -521,7 +521,7 @@ void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar)
}
}
#if defined(GPS) || defined(USE_SERIAL_PASSTHROUGH)
#if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
// Default data consumer for serialPassThrough.
static void nopConsumer(uint8_t data)
{

View file

@ -58,7 +58,7 @@
static serialPort_t *smartAudioSerialPort = NULL;
#if defined(CMS) || defined(VTX_COMMON)
#if defined(USE_CMS) || defined(VTX_COMMON)
static const char * const saPowerNames[] = {
"---", "25 ", "200", "500", "800",
};
@ -328,7 +328,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();

View file

@ -39,7 +39,7 @@
#define TRAMP_SERIAL_OPTIONS (SERIAL_BIDIR)
#if defined(CMS) || defined(VTX_COMMON)
#if defined(USE_CMS) || defined(VTX_COMMON)
const uint16_t trampPowerTable[] = {
25, 100, 200, 400, 600
};
@ -421,7 +421,7 @@ void vtxTrampProcess(uint32_t currentTimeUs)
debug[3] = 0;
#endif
#ifdef CMS
#ifdef USE_CMS
trampCmsUpdateStatusString();
#endif
}

View file

@ -2695,7 +2695,7 @@ bool navigationRTHAllowsLanding(void)
#else // NAV
#ifdef GPS
#ifdef USE_GPS
/* Fallback if navigation is not compiled in - handle GPS home coordinates */
static float GPS_scaleLonDown;
static float GPS_totalTravelDistance = 0;

View file

@ -32,7 +32,7 @@ extern int16_t GPS_directionToHome; // direction to home poin
void onNewGPSData(void);
#if defined(NAV)
#if defined(BLACKBOX)
#if defined(USE_BLACKBOX)
#define NAV_BLACKBOX
#endif

View file

@ -265,7 +265,7 @@ static bool shouldResetReferenceAltitude(void)
return false;
}
#if defined(GPS)
#if defined(USE_GPS)
/* Why is this here: Because GPS will be sending at quiet a nailed rate (if not overloaded by junk tasks at the brink of its specs)
* but we might read out with timejitter because Irq might be off by a few us so we do a +-10% margin around the time between GPS
* datasets representing the most common Hz-rates today. You might want to extend the list or find a smarter way.
@ -441,7 +441,7 @@ void onNewGPSData(void)
}
#endif
#if defined(BARO)
#if defined(USE_BARO)
/**
* Read BARO and update alt/vel topic
* Function is called from TASK_BARO
@ -468,7 +468,7 @@ void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
}
#endif
#if defined(PITOT)
#if defined(USE_PITOT)
/**
* Read Pitot and update airspeed topic
* Function is called at main loop rate, updates happen at reduced rate
@ -783,7 +783,7 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs)
if (useGpsZPos || isBaroValid) {
float gpsWeightScaler = 1.0f;
#if defined(BARO)
#if defined(USE_BARO)
if (isBaroValid) {
/* Apply only baro correction, no sonar */
inavFilterCorrectPos(Z, dt, baroResidual, positionEstimationConfig()->w_z_baro_p);
@ -1084,7 +1084,7 @@ void updatePositionEstimator(void)
const timeUs_t currentTimeUs = micros();
/* Periodic sensor updates */
#if defined(PITOT)
#if defined(USE_PITOT)
updatePitotTopic(currentTimeUs);
#endif

View file

@ -188,7 +188,7 @@ static uint8_t ibusFrameStatus(void)
}
else
{
#if defined(TELEMETRY) && defined(TELEMETRY_IBUS)
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
rxBytesToIgnore = respondToIbusRequest(ibus);
#endif
}
@ -220,7 +220,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = isSerialPortShared(portConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS);
#else
bool portShared = false;
@ -236,7 +236,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0)
);
#if defined(TELEMETRY) && defined(TELEMETRY_IBUS)
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
if (portShared) {
initSharedIbusTelemetry(ibusPort);
}

View file

@ -56,7 +56,7 @@
#include "rx/rx.h"
#include "rx/jetiexbus.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "sensors/sensors.h"
#include "sensors/battery.h"
#include "sensors/barometer.h"
@ -114,7 +114,7 @@ enum exBusHeader_e {
EXBUS_HEADER_DATA
};
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#define EXTEL_DATA_MSG (0x40)
#define EXTEL_UNMASK_TYPE (0x3F)
@ -208,7 +208,7 @@ static uint8_t jetiExBusRequestFrame[EXBUS_MAX_REQUEST_FRAME_SIZE];
static uint16_t jetiExBusChannelData[JETIEXBUS_CHANNEL_COUNT];
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
static uint8_t jetiExBusTelemetryFrame[40];
static uint8_t jetiExBusTransceiveState = EXBUS_TRANS_RX;
@ -235,7 +235,7 @@ uint16_t calcCRC16(uint8_t *pt, uint8_t msgLen)
return(crc16_data);
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
// Jeti Ex Telemetry CRC calculations for a frame
@ -397,7 +397,7 @@ static uint16_t jetiExBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uin
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
/*
-----------------------------------------------
Jeti Ex Bus Telemetry

View file

@ -161,7 +161,7 @@ static bool isPulseValid(uint16_t pulseDuration)
pulseDuration <= rxConfig()->rx_max_usec;
}
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
bool enabled = false;
@ -254,7 +254,7 @@ void rxInit(void)
break;
#endif
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
case RX_TYPE_SERIAL:
if (!serialRxInit(rxConfig(), &rxRuntimeConfig)) {
rxConfigMutable()->receiverType = RX_TYPE_NONE;

View file

@ -242,7 +242,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -257,7 +257,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
SBUS_PORT_OPTIONS | (rxConfig->sbus_inversion ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sBusPort;
}

View file

@ -36,7 +36,7 @@
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -74,7 +74,7 @@ static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
static serialPort_t *serialPort;
#ifdef SPEKTRUM_BIND
#ifdef USE_SPEKTRUM_BIND
static IO_t BindPin = DEFIO_IO(NONE);
#endif
#ifdef HARDWARE_BIND_PLUG
@ -172,7 +172,7 @@ static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint
return data;
}
#ifdef SPEKTRUM_BIND
#ifdef USE_SPEKTRUM_BIND
bool spekShouldBind(uint8_t spektrum_sat_bind)
{
@ -280,7 +280,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -295,7 +295,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = serialPort;
}

View file

@ -175,7 +175,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -190,7 +190,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sumdPort;
}

View file

@ -129,7 +129,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -137,7 +137,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, NULL, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sumhPort;
}

View file

@ -320,7 +320,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -335,7 +335,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = xBusPort;
}

View file

@ -65,16 +65,16 @@ 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 PITOT
#ifdef USE_PITOT
TASK_PITOT,
#endif
#ifdef USE_RANGEFINDER
@ -83,10 +83,10 @@ typedef enum {
#ifdef USE_DASHBOARD
TASK_DASHBOARD,
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
TASK_TELEMETRY,
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
TASK_LEDSTRIP,
#endif
#ifdef USE_PMW_SERVO_DRIVER
@ -95,10 +95,10 @@ typedef enum {
#ifdef STACK_CHECK
TASK_STACK_CHECK,
#endif
#ifdef OSD
#ifdef USE_OSD
TASK_OSD,
#endif
#ifdef CMS
#ifdef USE_CMS
TASK_CMS,
#endif
#ifdef USE_OPTICAL_FLOW

View file

@ -53,7 +53,7 @@ baro_t baro; // barometer access functions
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0);
#ifdef BARO
#ifdef USE_BARO
#define BARO_HARDWARE_DEFAULT BARO_AUTODETECT
#else
#define BARO_HARDWARE_DEFAULT BARO_NONE
@ -63,7 +63,7 @@ PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
.use_median_filtering = 1
);
#ifdef BARO
#ifdef USE_BARO
static timeMs_t baroCalibrationTimeout = 0;
static bool baroCalibrationFinished = false;

View file

@ -62,7 +62,7 @@ mag_t mag; // mag access functions
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 2);
#ifdef MAG
#ifdef USE_MAG
#define MAG_HARDWARE_DEFAULT MAG_AUTODETECT
#else
#define MAG_HARDWARE_DEFAULT MAG_NONE
@ -75,7 +75,7 @@ PG_RESET_TEMPLATE(compassConfig_t, compassConfig,
.magCalibrationTimeLimit = 30
);
#ifdef MAG
#ifdef USE_MAG
static uint8_t magInit = 0;
static uint8_t magUpdatedAtLeastOnce = 0;
@ -138,7 +138,7 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
FALLTHROUGH;
case MAG_GPS:
#ifdef GPS
#ifdef USE_GPS
if (gpsMagDetect(dev)) {
#ifdef MAG_GPS_ALIGN
dev->magAlign = MAG_GPS_ALIGN;

View file

@ -36,7 +36,7 @@ hardwareSensorStatus_e getHwGyroStatus(void)
hardwareSensorStatus_e getHwAccelerometerStatus(void)
{
#if defined(ACC)
#if defined(USE_ACC)
if (detectedSensors[SENSOR_INDEX_ACC] != ACC_NONE) {
if (accIsHealthy()) {
return HW_SENSOR_OK;
@ -62,7 +62,7 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void)
hardwareSensorStatus_e getHwCompassStatus(void)
{
#if defined(MAG)
#if defined(USE_MAG)
if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) {
if (compassIsHealthy()) {
return HW_SENSOR_OK;
@ -88,7 +88,7 @@ hardwareSensorStatus_e getHwCompassStatus(void)
hardwareSensorStatus_e getHwBarometerStatus(void)
{
#if defined(BARO)
#if defined(USE_BARO)
if (detectedSensors[SENSOR_INDEX_BARO] != BARO_NONE) {
if (baroIsHealthy()) {
return HW_SENSOR_OK;
@ -140,7 +140,7 @@ hardwareSensorStatus_e getHwRangefinderStatus(void)
hardwareSensorStatus_e getHwPitotmeterStatus(void)
{
#if defined(PITOT)
#if defined(USE_PITOT)
if (detectedSensors[SENSOR_INDEX_PITOT] != PITOT_NONE) {
if (pitotIsHealthy()) {
return HW_SENSOR_OK;
@ -166,7 +166,7 @@ hardwareSensorStatus_e getHwPitotmeterStatus(void)
hardwareSensorStatus_e getHwGPSStatus(void)
{
#if defined(GPS)
#if defined(USE_GPS)
if (sensors(SENSOR_GPS)) {
if (isGPSHealthy()) {
return HW_SENSOR_OK;

View file

@ -53,17 +53,17 @@ bool sensorsAutodetect(void)
accInit(getAccUpdateRate());
#ifdef BARO
#ifdef USE_BARO
baroInit();
#endif
#ifdef PITOT
#ifdef USE_PITOT
pitotInit();
#endif
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
mag.magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
#ifdef MAG
#ifdef USE_MAG
compassInit();
#endif
@ -80,21 +80,21 @@ bool sensorsAutodetect(void)
eepromUpdatePending = true;
}
#ifdef BARO
#ifdef USE_BARO
if (barometerConfig()->baro_hardware == BARO_AUTODETECT) {
barometerConfigMutable()->baro_hardware = detectedSensors[SENSOR_INDEX_BARO];
eepromUpdatePending = true;
}
#endif
#ifdef MAG
#ifdef USE_MAG
if (compassConfig()->mag_hardware == MAG_AUTODETECT) {
compassConfigMutable()->mag_hardware = detectedSensors[SENSOR_INDEX_MAG];
eepromUpdatePending = true;
}
#endif
#ifdef PITOT
#ifdef USE_PITOT
if (pitotmeterConfig()->pitot_hardware == PITOT_AUTODETECT) {
pitotmeterConfigMutable()->pitot_hardware = detectedSensors[SENSOR_INDEX_PITOT];
eepromUpdatePending = true;

View file

@ -44,7 +44,7 @@
pitot_t pitot;
#ifdef PITOT
#ifdef USE_PITOT
static timeMs_t pitotCalibrationTimeout = 0;
static bool pitotCalibrationFinished = false;
@ -55,7 +55,7 @@ static float indicatedAirspeed = 0;
PG_REGISTER_WITH_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_PITOTMETER_CONFIG, 0);
#ifdef PITOT
#ifdef USE_PITOT
#define PITOT_HARDWARE_DEFAULT PITOT_AUTODETECT
#else
#define PITOT_HARDWARE_DEFAULT PITOT_NONE

View file

@ -36,7 +36,7 @@
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define MPU6000_CS_PIN PA4
@ -47,14 +47,14 @@
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883
@ -62,7 +62,7 @@
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP085
#define USE_BARO_BMP280
@ -126,7 +126,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 5 (PA1) of the MOTOR outputs.
#define WS2811_GPIO_AF GPIO_AF_TIM5
#define WS2811_PIN PA1
@ -142,7 +142,7 @@
#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_VBAT)
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 // USART3 RX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -40,15 +40,15 @@
#define BMP280_SPI_BUS BUS_SPI2
#define BMP280_CS_PIN PB5
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW0_DEG
#define BARO
#define USE_BARO
#define USE_BARO_BMP280
#define USE_PITOT_MS4525
@ -85,7 +85,7 @@
/*
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_TIMER TIM3
#define WS2811_PIN PA6
#define WS2811_DMA_CHANNEL DMA1_Channel6
@ -107,7 +107,7 @@
#define I2C1_SDA PB9
// MAG is I2C, so it is only useful when I2C is available
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -122,7 +122,7 @@
#define USABLE_TIMER_CHANNEL_COUNT 12
#endif
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11

View file

@ -39,7 +39,7 @@
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// Using MPU6050 for the moment.
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6050
#define MPU6050_I2C_BUS BUS_I2C2
@ -53,7 +53,7 @@
#define MPU9250_CS_PIN PA15
#define MPU9250_SPI_BUS BUS_SPI3
#define ACC
#define USE_ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define USE_ACC_MPU6500
@ -62,11 +62,11 @@
#define ACC_MPU9250_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 MAG_I2C_BUS BUS_I2C2
#define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW180_DEG_FLIP
@ -111,7 +111,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define VBAT_SCALE_DEFAULT 20
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3

View file

@ -46,19 +46,19 @@
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW270_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_MPU9250
@ -66,7 +66,7 @@
#define MAG_MPU9250_ALIGN CW180_DEG_FLIP
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define USE_BARO_BMP280
@ -163,7 +163,7 @@
//#define BOARD_HAS_CURRENT_SENSOR
// LED strip configuration using RC1 pin.
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 41 (PA8) of the ESC outputs.
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
@ -173,7 +173,7 @@
#define WS2811_DMA_CHANNEL DMA_Channel_6
#define WS2811_TIMER_CHANNEL TIM_Channel_1
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN UART2_RX_PIN

View file

@ -43,19 +43,19 @@
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW270_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8963
#define USE_MAG_MPU9250
@ -68,7 +68,7 @@
#define AK8963_CS_PIN PC15
#define AK8963_SPI_BUS BUS_SPI3
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define USE_BARO_BMP280
@ -170,7 +170,7 @@
//#define BOARD_HAS_CURRENT_SENSOR
// LED strip configuration using RC1 pin.
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 41 (PA8) of the ESC outputs.
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
@ -181,7 +181,7 @@
#define WS2811_TIMER_CHANNEL TIM_CHANNEL_1
#define WS2811_TIMER_GPIO_AF GPIO_AF1_TIM1
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN UART2_RX_PIN

View file

@ -32,11 +32,11 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
@ -46,7 +46,7 @@
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -57,7 +57,7 @@
#define USE_RANGEFINDER_VL53L0X
#define VL53L0X_I2C_BUS BUS_I2C2
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
@ -115,7 +115,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 6 (PA0) of the ESC outputs.
#define WS2811_PIN PA0
#define WS2811_TIMER TIM5

View file

@ -30,11 +30,11 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
@ -43,13 +43,13 @@
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define BARO
#define USE_BARO
#ifdef ANYFCF7_EXTERNAL_BARO
#define BARO_I2C_BUS BUS_I2C2
@ -124,7 +124,7 @@
#define SPI4_MISO_PIN PE13
#define SPI4_MOSI_PIN PE14
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN SPI3_NSS_PIN
@ -172,7 +172,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 6 (PA0) of the ESC outputs.
#define WS2811_PIN PA1

View file

@ -30,11 +30,11 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
@ -43,13 +43,13 @@
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
@ -114,7 +114,7 @@
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN SPI3_NSS_PIN

View file

@ -36,26 +36,26 @@
#define MPU6500_CS_PIN SPI1_NSS_PIN
#define MPU6500_SPI_BUS BUS_SPI1
#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 BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN SPI3_NSS_PIN
@ -140,7 +140,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_GPIO_AF GPIO_AF_TIM4
#define WS2811_PIN PB8
#define WS2811_TIMER TIM4

View file

@ -44,21 +44,21 @@
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW0_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW0_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MAG3110
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP085
#define USE_BARO_BMP280
@ -137,7 +137,7 @@
#define ADC_CHANNEL_1_PIN PC3
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 6 (PB1) of the ESC outputs.
#define WS2811_PIN PB1
#define WS2811_TIMER TIM3
@ -157,7 +157,7 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11
// Number of available PWM outputs

View file

@ -45,22 +45,22 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// External I2C BARO
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define USE_BARO_BMP280
// External I2C MAG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -148,13 +148,13 @@
#define RSSI_ADC_CHANNEL ADC_CHN_3
// LED strip is on PWM5 output pin
//#define LED_STRIP
//#define USE_LED_STRIP
#define WS2811_PIN PB4
#define WS2811_TIMER TIM3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3, PB11 (Flexport)
#define BIND_PIN PB11
@ -168,7 +168,7 @@
//#define NAV_AUTO_MAG_DECLINATION
//#define NAV_GPS_GLITCH_DETECTION
#undef BLACKBOX
#undef USE_BLACKBOX
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DISABLE_UNCOMMON_MIXERS
@ -176,8 +176,8 @@
#ifdef USE_RX_NRF24
#undef USE_RX_PWM
#undef USE_RX_PPM
#undef SERIAL_RX
#undef SPEKTRUM_BIND
#undef USE_SERIAL_RX
#undef USE_SPEKTRUM_BIND
#endif
#define TARGET_MOTOR_COUNT 4
@ -196,10 +196,10 @@
//#define USE_FAKE_BARO
//#define USE_FAKE_GPS
//#undef TELEMETRY_FRSKY
//#define TELEMETRY_MAVLINK
//#undef USE_TELEMETRY_FRSKY
//#define USE_TELEMETRY_MAVLINK
//#define USE_SERIALRX_SUMD
//#define TELEMETRY_HOTT
//#define USE_TELEMETRY_HOTT
// CC3D is widely used for airplanes - enable fw_autotune
#define AUTOTUNE_FIXED_WING

View file

@ -29,7 +29,7 @@
#define USE_SPI
#define USE_SPI_DEVICE_1
#define GYRO
#define USE_GYRO
#define USE_GYRO_L3GD20
#define USE_GYRO_MPU6050
@ -41,16 +41,16 @@
#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 ACC_MPU6050_ALIGN CW0_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8975
#define USE_MAG_QMC5883

View file

@ -26,13 +26,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 USE_UART1
@ -81,19 +81,19 @@
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M
#define DEFAULT_RX_TYPE RX_TYPE_SPI
//#define TELEMETRY
//#define TELEMETRY_LTM
//#define USE_TELEMETRY
//#define USE_TELEMETRY_LTM
//#define TELEMETRY_NRF24_LTM
#undef USE_RX_PWM
#undef USE_RX_PPM
#undef SERIAL_RX
#undef USE_SERIAL_RX
#undef SKIP_TASK_STATISTICS
#else
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define USE_RX_MSP
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // UART2, PA3
#endif //USE_RX_NRF24

View file

@ -29,23 +29,23 @@
// MPU-6000 GRYO
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW0_DEG
//MPU-9250
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW0_DEG
#define MAG
#define USE_MAG
#define USE_MAG_MPU9250
// MPU6 interrupts
@ -53,13 +53,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_BUS BUS_SPI3
#define BMP280_CS_PIN PB3
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15

View file

@ -41,10 +41,10 @@
#define MPU6000_CS_PIN PC4
#define MPU6000_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
// MPU6000 interrupts
@ -52,7 +52,7 @@
#define MPU_INT_EXTI PC0
#define USE_MPU_DATA_READY_SIGNAL
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C3
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -67,7 +67,7 @@
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#endif
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C3
#define USE_BARO_MS5611
@ -154,4 +154,4 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(10) | TIM_N(11))
#undef PITOT
#undef USE_PITOT

View file

@ -49,7 +49,7 @@
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define USE_GYRO_MPU6500
@ -57,7 +57,7 @@
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define USE_ACC_MPU6500
@ -65,11 +65,11 @@
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW270_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_MAG9250
#define USE_MAG_HMC5883
@ -108,7 +108,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_DMA_STREAM DMA1_Channel3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3

View file

@ -25,16 +25,16 @@
#define LED1 PA8
#define LED2 PB1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6050
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6050
#define BARO
#define USE_BARO
#define USE_BARO_MS5611
//#define MAG
//#define USE_MAG
//#define USE_MAG_HMC5883
#define USE_UART1
@ -73,8 +73,8 @@
#undef USE_SERIAL_PASSTHROUGH
#undef USE_RX_PWM
#undef USE_RX_PPM
#undef SERIAL_RX
#undef BLACKBOX
#undef USE_SERIAL_RX
#undef USE_BLACKBOX
#define DEFAULT_RX_TYPE RX_TYPE_SPI

View file

@ -31,7 +31,7 @@
#define MPU6500_CS_PIN PB12
#define MPU6500_SPI_INSTANCE SPI2
#define GYRO
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_L3G4200D
//#define USE_GYRO_L3GD20
@ -42,7 +42,7 @@
#define GYRO_MPU6050_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_ADXL345
//#define USE_ACC_BMA280
@ -53,12 +53,12 @@
#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 USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
@ -99,7 +99,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3

View file

@ -39,21 +39,21 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW90_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611

View file

@ -37,19 +37,19 @@
#define MPU_INT_EXTI PB0
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW0_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5607
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
@ -109,7 +109,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define LED_STRIP
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_PIN PA8
#define WS2811_DMA_STREAM DMA1_Channel2
@ -123,7 +123,7 @@
#define M25P16_SPI_INSTANCE SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PA3
#define BIND_PIN PA3

View file

@ -38,28 +38,28 @@
#define MPU9250_CS_PIN PC0
#define MPU9250_SPI_BUS BUS_SPI3
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW180_DEG
#define MAG
#define USE_MAG
#define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW180_DEG
#define BARO
#define USE_BARO
#define USE_BARO_MS5611
#define MS5611_CS_PIN PC5
#define MS5611_SPI_BUS BUS_SPI3
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_CS_PIN PA4
#define MAX7456_SPI_BUS BUS_SPI1

View file

@ -41,13 +41,13 @@
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_BUS BUS_SPI1
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define USE_ACC_MPU9250
#define GYRO_MPU9250_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define USE_GYRO_MPU9250
@ -60,7 +60,7 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
// *************** Compass *****************************
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MPU9250
#define USE_MAG_MAG3110
@ -70,7 +70,7 @@
#define MAG_IST8310_ALIGN CW270_DEG
// *************** BARO *****************************
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
@ -81,7 +81,7 @@
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
@ -132,7 +132,7 @@
#define SERIAL_PORT_COUNT 4 // VCP, USART1, USART2, USART5
// *************** WS2811 *****************************
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PB1
#define WS2811_TIMER TIM3
#define WS2811_TIMER_CHANNEL TIM_Channel_4

View file

@ -29,8 +29,8 @@
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_ADDRESS 0x69
#define GYRO
#define ACC
#define USE_GYRO
#define USE_ACC
#define MPU6050_I2C_BUS BUS_I2C1
@ -64,7 +64,7 @@
#define I2C1_SDA PB7
#define USE_SPI
#define OSD
#define USE_OSD
// include the max7456 driver
#define USE_MAX7456

View file

@ -28,11 +28,11 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
@ -40,12 +40,12 @@
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define BARO
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI3
#define BMP280_CS_PIN PB3
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15

View file

@ -38,7 +38,7 @@
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG // changedkb 270
#define USE_GYRO_MPU6500
@ -46,7 +46,7 @@
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW90_DEG // changedkb 270
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG // changedkb 270
#define USE_ACC_MPU6500
@ -54,14 +54,14 @@
#define USE_ACC_MPU9250
#define ACC_MPU9250_ALIGN CW90_DEG // changedkb 270
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MPU9250
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
#define USE_BARO_BMP280
@ -146,7 +146,7 @@
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
@ -163,7 +163,7 @@
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// UART3,
#define BIND_PIN PB11

View file

@ -37,15 +37,15 @@
#define MPU6000_CS_PIN PB5
#define MPU6000_SPI_BUS BUS_SPI2
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW90_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -65,12 +65,12 @@
#define M25P16_SPI_INSTANCE SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define BARO
#define USE_BARO
#define USE_BARO_MS5611
#define MS5611_SPI_BUS BUS_SPI2
#define MS5611_CS_PIN PB2
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PA7
@ -122,7 +122,7 @@
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define WS2811_DMA_STREAM DMA1_Channel2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER

View file

@ -39,21 +39,21 @@
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PA4
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW90_DEG_FLIP
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG_FLIP
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C3
#define USE_BARO_MS5611
@ -68,7 +68,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
@ -141,7 +141,7 @@
#define RX_CHANNELS_TAER
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_GPIO_AF GPIO_AF_TIM3
#define WS2811_PIN PC6
#define WS2811_TIMER TIM3

View file

@ -48,13 +48,13 @@
#define MPU9250_CS_PIN SPI1_NSS_PIN
#define MPU9250_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
#define USE_GYRO_MPU9250
#define GYRO_MPU9250_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define USE_ACC_MPU9250
@ -90,14 +90,14 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PA6 // TIM16_CH1
#define WS2811_DMA_STREAM DMA1_Channel3
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART1, PC5
#define BIND_PIN PC5

View file

@ -42,11 +42,11 @@
#define MPU_INT_EXTI PC3
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
@ -73,7 +73,7 @@
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB10
@ -132,13 +132,13 @@
#endif
#define BARO
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define MAG
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_MAG3110 // External
#define USE_MAG_HMC5883 // External
@ -157,13 +157,13 @@
#define DEFAULT_FEATURES (FEATURE_OSD )
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PA15 // S5 pad for iNav
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream5
#define WS2811_DMA_CHANNEL DMA_Channel_3 // ???
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA1 // USART4 RX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -30,11 +30,11 @@
#define MPU_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#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
@ -47,10 +47,10 @@
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI2
//#define BARO
//#define USE_BARO
//#define USE_BARO_MS5611
//#define MAG
//#define USE_MAG
//#define USE_MAG_HMC5883
#define USB_IO
@ -94,7 +94,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define LED_STRIP
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PB8 // TIM16_CH1
@ -105,17 +105,17 @@
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART2, PB4
#define BIND_PIN PB4
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
//#undef GPS
#undef GPS_PROTO_NMEA
//#undef GPS_PROTO_UBLOX
#undef GPS_PROTO_I2C_NAV
#undef GPS_PROTO_NAZA
//#undef USE_GPS
#undef USE_GPS_PROTO_NMEA
//#undef USE_GPS_PROTO_UBLOX
#undef USE_GPS_PROTO_I2C_NAV
#undef USE_GPS_PROTO_NAZA
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 8

View file

@ -82,25 +82,25 @@
#define USE_FLASH_M25P16
#endif
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6050
#define USE_GYRO_MPU6500
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6050
#define USE_ACC_MPU6500
#define ACC_MPU6050_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 USE_MAG_QMC5883
#define MAG_HMC5883_ALIGN CW180_DEG
@ -176,14 +176,14 @@
//#define NAV_AUTO_MAG_DECLINATION
//#define NAV_GPS_GLITCH_DETECTION
// #define LED_STRIP
// #define USE_LED_STRIP
// #define WS2811_PIN PA6
// #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
// #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
#undef USE_SERIALRX_SPEKTRUM
#undef USE_SERIALRX_IBUS
//#define SPEKTRUM_BIND
//#define USE_SPEKTRUM_BIND
//#define BIND_PIN PA3
//#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -31,22 +31,22 @@
#define LED1 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#endif
#define GYRO
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
#define ACC
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
#define MPU6050_I2C_BUS BUS_I2C2
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883

View file

@ -34,7 +34,7 @@
#define USE_EXTI
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PA4
@ -42,11 +42,11 @@
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO_MPU6000_ALIGN CW90_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW90_DEG
#define BARO
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI1
#define BMP280_CS_PIN PA13
@ -56,7 +56,7 @@
#define USE_BARO_BMP180 // External
#define USE_BARO_MS5611 // External
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883 // External
#define USE_MAG_MAG3110 // External
@ -123,7 +123,7 @@
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI1
#define MAX7456_CS_PIN PB1
@ -139,7 +139,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define WS2811_DMA_STREAM DMA1_Channel2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
@ -155,7 +155,7 @@
#define BUTTON_B_PORT GPIOB // TRIG button, used for BINDPLUG_PIN
#define BUTTON_B_PIN Pin_0
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3
#define BIND_PIN PB11

View file

@ -56,8 +56,8 @@
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define ACC
#define USE_GYRO
#define USE_ACC
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
@ -88,14 +88,14 @@
#define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN
#endif
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define BARO
#define USE_BARO
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
#define USE_BARO_BMP280
@ -165,7 +165,7 @@
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15
@ -208,7 +208,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define LED_STRIP
#define USE_LED_STRIP
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5)
# define WS2811_PIN PB6
# define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST0_HANDLER
@ -225,7 +225,7 @@
#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 // USART3 RX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -31,8 +31,8 @@
#define BEEPER PD15
#define BEEPER_INVERTED
#define ACC
#define GYRO
#define USE_ACC
#define USE_GYRO
#define USE_DUAL_GYRO
// ICM-20608-G
@ -141,7 +141,7 @@
#define SPI4_MOSI_PIN PE6
#define OSD
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
@ -166,12 +166,12 @@
#define I2C_DEVICE (I2CDEV_2)
#define I2C_DEVICE_SHARES_UART3
#define BARO
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI1
#define BMP280_CS_PIN PA1
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
@ -188,7 +188,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// #define LED_STRIP
// #define USE_LED_STRIP
//Following configuration needs to be reviewed, when LED is enabled, VCP stops to work
//Until someone with deeper knowledge od DMA fixes it, LED are disabled in target

View file

@ -33,11 +33,11 @@
#define MPU_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
@ -65,9 +65,9 @@
#define SENSORS_SET (SENSOR_ACC)
#define TELEMETRY
#define BLACKBOX
#define SERIAL_RX
#define USE_TELEMETRY
#define USE_BLACKBOX
#define USE_SERIAL_RX
#define USE_SERVOS
#define BOARD_HAS_VOLTAGE_DIVIDER
@ -80,7 +80,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
//#define LED_STRIP
//#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PB8 // TIM16_CH1
#define WS2811_TIMER TIM16
@ -102,7 +102,7 @@
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3, PB11
#define BIND_PIN PB11

View file

@ -61,16 +61,16 @@
#define MPU9250_EXTI_PIN PD15
#define MPU9250_SPI_BUS BUS_SPI1
#define ACC
#define GYRO
#define USE_ACC
#define USE_GYRO
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_MPU9250
#define USE_MAG_QMC5883
#define USE_MAG_HMC5883
#define BARO
#define USE_BARO
#define USE_BARO_MS5611
#define MS5611_CS_PIN PD7
#define MS5611_SPI_BUS BUS_SPI2

View file

@ -47,7 +47,7 @@
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE
#define GYRO
#define USE_GYRO
#define USE_FAKE_GYRO
//#define USE_GYRO_L3G4200D
//#define USE_GYRO_L3GD20
@ -56,7 +56,7 @@
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
#define ACC
#define USE_ACC
#define USE_FAKE_ACC
//#define USE_ACC_ADXL345
//#define USE_ACC_BMA280
@ -65,12 +65,12 @@
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
//#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 USE_MAG_AK8975

View file

@ -29,22 +29,22 @@
#define MPU_INT_EXTI PA15
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI2
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_MS5611
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883 // External
#define USE_MAG_QMC5883 // External
@ -90,7 +90,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP // LED strip configuration using PWM motor output pin 5.
#define USE_LED_STRIP // LED strip configuration using PWM motor output pin 5.
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_PIN PB8 // TIM16_CH1
#define WS2811_DMA_STREAM DMA1_Channel3
@ -108,7 +108,7 @@
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // USART3,
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -43,15 +43,15 @@
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define GYRO
#define USE_GYRO
#define USE_GYRO_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC
#define USE_ACC_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define MAG
#define USE_MAG
#define USE_DUAL_MAG
#define MAG_I2C_BUS_EXT BUS_I2C2
#define MAG_I2C_BUS_INT BUS_I2C1
@ -60,7 +60,7 @@
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_MS5611
@ -127,7 +127,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define LED_STRIP
#define USE_LED_STRIP
// LED Strip can run off Pin 5 (PA1) of the MOTOR outputs.
#define WS2811_PIN PA1
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER
@ -141,7 +141,7 @@
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 //UART3_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -28,8 +28,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 USE_ACC_MPU6050
@ -38,11 +38,11 @@
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC_MPU6050_ALIGN CW270_DEG
#define BARO
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define MAG
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
@ -98,7 +98,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define LED_STRIP
#define USE_LED_STRIP
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_PIN PA8
@ -108,16 +108,16 @@
#undef NAV_MAX_WAYPOINTS
#define NAV_MAX_WAYPOINTS 30
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#undef GPS_PROTO_NAZA
#undef TELEMETRY_HOTT
#undef TELEMETRY_SMARTPORT
#undef TELEMETRY_IBUS
#undef USE_GPS_PROTO_NAZA
#undef USE_TELEMETRY_HOTT
#undef USE_TELEMETRY_SMARTPORT
#undef USE_TELEMETRY_IBUS
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 12

Some files were not shown because too many files have changed in this diff Show more