1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Converted more 'feature' type defines to use the 'USE_<x>' convention: LED_STRIP TARGET_CONFIG BRUSHED_ESC_AUTODETECT SERIAL_RX TELEMETRY TELEMETRY_CRSF TELEMETRY_FRSKY TELEMETRY_HOTT TELEMETRY_IBUS TELEMETRY_JETIEXBUS TELEMETRY_LTM TELEMETRY_MAVLINK TELEMETRY_SMARTPORT TELEMETRY_SRXL TELEMETRY_NRF24_LTM TELEMETRY_LTM SPEKTRUM_BIND NAV BUTTONS

This commit is contained in:
mikeller 2017-11-06 23:28:43 +13:00
parent cd2fc5254d
commit b78d8ad83e
140 changed files with 300 additions and 308 deletions

View file

@ -109,7 +109,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},

View file

@ -37,7 +37,7 @@
#include "fc/config.h"
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
static bool featureRead = false;
static uint8_t cmsx_FeatureLedstrip;

View file

@ -25,7 +25,7 @@
#include "drivers/buttons.h"
#if defined(BUTTONS)
#if defined(USE_BUTTONS)
#ifdef BUTTON_A_PIN
static IO_t buttonAPin = IO_NONE;

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 "build/debug.h"

View file

@ -29,7 +29,7 @@
#include "pwm_esc_detect.h"
#include "timer.h"
#ifdef BRUSHED_ESC_AUTODETECT
#ifdef USE_BRUSHED_ESC_AUTODETECT
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
void detectBrushedESC(void)

View file

@ -16,7 +16,7 @@
*/
#pragma once
#ifdef BRUSHED_ESC_AUTODETECT
#ifdef USE_BRUSHED_ESC_AUTODETECT
typedef enum {
MOTOR_UNKNOWN = 0,
MOTOR_BRUSHED,

View file

@ -96,7 +96,7 @@ typedef struct timerHardware_s {
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
uint8_t alternateFunction;
#endif
#if defined(USE_DSHOT) || defined(LED_STRIP) || defined(TRANSPONDER)
#if defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(TRANSPONDER)
#if defined(STM32F4) || defined(STM32F7)
DMA_Stream_TypeDef *dmaRef;
uint32_t dmaChannel;

View file

@ -22,7 +22,7 @@
#include "common/utils.h"
// allow conditional definition of DMA related members
#if defined(USE_DSHOT) || defined(LED_STRIP) || defined(TRANSPONDER)
#if defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(TRANSPONDER)
# define DEF_TIM_DMA_COND(...) __VA_ARGS__
#else
# define DEF_TIM_DMA_COND(...)

View file

@ -1226,7 +1226,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";
@ -3135,7 +3135,7 @@ const cliResourceValue_t resourceTable[] = {
{ OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 },
{ OWNER_SONAR_ECHO, PG_SONAR_CONFIG, offsetof(sonarConfig_t, echoTag), 0 },
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
{ OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ioTag), 0 },
#endif
{ OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, offsetof(serialPinConfig_t, ioTagTx[0]), SERIAL_PORT_MAX_INDEX },
@ -3440,7 +3440,7 @@ static void printConfig(char *cmdline, bool doDiff)
// reset all configs to defaults to do differencing
resetConfigs();
#if defined(TARGET_CONFIG)
#if defined(USE_TARGET_CONFIG)
targetConfiguration();
#endif
if (checkCommand(options, "defaults")) {
@ -3501,7 +3501,7 @@ static void printConfig(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);
@ -3615,7 +3615,7 @@ const clicmd_t cmdTable[] = {
"\t<+|->[name]", cliBeeper),
#endif
CLI_COMMAND_DEF("bl", "reboot into bootloader", NULL, cliBootloader),
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
#endif
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave]", cliDefaults),
@ -3649,7 +3649,7 @@ const clicmd_t cmdTable[] = {
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),
@ -3657,7 +3657,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("mixer", "configure mixer", "list\r\n\t<name>", cliMixer),
#endif
CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
#endif
CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor),

View file

@ -285,7 +285,7 @@ void resetConfigs(void)
{
pgResetAll();
#if defined(TARGET_CONFIG)
#if defined(USE_TARGET_CONFIG)
targetConfiguration();
#endif
@ -294,7 +294,7 @@ void resetConfigs(void)
setControlRateProfile(0);
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
reevaluateLedConfig();
#endif
}
@ -432,7 +432,7 @@ static void validateAndFixConfig(void)
featureClear(FEATURE_RX_PPM);
#endif
#ifndef SERIAL_RX
#ifndef USE_SERIAL_RX
featureClear(FEATURE_RX_SERIAL);
#endif
@ -448,7 +448,7 @@ static void validateAndFixConfig(void)
featureClear(FEATURE_SONAR);
#endif
#ifndef TELEMETRY
#ifndef USE_TELEMETRY
featureClear(FEATURE_TELEMETRY);
#endif
@ -460,7 +460,7 @@ static void validateAndFixConfig(void)
featureClear(FEATURE_RX_MSP);
#endif
#ifndef LED_STRIP
#ifndef USE_LED_STRIP
featureClear(FEATURE_LED_STRIP);
#endif

View file

@ -552,7 +552,7 @@ void processRx(timeUs_t currentTimeUs)
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY)) {
if ((!telemetryConfig()->telemetry_switch && ARMING_FLAG(ARMED)) ||
(telemetryConfig()->telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {

View file

@ -260,7 +260,7 @@ void init(void)
detectHardwareRevision();
#endif
#ifdef BRUSHED_ESC_AUTODETECT
#ifdef USE_BRUSHED_ESC_AUTODETECT
detectBrushedESC();
#endif
@ -296,7 +296,7 @@ void init(void)
EXTIInit();
#endif
#if defined(BUTTONS)
#if defined(USE_BUTTONS)
buttonsInit();
@ -603,7 +603,7 @@ void init(void)
}
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
ledStripInit();
if (feature(FEATURE_LED_STRIP)) {
@ -611,7 +611,7 @@ void init(void)
}
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY)) {
telemetryInit();
}

View file

@ -1061,7 +1061,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
}
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];
@ -1917,7 +1917,7 @@ static mspResult_e mspProcessInCommand(uint8_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

@ -201,7 +201,7 @@ void initActiveBoxIds(void)
BME(BOXBEEPERON);
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
if (feature(FEATURE_LED_STRIP)) {
BME(BOXLEDLOW);
}
@ -235,7 +235,7 @@ void initActiveBoxIds(void)
BME(BOXOSD);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY) && telemetryConfig()->telemetry_switch) {
BME(BOXTELEMETRY);
}

View file

@ -196,7 +196,7 @@ static void taskCalculateAltitude(timeUs_t currentTimeUs)
}}
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
static void taskTelemetry(timeUs_t currentTimeUs)
{
telemetryCheckState();
@ -299,7 +299,7 @@ void fcTasksInit(void)
#ifdef USE_DASHBOARD
setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD));
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
if (feature(FEATURE_TELEMETRY)) {
if (rxConfig()->serialrx_provider == SERIALRX_JETIEXBUS) {
@ -311,7 +311,7 @@ void fcTasksInit(void)
}
}
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
#endif
#ifdef TRANSPONDER
@ -526,7 +526,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
[TASK_TELEMETRY] = {
.taskName = "TELEMETRY",
.taskFunc = taskTelemetry,
@ -535,7 +535,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
[TASK_LEDSTRIP] = {
.taskName = "LEDSTRIP",
.taskFunc = ledStripUpdate,

View file

@ -168,7 +168,7 @@ static const char * const lookupTableBlackboxMode[] = {
};
#endif
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
static const char * const lookupTableSerialRX[] = {
"SPEK1024",
"SPEK2048",
@ -282,7 +282,7 @@ const lookupTableEntry_t lookupTables[] = {
#ifdef USE_SERVOS
{ lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
#endif
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
{ lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
#endif
#ifdef USE_RX_SPI
@ -390,7 +390,7 @@ const clivalue_t valueTable[] = {
{ "rc_interp_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolationInterval) },
{ "fpv_mix_degrees", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, fpvCamAngleDegrees) },
{ "max_aux_channels", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, MAX_AUX_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, max_aux_channel) },
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
{ "serialrx_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_inverted) },
#endif
@ -641,11 +641,11 @@ const clivalue_t valueTable[] = {
#endif
// PG_TELEMETRY_CONFIG
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
{ "tlm_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_switch) },
{ "tlm_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inverted) },
{ "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) },
#if defined(TELEMETRY_FRSKY)
#if defined(USE_TELEMETRY_FRSKY)
#if defined(USE_GPS)
{ "frsky_default_lat", VAR_INT16 | MASTER_VALUE, .config.minmax = { -9000, 9000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) },
{ "frsky_default_long", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) },
@ -656,13 +656,13 @@ const clivalue_t valueTable[] = {
#endif
{ "hott_alarm_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 120 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, hottAlarmSoundInterval) },
{ "pid_in_tlm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = {TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, pidValuesAsTelemetry) },
#if defined(TELEMETRY_IBUS)
#if defined(USE_TELEMETRY_IBUS)
{ "report_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, report_cell_voltage) },
#endif
#endif
// PG_LED_STRIP_CONFIG
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ledstrip_visual_beeper) },
#endif

View file

@ -39,7 +39,7 @@ typedef enum {
#ifdef USE_SERVOS
TABLE_GIMBAL_MODE,
#endif
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
TABLE_SERIAL_RX,
#endif
#ifdef USE_RX_SPI

View file

@ -75,7 +75,7 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->dev.useUnsyncedPwm = true;
#else
#ifdef BRUSHED_ESC_AUTODETECT
#ifdef USE_BRUSHED_ESC_AUTODETECT
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfig->minthrottle = 1000;
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;

View file

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

View file

@ -54,7 +54,7 @@
#include "msp/msp_serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -258,7 +258,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction
return NULL;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | TELEMETRY_PORT_FUNCTIONS_MASK)
#else
#define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX)
@ -294,7 +294,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

View file

@ -260,7 +260,7 @@ void init(void)
osdSlaveInit(osdDisplayPort);
#endif
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
ledStripInit();
if (feature(FEATURE_LED_STRIP)) {

View file

@ -22,7 +22,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "build/build_config.h"
#include "build/debug.h"

View file

@ -88,7 +88,7 @@ static int16_t RSSI_dBm;
static uint8_t telemetry_id;
static uint32_t telemetryTime;
#if defined(TELEMETRY_FRSKY)
#if defined(USE_TELEMETRY_FRSKY)
#define MAX_SERIAL_BYTES 64
static uint8_t hub_index;
static uint8_t idxx = 0;
@ -136,7 +136,7 @@ static void compute_RSSIdbm(uint8_t *packet)
processRssi(constrain((RSSI_dBm << 3) / 10, 0, 100));
}
#if defined(TELEMETRY_FRSKY)
#if defined(USE_TELEMETRY_FRSKY)
static uint8_t frsky_append_hub_data(uint8_t *buf)
{
if (telemetry_id == telemetry_expected_id)
@ -183,7 +183,7 @@ static void telemetry_build_frame(uint8_t *packet)
frame[3] = (uint8_t)((adcExternal1Sample & 0xff0) >> 4); // A1
frame[4] = (uint8_t)((adcRssiSample & 0xff0) >> 4); // A2
frame[5] = (uint8_t)RSSI_dBm;
#if defined(TELEMETRY_FRSKY)
#if defined(USE_TELEMETRY_FRSKY)
bytes_used = frsky_append_hub_data(&frame[8]);
#endif
frame[6] = bytes_used;
@ -714,7 +714,7 @@ static void frskyD_Rx_Setup(rx_spi_protocol_e protocol)
RX_enable();
#endif
#if defined(TELEMETRY_FRSKY)
#if defined(USE_TELEMETRY_FRSKY)
initFrSkyExternalTelemetry(&frSkyTelemetryInitFrameSpi,
&frSkyTelemetryWriteSpi);
#endif

View file

@ -27,7 +27,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "common/utils.h"
@ -37,7 +37,7 @@
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -171,7 +171,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
}
@ -204,7 +204,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
return false;
}
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
// bool portShared = telemetryCheckRxPortShared(portConfig);
bool portShared = isSerialPortShared(portConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS);
#else
@ -221,7 +221,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (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

@ -39,7 +39,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "build/build_config.h"
#include "build/debug.h"

View file

@ -276,7 +276,7 @@ static void writeAckPayload(const uint8_t *data, uint8_t length)
static void writeTelemetryAckPayload(void)
{
#ifdef TELEMETRY_NRF24_LTM
#ifdef USE_TELEMETRY_NRF24_LTM
// set up telemetry data, send back telemetry data in the ACK packet
static uint8_t sequenceNumber = 0;
static ltm_frame_e ltmFrameType = LTM_FRAME_START;

View file

@ -223,7 +223,7 @@ STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, bool valid)
}
}
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
bool enabled = false;
@ -315,7 +315,7 @@ void rxInit(void)
}
}
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) {
const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig);
if (!enabled) {

View file

@ -21,7 +21,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "common/utils.h"
@ -29,7 +29,7 @@
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
#include "rx/rx.h"
@ -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;
@ -256,7 +256,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sBusPort;
}

View file

@ -22,7 +22,7 @@
#include "platform.h"
#include "common/maths.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "build/debug.h"
@ -38,7 +38,7 @@
#include "fc/config.h"
#include "fc/fc_dispatch.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -527,7 +527,7 @@ void spektrumBind(rxConfig_t *rxConfig)
// Take care half-duplex case
switch (rxConfig->serialrx_provider) {
case SERIALRX_SRXL:
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (feature(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) {
bindPin = txPin;
}
@ -602,7 +602,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
}
srxlEnabled = false;
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig);
#else
bool portShared = false;
@ -610,7 +610,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
switch (rxConfig->serialrx_provider) {
case SERIALRX_SRXL:
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared);
#endif
case SERIALRX_SPEKTRUM2048:
@ -644,7 +644,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | ((srxlEnabled || rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = serialPort;
}

View file

@ -21,7 +21,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "common/utils.h"
@ -29,7 +29,7 @@
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -173,7 +173,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;
@ -187,7 +187,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sumdPort;
}

View file

@ -27,7 +27,7 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "common/utils.h"
@ -35,7 +35,7 @@
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -127,7 +127,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;
@ -135,7 +135,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0));
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sumhPort;
}

View file

@ -21,13 +21,13 @@
#include "platform.h"
#ifdef SERIAL_RX
#ifdef USE_SERIAL_RX
#include "drivers/time.h"
#include "io/serial.h"
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
@ -323,7 +323,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;
@ -337,7 +337,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
);
#ifdef TELEMETRY
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = xBusPort;
}

View file

@ -80,10 +80,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 TRANSPONDER

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"

View file

@ -18,9 +18,9 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
#define LED0_PIN PB3
#define LED1_PIN PB4

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"

View file

@ -18,14 +18,14 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define REMAP_TIM17_DMA
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
// LED's V1
#define LED0_PIN PB4
@ -113,7 +113,7 @@
#define VBAT_SCALE_DEFAULT 20
// LED strip configuration.
#define LED_STRIP
#define USE_LED_STRIP
#define BINDPLUG_PIN PB12

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"

View file

@ -17,11 +17,11 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
#define USBD_PRODUCT_STRING "AlienFlight F4"
@ -155,7 +155,7 @@
#define CURRENT_METER_SCALE_DEFAULT -667 // ACS712/714-30A - 66.666 mV/A inverted mode
// LED strip configuration.
#define LED_STRIP
#define USE_LED_STRIP
#define BINDPLUG_PIN PB2

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"
#include "config/feature.h"

View file

@ -17,11 +17,11 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF7"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
#define USBD_PRODUCT_STRING "AlienFlightNG F7"
@ -171,7 +171,7 @@
#define CURRENT_METER_SCALE_DEFAULT -667 // ACS712/714-30A - 66.666 mV/A inverted mode
// LED strip configuration.
#define LED_STRIP
#define USE_LED_STRIP
#define BINDPLUG_PIN PB2

View file

@ -37,7 +37,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "fc/rc_modes.h"
#include "common/axis.h"

View file

@ -44,18 +44,18 @@
#define USBD_PRODUCT_STRING "AlienWhoopF7"
#endif
#define TARGET_CONFIG // see config.c for target specific customizations
#define USE_TARGET_CONFIG // see config.c for target specific customizations
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define BRUSHED_MOTORS
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
/* Visual Alerts - SMD LEDs
*/
#define LED0_PIN PC12 // conflicts UART5
#define LED1_PIN PD2 // conflicts UART5
#define LED_STRIP
#define USE_LED_STRIP
/* Lost Quad Mode and Alerts - RCX03-787 Low Voltage Active Buzzer
*/
@ -219,7 +219,7 @@
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#else
//#undef CMS // TODO: OSD depends upon CMS
//#undef USE_CMS // TODO: OSD depends upon CMS
#undef USE_I2C
#endif

View file

@ -21,7 +21,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"
#include "common/maths.h"

View file

@ -18,11 +18,11 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "BBV2" // BeeBrain V2.
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define BRUSHED_ESC_AUTODETECT
#define USE_BRUSHED_ESC_AUTODETECT
#define LED0_PIN PB1
#define LED1_PIN PB2

View file

@ -139,7 +139,7 @@
#define RSSI_ADC_PIN PC2
#define LED_STRIP
#define USE_LED_STRIP
#define TRANSPONDER

View file

@ -123,7 +123,7 @@
#define CURRENT_METER_ADC_PIN PC1
#define VBAT_ADC_PIN PC2
#define LED_STRIP
#define USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
@ -133,7 +133,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_OSD )
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "blackbox/blackbox.h"

View file

@ -17,7 +17,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "BJF4"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define TARGET_VALIDATECONFIG
#define TARGET_PREINIT

View file

@ -116,10 +116,10 @@
#undef USE_SERIALRX_SUMD // Graupner Hott protocol
#undef USE_SERIALRX_SUMH // Graupner legacy protocol
#undef USE_SERIALRX_XBUS // JR
#undef LED_STRIP
#undef USE_LED_STRIP
#endif
//#undef LED_STRIP
//#undef USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// IO - from schematics

View file

@ -116,7 +116,7 @@
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#undef LED_STRIP
#undef USE_LED_STRIP
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff

View file

@ -87,9 +87,9 @@
//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_V202_1M
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
//#define TELEMETRY
//#define TELEMETRY_LTM
//#define TELEMETRY_NRF24_LTM
//#define USE_TELEMETRY
//#define USE_TELEMETRY_LTM
//#define USE_TELEMETRY_NRF24_LTM
#ifdef USE_PWM
#undef USE_PWM
#endif
@ -98,8 +98,8 @@
#undef USE_PPM
#endif
#ifdef SERIAL_RX
#undef SERIAL_RX
#ifdef USE_SERIAL_RX
#undef USE_SERIAL_RX
#endif
//#undef SKIP_TASK_STATISTICS

View file

@ -142,7 +142,7 @@
#define CURRENT_METER_SCALE_DEFAULT 250 // 3.3/120A = 25mv/A
// LED strip configuration.
#define LED_STRIP
#define USE_LED_STRIP
#define BINDPLUG_PIN PB2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"

View file

@ -120,7 +120,7 @@
#define I2C3_SDA PC9
// alternative defaults for Colibri/Gemini target
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT

View file

@ -415,7 +415,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
break;
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
case BST_LED_COLORS:
for (i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
hsvColor_t *color = &ledStripConfigMutable()->colors[i];
@ -567,7 +567,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
}
break;
#ifdef LED_STRIP
#ifdef USE_LED_STRIP
case BST_SET_LED_COLORS:
//for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
{

View file

@ -103,7 +103,7 @@
#define USE_BLACKBOX
#define LED_STRIP
#define USE_LED_STRIP
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define BRUSHED_MOTORS

View file

@ -92,7 +92,7 @@
#define VBAT_ADC_PIN PC4
#define CURRENT_METER_ADC_PIN PC5
#undef LED_STRIP
#undef USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048

View file

@ -139,7 +139,7 @@
#define CURRENT_METER_ADC_PIN PC2
#define RSSI_ADC_PIN PC1
#undef LED_STRIP
#undef USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "fc/config.h"
#include "config/feature.h"

View file

@ -18,13 +18,13 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "FORT"
#define USBD_PRODUCT_STRING "FortiniF4"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC14
/*--------------LED----------------*/
#define LED0_PIN PB5
#define LED1_PIN PB6
#define LED_STRIP
#define USE_LED_STRIP
/*---------------------------------*/
/*------------BEEPER---------------*/

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"
#include "config/feature.h"

View file

@ -29,8 +29,8 @@
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define TARGET_CONFIG
#define BRUSHED_ESC_AUTODETECT
#define USE_TARGET_CONFIG
#define USE_BRUSHED_ESC_AUTODETECT
#define LED0_PIN PB9
#define LED1_PIN PB5

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "telemetry/telemetry.h"
void targetConfiguration(void)

View file

@ -18,11 +18,11 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "PIK4"
#define USBD_PRODUCT_STRING "PikoF4"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
/*--------------LED----------------*/
#define LED0_PIN PA15
#define LED1_PIN PB6
#define LED_STRIP
#define USE_LED_STRIP
/*---------------------------------*/
/*------------BEEPER---------------*/

View file

@ -18,7 +18,7 @@
#include <stdint.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "drivers/io.h"
#include "rx/rx.h"
#include "io/serial.h"

View file

@ -18,12 +18,12 @@
#pragma once
// no space left
#undef TELEMETRY_JETIEXBUS
#undef USE_TELEMETRY_JETIEXBUS
#undef USE_TELEMETRY_HOTT
#undef USE_TELEMETRY_LTM
#define TARGET_BOARD_IDENTIFIER "FRF3"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0_PIN PB3

View file

@ -18,7 +18,7 @@
#include <stdint.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "drivers/io.h"
#include "rx/rx.h"
#include "io/serial.h"

View file

@ -17,7 +17,7 @@
#define TARGET_BOARD_IDENTIFIER "FRF4"
#define USBD_PRODUCT_STRING "FRSKYF4"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define LED0_PIN PB5
#define BEEPER PB4

View file

@ -134,7 +134,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#undef LED_STRIP
#undef USE_LED_STRIP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS

View file

@ -79,7 +79,7 @@
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#undef LED_STRIP
#undef USE_LED_STRIP
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "io/serial.h"

View file

@ -24,7 +24,7 @@
#define USBD_PRODUCT_STRING "KakuteF4-V1"
#endif
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define LED0_PIN PB5
#define LED1_PIN PB4

View file

@ -15,7 +15,7 @@
#pragma once
//#define TARGET_CONFIG
//#define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "KTF7"
#define USBD_PRODUCT_STRING "KakuteF7"
@ -168,7 +168,7 @@
#define VBAT_ADC_PIN PC3
#define RSSI_ADC_PIN PC5
#define LED_STRIP
#define USE_LED_STRIP
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "fc/config.h"

View file

@ -39,7 +39,7 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#ifdef KISSCC
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define USE_GYRO
#define USE_GYRO_MPU6050
@ -48,7 +48,7 @@
#define USE_ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW90_DEG
#undef LED_STRIP
#undef USE_LED_STRIP
#else
#define USE_GYRO
#define USE_GYRO_MPU6050

View file

@ -161,7 +161,7 @@
#define I2C1_SDA PB7
*/
#define LED_STRIP
#define USE_LED_STRIP
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC

View file

@ -30,7 +30,7 @@
#define VBAT_SCALE 113
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
void targetConfiguration(void)
{
voltageSensorADCConfigMutable(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale = VBAT_SCALE;

View file

@ -24,7 +24,7 @@
#define USBD_PRODUCT_STRING "KroozX"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define TARGET_PREINIT
#define LED0_PIN PA14 // Red LED
@ -149,7 +149,7 @@
#define RX_CHANNELS_TAER
#define DEFAULT_FEATURES (FEATURE_OSD)
#define LED_STRIP
#define USE_LED_STRIP
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -75,7 +75,7 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define LED_STRIP
#define USE_LED_STRIP
#define CAMERA_CONTROL_PIN PA15

View file

@ -150,7 +150,7 @@
#define DEFAULT_FEATURES (FEATURE_OSD )
#define LED_STRIP
#define USE_LED_STRIP
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_PIN PA3

View file

@ -127,9 +127,9 @@
#define DEFAULT_FEATURES (FEATURE_OSD )
#define LED_STRIP
#define USE_LED_STRIP
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA1 // USART4 RX
#define USE_ESCSERIAL

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "fc/config.h"

View file

@ -20,7 +20,7 @@
#define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define LED0_PIN PB5 // Blue LEDs - PB5
//#define LED1_PIN PB9 // Green LEDs - PB9

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "telemetry/telemetry.h"
#include "fc/config.h"

View file

@ -17,7 +17,7 @@
#pragma once
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#undef USE_MSP_DISPLAYPORT
#ifdef MLTEMPF4
@ -140,7 +140,7 @@
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define SENSORS_SET (SENSOR_ACC)
#define LED_STRIP
#define USE_LED_STRIP
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
@ -154,7 +154,7 @@
#define CURRENT_METER_SCALE_DEFAULT 140
// USART5 Rx, PD2
#define SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND
#define BIND_PIN UART5_RX_PIN
#define TARGET_IO_PORTA 0xffff

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"
#include "common/maths.h"

View file

@ -18,7 +18,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "MFPB"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "common/axis.h"
#include "common/utils.h"

View file

@ -17,9 +17,9 @@
#pragma once
#define TELEMETRY_IBUS
#define USE_TELEMETRY_IBUS
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define TARGET_VALIDATECONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define TARGET_BUS_INIT
@ -38,7 +38,7 @@
#define BRUSHED_MOTORS
#undef USE_SERVOS
#define TARGET_BOARD_IDENTIFIER "BEBR"
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#else
#define TARGET_BOARD_IDENTIFIER "AFNA"

View file

@ -17,10 +17,10 @@
#pragma once
#undef TELEMETRY_IBUS //no space left
#undef TELEMETRY_HOTT //no space left
#undef TELEMETRY_JETIEXBUS // no space left
#undef TELEMETRY_MAVLINK // no space left
#undef USE_TELEMETRY_IBUS //no space left
#undef USE_TELEMETRY_HOTT //no space left
#undef USE_TELEMETRY_JETIEXBUS // no space left
#undef USE_TELEMETRY_MAVLINK // no space left
#undef USE_RCDEVICE // no space left
#undef USE_RTC_TIME // no space left
@ -161,7 +161,7 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define DEFAULT_FEATURES (FEATURE_OSD)
#define BUTTONS
#define USE_BUTTONS
#define BUTTON_A_PIN PB1
#define BUTTON_B_PIN PB0

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "config/parameter_group.h"
#include "drivers/max7456.h"

View file

@ -15,7 +15,7 @@
#pragma once
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#if defined(OMNIBUSF4SD)
#define TARGET_BOARD_IDENTIFIER "OBSD"

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "io/serial.h"

View file

@ -15,7 +15,7 @@
#pragma once
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#ifdef OMNIBUSF7V2
#define TARGET_BOARD_IDENTIFIER "OB72"
@ -187,7 +187,7 @@
#define VBAT_ADC_PIN PC3
#define RSSI_ADC_PIN PC5
#define LED_STRIP
#define USE_LED_STRIP
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View file

@ -20,7 +20,7 @@
#include <platform.h>
#ifdef TARGET_CONFIG
#ifdef USE_TARGET_CONFIG
#include "fc/config.h"

View file

@ -19,7 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "RBFC"
#define USE_HARDWARE_REVISION_DETECTION
#define TARGET_CONFIG
#define USE_TARGET_CONFIG
#define LED0_PIN PB3
#define LED0_INVERTED

View file

@ -104,10 +104,7 @@
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
#define NAV
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
#define NAV_MAX_WAYPOINTS 60
#define USE_NAV
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

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