mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Merge pull request #3302 from blckmn/config_led
Making status LEDs configurable.
This commit is contained in:
commit
98b301f1e8
76 changed files with 216 additions and 208 deletions
3
Makefile
3
Makefile
|
@ -1018,7 +1018,8 @@ STM32F7xx_COMMON_SRC = \
|
||||||
drivers/serial_uart_stm32f7xx.c \
|
drivers/serial_uart_stm32f7xx.c \
|
||||||
drivers/serial_uart_hal.c
|
drivers/serial_uart_hal.c
|
||||||
|
|
||||||
F7EXCLUDES = drivers/bus_spi.c \
|
F7EXCLUDES = \
|
||||||
|
drivers/bus_spi.c \
|
||||||
drivers/bus_i2c.c \
|
drivers/bus_i2c.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
drivers/serial_uart.c
|
drivers/serial_uart.c
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#define NOOP do {} while (0)
|
||||||
|
|
||||||
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
|
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
|
||||||
#define ARRAYEND(x) (&(x)[ARRAYLEN(x)])
|
#define ARRAYEND(x) (&(x)[ARRAYLEN(x)])
|
||||||
|
|
||||||
|
|
|
@ -17,24 +17,49 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "config/parameter_group_ids.h"
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "io_impl.h"
|
#include "io_impl.h"
|
||||||
|
|
||||||
#include "light_led.h"
|
#include "light_led.h"
|
||||||
|
|
||||||
static IO_t leds[LED_NUMBER];
|
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
||||||
static uint8_t ledPolarity = 0;
|
|
||||||
|
static IO_t leds[STATUS_LED_NUMBER];
|
||||||
|
static uint8_t ledInversion = 0;
|
||||||
|
|
||||||
|
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
||||||
|
{
|
||||||
|
#ifdef LED0_PIN
|
||||||
|
statusLedConfig->ioTags[0] = IO_TAG(LED0_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_PIN
|
||||||
|
statusLedConfig->ioTags[1] = IO_TAG(LED1_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_PIN
|
||||||
|
statusLedConfig->ioTags[2] = IO_TAG(LED2_PIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
statusLedConfig->inversion = 0
|
||||||
|
#ifdef LED0_INVERTED
|
||||||
|
| BIT(0)
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_INVERTED
|
||||||
|
| BIT(1)
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_INVERTED
|
||||||
|
| BIT(2)
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
void ledInit(const statusLedConfig_t *statusLedConfig)
|
void ledInit(const statusLedConfig_t *statusLedConfig)
|
||||||
{
|
{
|
||||||
LED0_OFF;
|
ledInversion = statusLedConfig->inversion;
|
||||||
LED1_OFF;
|
for (int i = 0; i < STATUS_LED_NUMBER; i++) {
|
||||||
LED2_OFF;
|
if (statusLedConfig->ioTags[i]) {
|
||||||
|
leds[i] = IOGetByTag(statusLedConfig->ioTags[i]);
|
||||||
ledPolarity = statusLedConfig->polarity;
|
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
|
||||||
if (statusLedConfig->ledTags[i]) {
|
|
||||||
leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
|
|
||||||
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
|
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
|
||||||
IOConfigGPIO(leds[i], IOCFG_OUT_PP);
|
IOConfigGPIO(leds[i], IOCFG_OUT_PP);
|
||||||
} else {
|
} else {
|
||||||
|
@ -54,6 +79,6 @@ void ledToggle(int led)
|
||||||
|
|
||||||
void ledSet(int led, bool on)
|
void ledSet(int led, bool on)
|
||||||
{
|
{
|
||||||
const bool inverted = (1 << (led)) & ledPolarity;
|
const bool inverted = (1 << (led)) & ledInversion;
|
||||||
IOWrite(leds[led], on ? inverted : !inverted);
|
IOWrite(leds[led], on ? inverted : !inverted);
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,47 +19,48 @@
|
||||||
|
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
#define LED_NUMBER 3
|
#define STATUS_LED_NUMBER 3
|
||||||
|
|
||||||
typedef struct statusLedConfig_s {
|
typedef struct statusLedConfig_s {
|
||||||
ioTag_t ledTags[LED_NUMBER];
|
ioTag_t ioTags[STATUS_LED_NUMBER];
|
||||||
uint8_t polarity;
|
uint8_t inversion;
|
||||||
} statusLedConfig_t;
|
} statusLedConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(statusLedConfig_t, statusLedConfig);
|
PG_DECLARE(statusLedConfig_t, statusLedConfig);
|
||||||
|
|
||||||
// Helpful macros
|
// Helpful macros
|
||||||
#ifdef LED0
|
#if defined(UNIT_TEST) || defined(USE_FAKE_LED)
|
||||||
# define LED0_TOGGLE ledToggle(0)
|
|
||||||
# define LED0_OFF ledSet(0, false)
|
|
||||||
# define LED0_ON ledSet(0, true)
|
|
||||||
#else
|
|
||||||
# define LED0_TOGGLE do {} while(0)
|
|
||||||
# define LED0_OFF do {} while(0)
|
|
||||||
# define LED0_ON do {} while(0)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef LED1
|
#define LED0_TOGGLE NOOP
|
||||||
# define LED1_TOGGLE ledToggle(1)
|
#define LED0_OFF NOOP
|
||||||
# define LED1_OFF ledSet(1, false)
|
#define LED0_ON NOOP
|
||||||
# define LED1_ON ledSet(1, true)
|
|
||||||
#else
|
#define LED1_TOGGLE NOOP
|
||||||
# define LED1_TOGGLE do {} while(0)
|
#define LED1_OFF NOOP
|
||||||
# define LED1_OFF do {} while(0)
|
#define LED1_ON NOOP
|
||||||
# define LED1_ON do {} while(0)
|
|
||||||
#endif
|
#define LED2_TOGGLE NOOP
|
||||||
|
#define LED2_OFF NOOP
|
||||||
|
#define LED2_ON NOOP
|
||||||
|
|
||||||
#ifdef LED2
|
|
||||||
# define LED2_TOGGLE ledToggle(2)
|
|
||||||
# define LED2_OFF ledSet(2, false)
|
|
||||||
# define LED2_ON ledSet(2, true)
|
|
||||||
#else
|
#else
|
||||||
# define LED2_TOGGLE do {} while(0)
|
|
||||||
# define LED2_OFF do {} while(0)
|
#define LED0_TOGGLE ledToggle(0)
|
||||||
# define LED2_ON do {} while(0)
|
#define LED0_OFF ledSet(0, false)
|
||||||
#endif
|
#define LED0_ON ledSet(0, true)
|
||||||
|
|
||||||
|
#define LED1_TOGGLE ledToggle(1)
|
||||||
|
#define LED1_OFF ledSet(1, false)
|
||||||
|
#define LED1_ON ledSet(1, true)
|
||||||
|
|
||||||
|
#define LED2_TOGGLE ledToggle(2)
|
||||||
|
#define LED2_OFF ledSet(2, false)
|
||||||
|
#define LED2_ON ledSet(2, true)
|
||||||
|
|
||||||
void ledInit(const statusLedConfig_t *statusLedConfig);
|
void ledInit(const statusLedConfig_t *statusLedConfig);
|
||||||
void ledToggle(int led);
|
void ledToggle(int led);
|
||||||
void ledSet(int led, bool state);
|
void ledSet(int led, bool state);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -74,6 +74,7 @@ extern uint8_t __config_end;
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/vcd.h"
|
#include "drivers/vcd.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "fc/settings.h"
|
#include "fc/settings.h"
|
||||||
#include "fc/cli.h"
|
#include "fc/cli.h"
|
||||||
|
@ -2755,6 +2756,7 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
{ OWNER_I2C_SCL, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagScl[0]), I2CDEV_COUNT },
|
{ OWNER_I2C_SCL, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagScl[0]), I2CDEV_COUNT },
|
||||||
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
|
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
|
||||||
#endif
|
#endif
|
||||||
|
{ OWNER_LED, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, ioTags[0]), STATUS_LED_NUMBER },
|
||||||
};
|
};
|
||||||
|
|
||||||
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
||||||
|
|
|
@ -148,7 +148,6 @@ PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
|
||||||
#ifdef USE_PPM
|
#ifdef USE_PPM
|
||||||
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
||||||
#endif
|
#endif
|
||||||
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
||||||
|
@ -255,35 +254,6 @@ void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
|
||||||
#define SECOND_PORT_INDEX 1
|
#define SECOND_PORT_INDEX 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
|
||||||
{
|
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
|
||||||
statusLedConfig->ledTags[i] = IO_TAG_NONE;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef LED0
|
|
||||||
statusLedConfig->ledTags[0] = IO_TAG(LED0);
|
|
||||||
#endif
|
|
||||||
#ifdef LED1
|
|
||||||
statusLedConfig->ledTags[1] = IO_TAG(LED1);
|
|
||||||
#endif
|
|
||||||
#ifdef LED2
|
|
||||||
statusLedConfig->ledTags[2] = IO_TAG(LED2);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
statusLedConfig->polarity = 0
|
|
||||||
#ifdef LED0_INVERTED
|
|
||||||
| BIT(0)
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_INVERTED
|
|
||||||
| BIT(1)
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_INVERTED
|
|
||||||
| BIT(2)
|
|
||||||
#endif
|
|
||||||
;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifndef USE_OSD_SLAVE
|
#ifndef USE_OSD_SLAVE
|
||||||
uint8_t getCurrentPidProfileIndex(void)
|
uint8_t getCurrentPidProfileIndex(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -223,7 +223,9 @@ void init(void)
|
||||||
targetPreInit();
|
targetPreInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(UNIT_TEST) && !defined(USE_FAKE_LED)
|
||||||
ledInit(statusLedConfig());
|
ledInit(statusLedConfig());
|
||||||
|
#endif
|
||||||
LED2_ON;
|
LED2_ON;
|
||||||
|
|
||||||
#ifdef USE_EXTI
|
#ifdef USE_EXTI
|
||||||
|
|
|
@ -36,6 +36,8 @@
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
#include "config/parameter_group_ids.h"
|
#include "config/parameter_group_ids.h"
|
||||||
|
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "fc/controlrate_profile.h"
|
#include "fc/controlrate_profile.h"
|
||||||
#include "fc/fc_core.h"
|
#include "fc/fc_core.h"
|
||||||
|
@ -714,6 +716,7 @@ const clivalue_t valueTable[] = {
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
{ "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) },
|
{ "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) },
|
||||||
#endif
|
#endif
|
||||||
|
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
|
||||||
};
|
};
|
||||||
|
|
||||||
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
|
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PB5 // Blue LED - PB5
|
#define LED0_PIN PB5 // Blue LED - PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
|
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
#define CONFIG_PREFER_ACC_ON
|
#define CONFIG_PREFER_ACC_ON
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define BEEPER PA12
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
|
|
||||||
#define BRUSHED_ESC_AUTODETECT
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define BEEPER PA12
|
||||||
|
|
||||||
|
|
|
@ -57,7 +57,7 @@ void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
/* depending on revision ... depends on the LEDs to be utilised. */
|
/* depending on revision ... depends on the LEDs to be utilised. */
|
||||||
if (hardwareRevision == AFF3_REV_2) {
|
if (hardwareRevision == AFF3_REV_2) {
|
||||||
statusLedConfigMutable()->polarity = 0
|
statusLedConfigMutable()->inversion = 0
|
||||||
#ifdef LED0_A_INVERTED
|
#ifdef LED0_A_INVERTED
|
||||||
| BIT(0)
|
| BIT(0)
|
||||||
#endif
|
#endif
|
||||||
|
@ -69,17 +69,17 @@ void targetConfiguration(void)
|
||||||
#endif
|
#endif
|
||||||
;
|
;
|
||||||
|
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
for (int i = 0; i < STATUS_LED_NUMBER; i++) {
|
||||||
statusLedConfigMutable()->ledTags[i] = IO_TAG_NONE;
|
statusLedConfigMutable()->ioTags[i] = IO_TAG_NONE;
|
||||||
}
|
}
|
||||||
#ifdef LED0_A
|
#ifdef LED0_A
|
||||||
statusLedConfigMutable()->ledTags[0] = IO_TAG(LED0_A);
|
statusLedConfigMutable()->ioTags[0] = IO_TAG(LED0_A);
|
||||||
#endif
|
#endif
|
||||||
#ifdef LED1_A
|
#ifdef LED1_A
|
||||||
statusLedConfigMutable()->ledTags[1] = IO_TAG(LED1_A);
|
statusLedConfigMutable()->ioTags[1] = IO_TAG(LED1_A);
|
||||||
#endif
|
#endif
|
||||||
#ifdef LED2_A
|
#ifdef LED2_A
|
||||||
statusLedConfigMutable()->ledTags[2] = IO_TAG(LED2_A);
|
statusLedConfigMutable()->ioTags[2] = IO_TAG(LED2_A);
|
||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
gyroConfigMutable()->gyro_sync_denom = 2;
|
gyroConfigMutable()->gyro_sync_denom = 2;
|
||||||
|
|
|
@ -28,8 +28,8 @@
|
||||||
#define BRUSHED_ESC_AUTODETECT
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
// LED's V1
|
// LED's V1
|
||||||
#define LED0 PB4
|
#define LED0_PIN PB4
|
||||||
#define LED1 PB5
|
#define LED1_PIN PB5
|
||||||
|
|
||||||
// LED's V2
|
// LED's V2
|
||||||
#define LED0_A PB8
|
#define LED0_A PB8
|
||||||
|
|
|
@ -25,8 +25,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "AlienFlight F4"
|
#define USBD_PRODUCT_STRING "AlienFlight F4"
|
||||||
|
|
||||||
#define LED0 PC12
|
#define LED0_PIN PC12
|
||||||
#define LED1 PD2
|
#define LED1_PIN PD2
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define BEEPER PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -25,8 +25,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "AlienFlightNG F7"
|
#define USBD_PRODUCT_STRING "AlienFlightNG F7"
|
||||||
|
|
||||||
#define LED0 PC12
|
#define LED0_PIN PC12
|
||||||
#define LED1 PD2
|
#define LED1_PIN PD2
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define BEEPER PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "BeeRotorF4"
|
#define USBD_PRODUCT_STRING "BeeRotorF4"
|
||||||
|
|
||||||
#define LED0 PB4
|
#define LED0_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PB3
|
#define BEEPER PB3
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -28,9 +28,9 @@
|
||||||
|
|
||||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
|
||||||
#define LED0 PB6
|
#define LED0_PIN PB6
|
||||||
#define LED1 PB5
|
#define LED1_PIN PB5
|
||||||
#define LED2 PB4
|
#define LED2_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define BEEPER PC1
|
||||||
#define BEEPER_OPT PB7
|
#define BEEPER_OPT PB7
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
|
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
|
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
|
||||||
|
|
||||||
|
|
|
@ -24,9 +24,9 @@
|
||||||
#define STM32F3DISCOVERY
|
#define STM32F3DISCOVERY
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
#define LED0_PIN PE8 // Blue LEDs - PE8/PE12
|
||||||
#define LED0_INVERTED
|
#define LED0_INVERTED
|
||||||
#define LED1 PE10 // Orange LEDs - PE10/PE14
|
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
||||||
|
|
|
@ -21,9 +21,9 @@
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
#define TARGET_BUS_INIT
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1 PC13
|
#define LED1_PIN PC13
|
||||||
#define LED2 PC15
|
#define LED2_PIN PC15
|
||||||
|
|
||||||
#undef BEEPER
|
#undef BEEPER
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz
|
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
||||||
|
|
||||||
#define LED0 PB0
|
#define LED0_PIN PB0
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -26,8 +26,8 @@
|
||||||
|
|
||||||
#define TARGET_XTAL_MHZ 16
|
#define TARGET_XTAL_MHZ 16
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1 PC13
|
#define LED1_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PC5
|
#define BEEPER PC5
|
||||||
|
|
||||||
|
|
|
@ -26,9 +26,9 @@
|
||||||
|
|
||||||
#undef USE_RX_MSP // never used.
|
#undef USE_RX_MSP // never used.
|
||||||
|
|
||||||
#define LED0 PC15
|
#define LED0_PIN PC15
|
||||||
#define LED1 PC14
|
#define LED1_PIN PC14
|
||||||
#define LED2 PC13
|
#define LED2_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PB13
|
#define BEEPER PB13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -42,9 +42,9 @@
|
||||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(4) )
|
#define USED_TIMERS ( TIM_N(2) | TIM_N(4) )
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PD2
|
#define LED0_PIN PD2
|
||||||
#define LED1 PC0
|
#define LED1_PIN PC0
|
||||||
#define LED2 PC3
|
#define LED2_PIN PC3
|
||||||
|
|
||||||
// Using STM32F405RG, 64 pin package (LQFP64)
|
// Using STM32F405RG, 64 pin package (LQFP64)
|
||||||
// 16 pins per port, ports A, B, C, and also PD2
|
// 16 pins per port, ports A, B, C, and also PD2
|
||||||
|
|
|
@ -22,11 +22,11 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
// tqfp48 pin 34
|
// tqfp48 pin 34
|
||||||
#define LED0 PA13
|
#define LED0_PIN PA13
|
||||||
// tqfp48 pin 37
|
// tqfp48 pin 37
|
||||||
#define LED1 PA14
|
#define LED1_PIN PA14
|
||||||
// tqfp48 pin 38
|
// tqfp48 pin 38
|
||||||
#define LED2 PA15
|
#define LED2_PIN PA15
|
||||||
|
|
||||||
#define BEEPER PB2
|
#define BEEPER PB2
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,9 +22,9 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Elle0"
|
#define USBD_PRODUCT_STRING "Elle0"
|
||||||
|
|
||||||
#define LED0 PA8
|
#define LED0_PIN PA8
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2 PC2
|
#define LED2_PIN PC2
|
||||||
|
|
||||||
// MPU9250 interrupt
|
// MPU9250 interrupt
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -20,9 +20,9 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Swift-Flyer F4BY"
|
#define USBD_PRODUCT_STRING "Swift-Flyer F4BY"
|
||||||
|
|
||||||
#define LED0 PE3 // Blue LED
|
#define LED0_PIN PE3 // Blue LED
|
||||||
#define LED1 PE2 // Red LED
|
#define LED1_PIN PE2 // Red LED
|
||||||
#define LED2 PE1 // Blue LED
|
#define LED2_PIN PE1 // Blue LED
|
||||||
|
|
||||||
#define BEEPER PE5
|
#define BEEPER PE5
|
||||||
|
|
||||||
|
|
|
@ -19,8 +19,8 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "FORT"
|
#define TARGET_BOARD_IDENTIFIER "FORT"
|
||||||
#define USBD_PRODUCT_STRING "FortiniF4"
|
#define USBD_PRODUCT_STRING "FortiniF4"
|
||||||
/*--------------LED----------------*/
|
/*--------------LED----------------*/
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB6
|
#define LED1_PIN PB6
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -32,8 +32,8 @@
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
#define BRUSHED_ESC_AUTODETECT
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
#define LED0 PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1 PB5
|
#define LED1_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -19,8 +19,8 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "PIK4"
|
#define TARGET_BOARD_IDENTIFIER "PIK4"
|
||||||
#define USBD_PRODUCT_STRING "PikoF4"
|
#define USBD_PRODUCT_STRING "PikoF4"
|
||||||
/*--------------LED----------------*/
|
/*--------------LED----------------*/
|
||||||
#define LED0 PA15
|
#define LED0_PIN PA15
|
||||||
#define LED1 PB6
|
#define LED1_PIN PB6
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "FishDroneF4"
|
#define USBD_PRODUCT_STRING "FishDroneF4"
|
||||||
|
|
||||||
#define LED0 PC13
|
#define LED0_PIN PC13
|
||||||
#define LED1 PC14
|
#define LED1_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
#define USBD_PRODUCT_STRING "FRSKYF4"
|
#define USBD_PRODUCT_STRING "FRSKYF4"
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
#define CONFIG_PREFER_ACC_ON
|
#define CONFIG_PREFER_ACC_ON
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -25,8 +25,8 @@
|
||||||
#define USBD_PRODUCT_STRING "FuryF4"
|
#define USBD_PRODUCT_STRING "FuryF4"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define BEEPER PA8
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "FuryF7"
|
#define USBD_PRODUCT_STRING "FuryF7"
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PD10
|
#define BEEPER PD10
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB7
|
#define LED0_PIN PB7
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MPU_INT_EXTI PC13
|
#define MPU_INT_EXTI PC13
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -20,9 +20,9 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "KakuteF4-V1"
|
#define USBD_PRODUCT_STRING "KakuteF4-V1"
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2 PB6
|
#define LED2_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define BEEPER PC9
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
#define ESCSERIAL_TIMER_TX_HARDWARE 6
|
#define ESCSERIAL_TIMER_TX_HARDWARE 6
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
#define LED0 PB1
|
#define LED0_PIN PB1
|
||||||
|
|
||||||
#define BEEPER PB13
|
#define BEEPER PB13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -32,11 +32,11 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PLUMF4) || defined(KIWIF4V2)
|
#if defined(PLUMF4) || defined(KIWIF4V2)
|
||||||
#define LED0 PB4
|
#define LED0_PIN PB4
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define BEEPER PA8
|
||||||
|
|
|
@ -27,8 +27,8 @@
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
#define TARGET_PREINIT
|
#define TARGET_PREINIT
|
||||||
|
|
||||||
#define LED0 PA14 // Red LED
|
#define LED0_PIN PA14 // Red LED
|
||||||
#define LED1 PA13 // Green LED
|
#define LED1_PIN PA13 // Green LED
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define BEEPER PC1
|
||||||
|
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
||||||
// MPU6000 interrupts
|
// MPU6000 interrupts
|
||||||
|
|
|
@ -26,10 +26,10 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PC15
|
#define LED0_PIN PC15
|
||||||
#define LED1 PC14
|
#define LED1_PIN PC14
|
||||||
#ifndef LUXV2_RACE
|
#ifndef LUXV2_RACE
|
||||||
#define LED2 PC13
|
#define LED2_PIN PC13
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LUXV2_RACE
|
#ifdef LUXV2_RACE
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "MatekF4"
|
#define USBD_PRODUCT_STRING "MatekF4"
|
||||||
|
|
||||||
#define LED0 PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1 PA14
|
#define LED1_PIN PA14
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define BEEPER PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -19,8 +19,8 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY
|
#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define BEEPER PA12
|
||||||
|
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
#define LED0 PB5 // Blue LEDs - PB5
|
#define LED0_PIN PB5 // Blue LEDs - PB5
|
||||||
//#define LED1 PB9 // Green LEDs - PB9
|
//#define LED1_PIN PB9 // Green LEDs - PB9
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -26,8 +26,8 @@
|
||||||
|
|
||||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define BEEPER PA12
|
||||||
|
|
||||||
|
|
|
@ -24,9 +24,9 @@
|
||||||
|
|
||||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
|
||||||
#define LED0 PB6
|
#define LED0_PIN PB6
|
||||||
#define LED1 PB5
|
#define LED1_PIN PB5
|
||||||
#define LED2 PB4
|
#define LED2_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define BEEPER PC1
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -33,8 +33,8 @@
|
||||||
#define USBD_SERIALNUMBER_STRING "0x8020000" // Remove this at the next major release (?)
|
#define USBD_SERIALNUMBER_STRING "0x8020000" // Remove this at the next major release (?)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
//#define LED1 PB4 // Remove this at the next major release
|
//#define LED1_PIN PB4 // Remove this at the next major release
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "OmnibusF7"
|
#define USBD_PRODUCT_STRING "OmnibusF7"
|
||||||
|
|
||||||
#define LED0 PE0
|
#define LED0_PIN PE0
|
||||||
|
|
||||||
#define BEEPER PD15
|
#define BEEPER PD15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -21,10 +21,10 @@
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#define LED0_INVERTED
|
#define LED0_INVERTED
|
||||||
|
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define BEEPER PA12
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB4
|
#define LED0_PIN PB4
|
||||||
#define LED1 PB5
|
#define LED1_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -48,10 +48,10 @@
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#if defined(PODIUMF4)
|
#if defined(PODIUMF4)
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2 PB6
|
#define LED2_PIN PB6
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
||||||
|
@ -64,7 +64,7 @@
|
||||||
#define BEEPER PB6
|
#define BEEPER PB6
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#else
|
#else
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
// Leave beeper here but with none as io - so disabled unless mapped.
|
// Leave beeper here but with none as io - so disabled unless mapped.
|
||||||
#define BEEPER NONE
|
#define BEEPER NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -23,8 +23,8 @@
|
||||||
#define USBD_SERIALNUMBER_STRING "0x8010000"
|
#define USBD_SERIALNUMBER_STRING "0x8010000"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1 PC13
|
#define LED1_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define BEEPER PC13
|
||||||
|
|
||||||
|
|
|
@ -19,8 +19,8 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "RGF3" // rgSSD_F3
|
#define TARGET_BOARD_IDENTIFIER "RGF3" // rgSSD_F3
|
||||||
|
|
||||||
#define LED0 PC1
|
#define LED0_PIN PC1
|
||||||
#define LED1 PC0
|
#define LED1_PIN PC0
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define BEEPER PA8
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "SIRF"
|
#define TARGET_BOARD_IDENTIFIER "SIRF"
|
||||||
|
|
||||||
#define LED0 PB2
|
#define LED0_PIN PB2
|
||||||
#define BEEPER PA1
|
#define BEEPER PA1
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -45,6 +45,8 @@
|
||||||
#undef SCHEDULER_DELAY_LIMIT
|
#undef SCHEDULER_DELAY_LIMIT
|
||||||
#define SCHEDULER_DELAY_LIMIT 1
|
#define SCHEDULER_DELAY_LIMIT 1
|
||||||
|
|
||||||
|
#define USE_FAKE_LED
|
||||||
|
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_FAKE_ACC
|
#define USE_FAKE_ACC
|
||||||
|
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4
|
#define LED0_PIN PB4 // Blue (Rev 1 & 2) - PB4
|
||||||
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
#define LED1_PIN PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||||
|
|
||||||
#define BEEPER PA1
|
#define BEEPER PA1
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -23,9 +23,9 @@
|
||||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2 PB6
|
#define LED2_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define BEEPER PC9
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -30,11 +30,11 @@
|
||||||
#if defined(ZCOREF3)
|
#if defined(ZCOREF3)
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PB8
|
#define LED0_PIN PB8
|
||||||
#else
|
#else
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
|
@ -46,7 +46,7 @@
|
||||||
|
|
||||||
#define BRUSHED_ESC_AUTODETECT
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
#define LED0 PB8
|
#define LED0_PIN PB8
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PB8
|
#define LED0_PIN PB8
|
||||||
#else
|
#else
|
||||||
#define TARGET_BOARD_IDENTIFIER "SRFM"
|
#define TARGET_BOARD_IDENTIFIER "SRFM"
|
||||||
|
|
||||||
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0_PIN PB3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1 PB2
|
#define LED1_PIN PB2
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define LED0 PA15
|
#define LED0_PIN PA15
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "SP Racing F4 NEO"
|
#define USBD_PRODUCT_STRING "SP Racing F4 NEO"
|
||||||
|
|
||||||
#define LED0 PA0
|
#define LED0_PIN PA0
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -27,16 +27,16 @@
|
||||||
#define USBD_PRODUCT_STRING "SP Racing F4 NEO"
|
#define USBD_PRODUCT_STRING "SP Racing F4 NEO"
|
||||||
|
|
||||||
#if (SPRACINGF4NEO_REV >= 3)
|
#if (SPRACINGF4NEO_REV >= 3)
|
||||||
#define LED0 PA0
|
#define LED0_PIN PA0
|
||||||
#define LED1 PB1
|
#define LED1_PIN PB1
|
||||||
#endif
|
#endif
|
||||||
#if (SPRACINGF4NEO_REV == 2)
|
#if (SPRACINGF4NEO_REV == 2)
|
||||||
#define LED0 PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1 PB2
|
#define LED1_PIN PB2
|
||||||
#endif
|
#endif
|
||||||
#if (SPRACINGF4NEO_REV == 1)
|
#if (SPRACINGF4NEO_REV == 1)
|
||||||
#define LED0 PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1 PB2
|
#define LED1_PIN PB2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
|
|
@ -31,9 +31,9 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
#define LED0_PIN PE8 // Blue LEDs - PE8/PE12
|
||||||
#define LED0_INVERTED
|
#define LED0_INVERTED
|
||||||
#define LED1 PE10 // Orange LEDs - PE10/PE14
|
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PD12
|
#define BEEPER PD12
|
||||||
|
|
|
@ -22,8 +22,8 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "TFSH" // http://fishpepper.de/projects/tinyFISH
|
#define TARGET_BOARD_IDENTIFIER "TFSH" // http://fishpepper.de/projects/tinyFISH
|
||||||
|
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1 PA13
|
#define LED1_PIN PA13
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0_PIN PC14
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -21,9 +21,9 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "YupiF4"
|
#define USBD_PRODUCT_STRING "YupiF4"
|
||||||
|
|
||||||
#define LED0 PB6
|
#define LED0_PIN PB6
|
||||||
#define LED1 PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2 PB5
|
#define LED2_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define BEEPER PC9
|
||||||
#define BEEPER_PWM_HZ 2200 // Beeper PWM frequency in Hz
|
#define BEEPER_PWM_HZ 2200 // Beeper PWM frequency in Hz
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue