Merge pull request #5285 from jflyper/bfdev-convert-beeper-to-USE_-scheme
BEEPER Conversion to use USE_ scheme
This commit is contained in:
commit
bf11921dc0
|
@ -40,7 +40,7 @@ loadDmaBufferFn *loadDmaBuffer;
|
||||||
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
static pwmOutputPort_t beeperPwm;
|
static pwmOutputPort_t beeperPwm;
|
||||||
static uint16_t freqBeep = 0;
|
static uint16_t freqBeep = 0;
|
||||||
#endif
|
#endif
|
||||||
|
@ -464,7 +464,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
void pwmWriteBeeper(bool onoffBeep)
|
void pwmWriteBeeper(bool onoffBeep)
|
||||||
{
|
{
|
||||||
if (!beeperPwm.io)
|
if (!beeperPwm.io)
|
||||||
|
|
|
@ -199,7 +199,7 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
||||||
void pwmCompleteDshotMotorUpdate(uint8_t motorCount);
|
void pwmCompleteDshotMotorUpdate(uint8_t motorCount);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
void pwmWriteBeeper(bool onoffBeep);
|
void pwmWriteBeeper(bool onoffBeep);
|
||||||
void pwmToggleBeeper(void);
|
void pwmToggleBeeper(void);
|
||||||
void beeperPwmInit(const ioTag_t tag, uint16_t frequency);
|
void beeperPwmInit(const ioTag_t tag, uint16_t frequency);
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
|
|
||||||
#include "sound_beeper.h"
|
#include "sound_beeper.h"
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
static IO_t beeperIO = DEFIO_IO(NONE);
|
static IO_t beeperIO = DEFIO_IO(NONE);
|
||||||
static bool beeperInverted = false;
|
static bool beeperInverted = false;
|
||||||
static uint16_t beeperFrequency = 0;
|
static uint16_t beeperFrequency = 0;
|
||||||
|
@ -35,7 +35,7 @@ static uint16_t beeperFrequency = 0;
|
||||||
|
|
||||||
void systemBeep(bool onoff)
|
void systemBeep(bool onoff)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
if (beeperFrequency == 0) {
|
if (beeperFrequency == 0) {
|
||||||
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
||||||
} else {
|
} else {
|
||||||
|
@ -48,7 +48,7 @@ void systemBeep(bool onoff)
|
||||||
|
|
||||||
void systemBeepToggle(void)
|
void systemBeepToggle(void)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
if (beeperFrequency == 0) {
|
if (beeperFrequency == 0) {
|
||||||
IOToggle(beeperIO);
|
IOToggle(beeperIO);
|
||||||
} else {
|
} else {
|
||||||
|
@ -59,7 +59,7 @@ void systemBeepToggle(void)
|
||||||
|
|
||||||
void beeperInit(const beeperDevConfig_t *config)
|
void beeperInit(const beeperDevConfig_t *config)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperFrequency = config->frequency;
|
beeperFrequency = config->frequency;
|
||||||
if (beeperFrequency == 0) {
|
if (beeperFrequency == 0) {
|
||||||
beeperIO = IOGetByTag(config->ioTag);
|
beeperIO = IOGetByTag(config->ioTag);
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
#define BEEP_TOGGLE systemBeepToggle()
|
#define BEEP_TOGGLE systemBeepToggle()
|
||||||
#define BEEP_OFF systemBeep(false)
|
#define BEEP_OFF systemBeep(false)
|
||||||
#define BEEP_ON systemBeep(true)
|
#define BEEP_ON systemBeep(true)
|
||||||
|
|
|
@ -500,7 +500,7 @@ void changePidProfile(uint8_t pidProfileIndex)
|
||||||
|
|
||||||
void beeperOffSet(uint32_t mask)
|
void beeperOffSet(uint32_t mask)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->beeper_off_flags |= mask;
|
beeperConfigMutable()->beeper_off_flags |= mask;
|
||||||
#else
|
#else
|
||||||
UNUSED(mask);
|
UNUSED(mask);
|
||||||
|
@ -509,7 +509,7 @@ void beeperOffSet(uint32_t mask)
|
||||||
|
|
||||||
void beeperOffSetAll(uint8_t beeperCount)
|
void beeperOffSetAll(uint8_t beeperCount)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
|
beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
|
||||||
#else
|
#else
|
||||||
UNUSED(beeperCount);
|
UNUSED(beeperCount);
|
||||||
|
@ -518,7 +518,7 @@ void beeperOffSetAll(uint8_t beeperCount)
|
||||||
|
|
||||||
void beeperOffClear(uint32_t mask)
|
void beeperOffClear(uint32_t mask)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->beeper_off_flags &= ~(mask);
|
beeperConfigMutable()->beeper_off_flags &= ~(mask);
|
||||||
#else
|
#else
|
||||||
UNUSED(mask);
|
UNUSED(mask);
|
||||||
|
@ -527,14 +527,14 @@ void beeperOffClear(uint32_t mask)
|
||||||
|
|
||||||
void beeperOffClearAll(void)
|
void beeperOffClearAll(void)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->beeper_off_flags = 0;
|
beeperConfigMutable()->beeper_off_flags = 0;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t getBeeperOffMask(void)
|
uint32_t getBeeperOffMask(void)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
return beeperConfig()->beeper_off_flags;
|
return beeperConfig()->beeper_off_flags;
|
||||||
#else
|
#else
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -543,7 +543,7 @@ uint32_t getBeeperOffMask(void)
|
||||||
|
|
||||||
void setBeeperOffMask(uint32_t mask)
|
void setBeeperOffMask(uint32_t mask)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->beeper_off_flags = mask;
|
beeperConfigMutable()->beeper_off_flags = mask;
|
||||||
#else
|
#else
|
||||||
UNUSED(mask);
|
UNUSED(mask);
|
||||||
|
@ -552,7 +552,7 @@ void setBeeperOffMask(uint32_t mask)
|
||||||
|
|
||||||
uint32_t getPreferredBeeperOffMask(void)
|
uint32_t getPreferredBeeperOffMask(void)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
return beeperConfig()->preferred_beeper_off_flags;
|
return beeperConfig()->preferred_beeper_off_flags;
|
||||||
#else
|
#else
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -561,7 +561,7 @@ uint32_t getPreferredBeeperOffMask(void)
|
||||||
|
|
||||||
void setPreferredBeeperOffMask(uint32_t mask)
|
void setPreferredBeeperOffMask(uint32_t mask)
|
||||||
{
|
{
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperConfigMutable()->preferred_beeper_off_flags = mask;
|
beeperConfigMutable()->preferred_beeper_off_flags = mask;
|
||||||
#else
|
#else
|
||||||
UNUSED(mask);
|
UNUSED(mask);
|
||||||
|
|
|
@ -411,7 +411,7 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperInit(beeperDevConfig());
|
beeperInit(beeperDevConfig());
|
||||||
#endif
|
#endif
|
||||||
/* temp until PGs are implemented. */
|
/* temp until PGs are implemented. */
|
||||||
|
|
|
@ -255,7 +255,7 @@ void fcTasksInit(void)
|
||||||
|
|
||||||
setTaskEnabled(TASK_DISPATCH, dispatchIsEnabled());
|
setTaskEnabled(TASK_DISPATCH, dispatchIsEnabled());
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
setTaskEnabled(TASK_BEEPER, true);
|
setTaskEnabled(TASK_BEEPER, true);
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GPS
|
#ifdef USE_GPS
|
||||||
|
@ -437,7 +437,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
.staticPriority = TASK_PRIORITY_HIGH,
|
.staticPriority = TASK_PRIORITY_HIGH,
|
||||||
},
|
},
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
[TASK_BEEPER] = {
|
[TASK_BEEPER] = {
|
||||||
.taskName = "BEEPER",
|
.taskName = "BEEPER",
|
||||||
.taskFunc = beeperUpdate,
|
.taskFunc = beeperUpdate,
|
||||||
|
|
|
@ -2057,7 +2057,7 @@ static void cliFeature(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
|
static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
|
||||||
{
|
{
|
||||||
const uint8_t beeperCount = beeperTableEntryCount();
|
const uint8_t beeperCount = beeperTableEntryCount();
|
||||||
|
@ -3162,7 +3162,7 @@ typedef struct {
|
||||||
} cliResourceValue_t;
|
} cliResourceValue_t;
|
||||||
|
|
||||||
const cliResourceValue_t resourceTable[] = {
|
const cliResourceValue_t resourceTable[] = {
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
{ OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, ioTag), 0 },
|
{ OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, ioTag), 0 },
|
||||||
#endif
|
#endif
|
||||||
{ OWNER_MOTOR, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.ioTags[0]), MAX_SUPPORTED_MOTORS },
|
{ OWNER_MOTOR, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.ioTags[0]), MAX_SUPPORTED_MOTORS },
|
||||||
|
@ -3557,7 +3557,7 @@ static void printConfig(char *cmdline, bool doDiff)
|
||||||
cliPrintHashLine("feature");
|
cliPrintHashLine("feature");
|
||||||
printFeature(dumpMask, &featureConfig_Copy, featureConfig());
|
printFeature(dumpMask, &featureConfig_Copy, featureConfig());
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
cliPrintHashLine("beeper");
|
cliPrintHashLine("beeper");
|
||||||
printBeeper(dumpMask, &beeperConfig_Copy, beeperConfig());
|
printBeeper(dumpMask, &beeperConfig_Copy, beeperConfig());
|
||||||
#endif
|
#endif
|
||||||
|
@ -3677,7 +3677,7 @@ static void cliHelp(char *cmdline);
|
||||||
const clicmd_t cmdTable[] = {
|
const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
|
CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
|
||||||
CLI_COMMAND_DEF("aux", "configure modes", "<index> <mode> <aux> <start> <end> <logic>", cliAux),
|
CLI_COMMAND_DEF("aux", "configure modes", "<index> <mode> <aux> <start> <end> <logic>", cliAux),
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
|
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
|
||||||
"\t<+|->[name]", cliBeeper),
|
"\t<+|->[name]", cliBeeper),
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -471,7 +471,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
sbufWriteU32(dst, featureMask());
|
sbufWriteU32(dst, featureMask());
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
case MSP_BEEPER_CONFIG:
|
case MSP_BEEPER_CONFIG:
|
||||||
sbufWriteU32(dst, getBeeperOffMask());
|
sbufWriteU32(dst, getBeeperOffMask());
|
||||||
sbufWriteU8(dst, beeperConfig()->dshotBeaconTone);
|
sbufWriteU8(dst, beeperConfig()->dshotBeaconTone);
|
||||||
|
@ -1849,7 +1849,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
featureSet(sbufReadU32(src)); // features bitmap
|
featureSet(sbufReadU32(src)); // features bitmap
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
case MSP_SET_BEEPER_CONFIG:
|
case MSP_SET_BEEPER_CONFIG:
|
||||||
beeperOffClearAll();
|
beeperOffClearAll();
|
||||||
setBeeperOffMask(sbufReadU32(src));
|
setBeeperOffMask(sbufReadU32(src));
|
||||||
|
|
|
@ -524,7 +524,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "ibatv_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, offset) },
|
{ "ibatv_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, offset) },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
// PG_BEEPER_DEV_CONFIG
|
// PG_BEEPER_DEV_CONFIG
|
||||||
{ "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isInverted) },
|
{ "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isInverted) },
|
||||||
{ "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isOpenDrain) },
|
{ "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isOpenDrain) },
|
||||||
|
|
|
@ -57,8 +57,7 @@
|
||||||
#define IS_INVERTED false
|
#define IS_INVERTED false
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
#define BEEPER_PIN BEEPER
|
|
||||||
#ifndef BEEPER_PWM_HZ
|
#ifndef BEEPER_PWM_HZ
|
||||||
#define BEEPER_PWM_HZ 0
|
#define BEEPER_PWM_HZ 0
|
||||||
#endif
|
#endif
|
||||||
|
@ -76,7 +75,7 @@
|
||||||
#define BEEPER_COMMAND_REPEAT 0xFE
|
#define BEEPER_COMMAND_REPEAT 0xFE
|
||||||
#define BEEPER_COMMAND_STOP 0xFF
|
#define BEEPER_COMMAND_STOP 0xFF
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
/* Beeper Sound Sequences: (Square wave generation)
|
/* Beeper Sound Sequences: (Square wave generation)
|
||||||
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
|
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
|
||||||
* start when 0xFF stops the sound when it's completed.
|
* start when 0xFF stops the sound when it's completed.
|
||||||
|
|
|
@ -425,11 +425,11 @@ void esc4wayProcess(serialPort_t *mspPort)
|
||||||
port = mspPort;
|
port = mspPort;
|
||||||
|
|
||||||
// Start here with UART Main loop
|
// Start here with UART Main loop
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
// fix for buzzer often starts beeping continuously when the ESCs are read
|
// fix for buzzer often starts beeping continuously when the ESCs are read
|
||||||
// switch beeper silent here
|
// switch beeper silent here
|
||||||
beeperSilence();
|
beeperSilence();
|
||||||
#endif
|
#endif
|
||||||
bool isExitScheduled = false;
|
bool isExitScheduled = false;
|
||||||
|
|
||||||
while (1) {
|
while (1) {
|
||||||
|
|
|
@ -188,7 +188,7 @@ void init(void)
|
||||||
|
|
||||||
serialInit(false, SERIAL_PORT_NONE);
|
serialInit(false, SERIAL_PORT_NONE);
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
beeperInit(beeperDevConfig());
|
beeperInit(beeperDevConfig());
|
||||||
#endif
|
#endif
|
||||||
/* temp until PGs are implemented. */
|
/* temp until PGs are implemented. */
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
@ -35,14 +35,12 @@ PG_REGISTER_WITH_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig, PG_BEEPER_DE
|
||||||
#define IS_INVERTED false
|
#define IS_INVERTED false
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
|
||||||
#define BEEPER_PIN BEEPER
|
|
||||||
#ifndef BEEPER_PWM_HZ
|
#ifndef BEEPER_PWM_HZ
|
||||||
#define BEEPER_PWM_HZ 0
|
#define BEEPER_PWM_HZ 0
|
||||||
#endif
|
#endif
|
||||||
#else
|
|
||||||
|
#ifndef BEEPER_PIN
|
||||||
#define BEEPER_PIN NONE
|
#define BEEPER_PIN NONE
|
||||||
#define BEEPER_PWM_HZ 0
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
|
PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
|
||||||
|
|
|
@ -64,7 +64,7 @@ typedef enum {
|
||||||
TASK_BATTERY_VOLTAGE,
|
TASK_BATTERY_VOLTAGE,
|
||||||
TASK_BATTERY_CURRENT,
|
TASK_BATTERY_CURRENT,
|
||||||
TASK_BATTERY_ALERTS,
|
TASK_BATTERY_ALERTS,
|
||||||
#ifdef BEEPER
|
#ifdef USE_BEEPER
|
||||||
TASK_BEEPER,
|
TASK_BEEPER,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GPS
|
#ifdef USE_GPS
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB5 // Blue LED - PB5
|
#define LED0_PIN PB5 // Blue LED - PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
|
|
||||||
// MPU6050 interrupts
|
// MPU6050 interrupts
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA12
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA12
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MAG_INT_EXTI PC14
|
#define MAG_INT_EXTI PC14
|
||||||
|
|
|
@ -40,7 +40,7 @@ void detectHardwareRevision(void)
|
||||||
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
||||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||||
|
|
||||||
RXDetectPin = IOGetByTag(IO_TAG(BEEPER));
|
RXDetectPin = IOGetByTag(IO_TAG(BEEPER_PIN));
|
||||||
IOInit(RXDetectPin, OWNER_SYSTEM, 0);
|
IOInit(RXDetectPin, OWNER_SYSTEM, 0);
|
||||||
IOConfigGPIO(RXDetectPin, IOCFG_IPU);
|
IOConfigGPIO(RXDetectPin, IOCFG_IPU);
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,8 @@
|
||||||
#define LED0_A PB8
|
#define LED0_A PB8
|
||||||
#define LED1_A PB9
|
#define LED1_A PB9
|
||||||
|
|
||||||
#define BEEPER PA5
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA5
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#define LED0_PIN PC12
|
#define LED0_PIN PC12
|
||||||
#define LED1_PIN PD2
|
#define LED1_PIN PD2
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART2 PC15
|
#define INVERTER_PIN_UART2 PC15
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#define LED0_PIN PC12
|
#define LED0_PIN PC12
|
||||||
#define LED1_PIN PD2
|
#define LED1_PIN PD2
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU interrupt
|
// MPU interrupt
|
||||||
|
|
|
@ -57,7 +57,8 @@
|
||||||
|
|
||||||
/* Lost Quad Mode and Alerts - RCX03-787 Low Voltage Active Buzzer
|
/* Lost Quad Mode and Alerts - RCX03-787 Low Voltage Active Buzzer
|
||||||
*/
|
*/
|
||||||
#define BEEPER PA2
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA2
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
/* Serial Peripheral Interface (SPI) - Up to 50 Mbit/s on F7
|
/* Serial Peripheral Interface (SPI) - Up to 50 Mbit/s on F7
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PB7
|
#define LED0_PIN PB7
|
||||||
#define LED1_PIN PB6
|
#define LED1_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB2 // Unused pin, can be mapped to elsewhere
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
|
|
|
@ -26,7 +26,8 @@
|
||||||
#define LED0_PIN PB6 //red
|
#define LED0_PIN PB6 //red
|
||||||
#define LED1_PIN PB9 //blue
|
#define LED1_PIN PB9 //blue
|
||||||
|
|
||||||
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB2 // Unused pin, can be mapped to elsewhere
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB4
|
#define LED0_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PB3
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB3
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// PC13 used as inverter select GPIO for UART2
|
// PC13 used as inverter select GPIO for UART2
|
||||||
|
|
|
@ -32,7 +32,8 @@
|
||||||
#define LED1_PIN PB5
|
#define LED1_PIN PB5
|
||||||
#define LED2_PIN PB4
|
#define LED2_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC1
|
||||||
#define BEEPER_OPT PB7
|
#define BEEPER_OPT PB7
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
|
#define INVERTER_PIN_UART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
|
||||||
|
|
||||||
#define BEEPER PA15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA15
|
||||||
#define BEEPER_OPT PA2
|
#define BEEPER_OPT PA2
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -29,7 +29,8 @@
|
||||||
#define LED1_PIN 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 USE_BEEPER
|
||||||
|
#define BEEPER_PIN PE9 // Red LEDs - PE9/PE13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
#define LED1_PIN PC13
|
#define LED1_PIN PC13
|
||||||
#define LED2_PIN PC15
|
#define LED2_PIN PC15
|
||||||
|
|
||||||
#undef BEEPER
|
#undef USE_BEEPER
|
||||||
|
|
||||||
#define USE_GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN 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
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
||||||
|
|
||||||
#define LED0_PIN PB0
|
#define LED0_PIN PB0
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
//define camera control
|
//define camera control
|
||||||
|
|
|
@ -29,7 +29,8 @@
|
||||||
#define LED0_PIN PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1_PIN PC13
|
#define LED1_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PC5
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC5
|
||||||
|
|
||||||
#define INVERTER_PIN_UART2 PB2 // PB2 used as inverter select GPIO
|
#define INVERTER_PIN_UART2 PB2 // PB2 used as inverter select GPIO
|
||||||
|
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#define LED1_PIN PC14
|
#define LED1_PIN PC14
|
||||||
#define LED2_PIN PC13
|
#define LED2_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PB13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6500 interrupt
|
// MPU6500 interrupt
|
||||||
|
|
|
@ -113,7 +113,8 @@
|
||||||
#if defined(CRAZYFLIE2BQ)
|
#if defined(CRAZYFLIE2BQ)
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define BEEPER PC12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC12
|
||||||
|
|
||||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||||
|
|
|
@ -26,7 +26,8 @@
|
||||||
//LED & BEE-------------------------------
|
//LED & BEE-------------------------------
|
||||||
#define LED0_PIN PC14
|
#define LED0_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
//define camera control
|
//define camera control
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
// tqfp48 pin 38
|
// tqfp48 pin 38
|
||||||
#define LED2_PIN PA15
|
#define LED2_PIN PA15
|
||||||
|
|
||||||
#define BEEPER PB2
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB2
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -96,7 +96,7 @@
|
||||||
|
|
||||||
|
|
||||||
#undef USE_SERVOS
|
#undef USE_SERVOS
|
||||||
#undef BEEPER
|
#undef USE_BEEPER
|
||||||
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED1_PIN PE2 // Red LED
|
#define LED1_PIN PE2 // Red LED
|
||||||
#define LED2_PIN PE1 // Blue LED
|
#define LED2_PIN PE1 // Blue LED
|
||||||
|
|
||||||
#define BEEPER PE5
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PE5
|
||||||
|
|
||||||
#define INVERTER_PIN_UART6 PD3
|
#define INVERTER_PIN_UART6 PD3
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,8 @@
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
/*------------BEEPER---------------*/
|
/*------------BEEPER---------------*/
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,8 @@
|
||||||
#define LED0_PIN PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1_PIN PB5
|
#define LED1_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6000 interrupts
|
// MPU6000 interrupts
|
||||||
|
|
|
@ -35,7 +35,8 @@
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
/*------------BEEPER---------------*/
|
/*------------BEEPER---------------*/
|
||||||
#define BEEPER PA14
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA14
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PC13
|
#define LED0_PIN PC13
|
||||||
#define LED1_PIN PC14
|
#define LED1_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART6 PC8
|
#define INVERTER_PIN_UART6 PC8
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#define USE_TARGET_CONFIG
|
#define USE_TARGET_CONFIG
|
||||||
|
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART6 PC8
|
#define INVERTER_PIN_UART6 PC8
|
||||||
|
|
|
@ -31,7 +31,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PC14
|
#define LED0_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA8
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PD10
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PD10
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB7
|
#define LED0_PIN PB7
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MPU_INT_EXTI PC13
|
#define MPU_INT_EXTI PC13
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,8 @@
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2_PIN PB6
|
#define LED2_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC9
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#define INVERTER_PIN_UART3 PB15
|
#define INVERTER_PIN_UART3 PB15
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PA2
|
#define LED0_PIN PA2
|
||||||
|
|
||||||
#define BEEPER PD15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PD15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
|
|
|
@ -31,7 +31,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB1
|
#define LED0_PIN PB1
|
||||||
|
|
||||||
#define BEEPER PB13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -29,7 +29,8 @@
|
||||||
#define LED1 PC8 // blingbling
|
#define LED1 PC8 // blingbling
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC9
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PB12
|
#define MPU6000_CS_PIN PB12
|
||||||
|
|
|
@ -39,7 +39,8 @@
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA8
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,8 @@
|
||||||
#define LED0_PIN PA14 // Red LED
|
#define LED0_PIN PA14 // Red LED
|
||||||
#define LED1_PIN PA13 // Green LED
|
#define LED1_PIN PA13 // Green LED
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC1
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PB13
|
#define INVERTER_PIN_UART1 PB13
|
||||||
#define INVERTER_PIN_UART6 PB12
|
#define INVERTER_PIN_UART6 PB12
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MPU_INT_EXTI PA3
|
#define MPU_INT_EXTI PA3
|
||||||
|
|
|
@ -33,9 +33,11 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LUXV2_RACE
|
#ifdef LUXV2_RACE
|
||||||
#define BEEPER PB9
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB9
|
||||||
#else
|
#else
|
||||||
#define BEEPER PB13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB13
|
||||||
#endif
|
#endif
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#define LED0_PIN PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1_PIN PA14
|
#define LED1_PIN PA14
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#define LED0_PIN PC13
|
#define LED0_PIN PC13
|
||||||
#define LED1_PIN PC14
|
#define LED1_PIN PC14
|
||||||
|
|
||||||
#define BEEPER PB2
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB2
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// *************** Gyro & ACC **********************
|
// *************** Gyro & ACC **********************
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PC13
|
#define LED0_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1_PIN PA14
|
#define LED1_PIN PA14
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// *************** Gyro & ACC **********************
|
// *************** Gyro & ACC **********************
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA12
|
||||||
|
|
||||||
#define BARO_XCLR_PIN PC13
|
#define BARO_XCLR_PIN PC13
|
||||||
#define BARO_EOC_PIN PC14
|
#define BARO_EOC_PIN PC14
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PC14
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC14
|
||||||
|
|
||||||
#define USE_GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#define LED0_PIN PB5 // Blue LEDs - PB5
|
#define LED0_PIN PB5 // Blue LEDs - PB5
|
||||||
//#define LED1_PIN PB9 // Green LEDs - PB9
|
//#define LED1_PIN PB9 // Green LEDs - PB9
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6050 interrupts
|
// MPU6050 interrupts
|
||||||
|
|
|
@ -31,7 +31,8 @@
|
||||||
#define LED0_PIN PC3
|
#define LED0_PIN PC3
|
||||||
//#define LED1 PC4
|
//#define LED1 PC4
|
||||||
|
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -29,7 +29,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA12
|
||||||
|
|
||||||
#if defined(AFROMINI)
|
#if defined(AFROMINI)
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#define LED1_PIN PB5
|
#define LED1_PIN PB5
|
||||||
#define LED2_PIN PB4
|
#define LED2_PIN PB4
|
||||||
|
|
||||||
#define BEEPER PC1
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC1
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6500 interrupt
|
// MPU6500 interrupt
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PA4
|
#define LED0_PIN PA4
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_DSHOT_DMAR
|
#define USE_DSHOT_DMAR
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PA5 // Onboard LED
|
#define LED0_PIN PA5 // Onboard LED
|
||||||
|
|
||||||
//#define BEEPER PD12
|
//#define USE_BEEPER
|
||||||
|
//#define BEEPER_PIN PD12
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PB7
|
#define LED0_PIN PB7
|
||||||
#define LED1_PIN PB14
|
#define LED1_PIN PB14
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
|
|
|
@ -26,7 +26,8 @@
|
||||||
#define LED0_PIN PB7 // blue
|
#define LED0_PIN PB7 // blue
|
||||||
#define LED1_PIN PB14 // red
|
#define LED1_PIN PB14 // red
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
|
|
|
@ -37,7 +37,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -50,7 +50,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB5
|
#define LED0_PIN PB5
|
||||||
//#define LED1_PIN PB4 // Remove this at the next major release
|
//#define LED1_PIN PB4 // Remove this at the next major release
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#if defined(OMNIBUSF4SD) || defined(DYSF4PRO)
|
#if defined(OMNIBUSF4SD) || defined(DYSF4PRO)
|
||||||
|
|
|
@ -30,7 +30,9 @@
|
||||||
|
|
||||||
//LED & BEEPER------------------------------
|
//LED & BEEPER------------------------------
|
||||||
#define LED0_PIN PE0
|
#define LED0_PIN PE0
|
||||||
#define BEEPER PD15
|
|
||||||
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PD15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
//CAMERA CONTROL----------------------------
|
//CAMERA CONTROL----------------------------
|
||||||
|
|
|
@ -18,7 +18,8 @@
|
||||||
#define USBD_PRODUCT_STRING "PYRODRONEF4"
|
#define USBD_PRODUCT_STRING "PYRODRONEF4"
|
||||||
|
|
||||||
#define LED0_PIN PB4
|
#define LED0_PIN PB4
|
||||||
#define BEEPER PB5
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB5
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART1 PC3 // PC3 used as sBUS inverter select GPIO
|
#define INVERTER_PIN_UART1 PC3 // PC3 used as sBUS inverter select GPIO
|
||||||
|
|
|
@ -27,7 +27,8 @@
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PA12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA12
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -30,7 +30,8 @@
|
||||||
#define LED0_PIN PB4
|
#define LED0_PIN PB4
|
||||||
#define LED1_PIN PB5
|
#define LED1_PIN PB5
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -56,17 +56,21 @@
|
||||||
|
|
||||||
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
||||||
#if defined(AIRBOTF4) || defined(AIRBOTF4SD)
|
#if defined(AIRBOTF4) || defined(AIRBOTF4SD)
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#elif defined(REVOLT)
|
#elif defined(REVOLT)
|
||||||
#define BEEPER PB4
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB4
|
||||||
#elif defined(SOULF4)
|
#elif defined(SOULF4)
|
||||||
#define BEEPER PB6
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB6
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#else
|
#else
|
||||||
#define LED1_PIN 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 USE_BEEPER
|
||||||
|
#define BEEPER_PIN NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(REVOLT)
|
#if defined(REVOLT)
|
||||||
|
|
|
@ -26,7 +26,8 @@
|
||||||
#define LED0_PIN PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1_PIN PC13
|
#define LED1_PIN PC13
|
||||||
|
|
||||||
#define BEEPER PC13
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
|
|
||||||
#define MPU6500_CS_PIN PB12
|
#define MPU6500_CS_PIN PB12
|
||||||
#define MPU6500_SPI_INSTANCE SPI2
|
#define MPU6500_SPI_INSTANCE SPI2
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#define LED0_PIN PC1
|
#define LED0_PIN PC1
|
||||||
#define LED1_PIN PC0
|
#define LED1_PIN PC0
|
||||||
|
|
||||||
#define BEEPER PA8
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA8
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define MPU6000_CS_PIN PB2
|
#define MPU6000_CS_PIN PB2
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MPU_INT_EXTI PC13
|
#define MPU_INT_EXTI PC13
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "SIRF"
|
#define TARGET_BOARD_IDENTIFIER "SIRF"
|
||||||
|
|
||||||
#define LED0_PIN PB2
|
#define LED0_PIN PB2
|
||||||
#define BEEPER PA1
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA1
|
||||||
|
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#define LED0_PIN PB4 // Blue (Rev 1 & 2) - PB4
|
#define LED0_PIN PB4 // Blue (Rev 1 & 2) - PB4
|
||||||
#define LED1_PIN PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
#define LED1_PIN PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||||
|
|
||||||
#define BEEPER PA1
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA1
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6050 interrupts
|
// MPU6050 interrupts
|
||||||
|
|
|
@ -27,7 +27,8 @@
|
||||||
#define LED1_PIN PB4
|
#define LED1_PIN PB4
|
||||||
#define LED2_PIN PB6
|
#define LED2_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PC9
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC9
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART6 PC6
|
#define INVERTER_PIN_UART6 PC6
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#define LED0_PIN PA15
|
#define LED0_PIN PA15
|
||||||
#define LED1_PIN PC8
|
#define LED1_PIN PC8
|
||||||
|
|
||||||
#define BEEPER PC2
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC2
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -37,7 +37,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -51,7 +51,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PB8
|
#define LED0_PIN PB8
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -36,7 +36,8 @@
|
||||||
#define LED0_PIN PB3
|
#define LED0_PIN PB3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -33,7 +33,8 @@
|
||||||
#define LED0_PIN PB9
|
#define LED0_PIN PB9
|
||||||
#define LED1_PIN PB2
|
#define LED1_PIN PB2
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PA0
|
#define LED0_PIN PA0
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART2 PB2
|
#define INVERTER_PIN_UART2 PB2
|
||||||
|
|
|
@ -39,7 +39,8 @@
|
||||||
#define LED1_PIN PB2
|
#define LED1_PIN PB2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#if (SPRACINGF4NEO_REV >= 2)
|
#if (SPRACINGF4NEO_REV >= 2)
|
||||||
|
|
|
@ -40,7 +40,8 @@
|
||||||
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
||||||
#define LED1_INVERTED
|
#define LED1_INVERTED
|
||||||
|
|
||||||
#define BEEPER PD12
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PD12
|
||||||
#define BEEPER_PWM_HZ 2000 // Beeper PWM frequency in Hz
|
#define BEEPER_PWM_HZ 2000 // Beeper PWM frequency in Hz
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#define LED0_PIN PC14
|
#define LED0_PIN PC14
|
||||||
#define LED1_PIN PA13
|
#define LED1_PIN PA13
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define LED0_PIN PD14
|
#define LED0_PIN PD14
|
||||||
#define LED1_PIN PD15
|
#define LED1_PIN PD15
|
||||||
#define BEEPER PA0
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define INVERTER_PIN_UART6 PD7
|
#define INVERTER_PIN_UART6 PD7
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#define LED1_PIN PC14
|
#define LED1_PIN PC14
|
||||||
|
|
||||||
//BEEPER
|
//BEEPER
|
||||||
#define BEEPER PB14
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB14
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
// MPU6500 interrupt
|
// MPU6500 interrupt
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue