mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
*** IO Driver updates ***
LED driver update Buzzer driver update Inverter driver update Spektrum bind driver update
This commit is contained in:
parent
9e30e69cee
commit
7db5445bf7
35 changed files with 305 additions and 724 deletions
18
Makefile
18
Makefile
|
@ -397,7 +397,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drivers/flash_m25p16.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
|
@ -407,7 +407,6 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
|
@ -443,7 +442,7 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
|
|||
drivers/flash_m25p16.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/pwm_mapping.c \
|
||||
|
@ -453,7 +452,6 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
|
|||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
|
@ -474,7 +472,7 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drivers/bus_spi.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/pwm_mapping.c \
|
||||
|
@ -484,7 +482,6 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
|
@ -500,13 +497,12 @@ CJMCU_SRC = \
|
|||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rx.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
|
@ -532,7 +528,7 @@ CC3D_SRC = \
|
|||
drivers/flash_m25p16.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/pwm_mapping.c \
|
||||
|
@ -542,7 +538,6 @@ CC3D_SRC = \
|
|||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
|
@ -559,13 +554,12 @@ STM32F30x_COMMON_SRC += \
|
|||
drivers/bus_spi.c \
|
||||
drivers/display_ug2864hsweg01.h \
|
||||
drivers/gpio_stm32f30x.c \
|
||||
drivers/light_led_stm32f30x.c \
|
||||
drivers/light_led.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rx.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f30x.c \
|
||||
drivers/sound_beeper_stm32f30x.c \
|
||||
drivers/system_stm32f30x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f30x.c
|
||||
|
|
|
@ -20,26 +20,26 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef INVERTER
|
||||
#ifdef INVERTER
|
||||
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
|
||||
#include "inverter.h"
|
||||
|
||||
static const IO_t pin = DEFIO_IO(INVERTER);
|
||||
|
||||
void initInverter(void)
|
||||
{
|
||||
struct {
|
||||
GPIO_TypeDef *gpio;
|
||||
gpio_config_t cfg;
|
||||
} gpio_setup = {
|
||||
.gpio = INVERTER_GPIO,
|
||||
// configure for Push-Pull
|
||||
.cfg = { INVERTER_PIN, Mode_Out_PP, Speed_2MHz }
|
||||
};
|
||||
IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterSet(false);
|
||||
}
|
||||
|
||||
RCC_APB2PeriphClockCmd(INVERTER_PERIPHERAL, ENABLE);
|
||||
|
||||
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
|
||||
void inverterSet(bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -18,8 +18,9 @@
|
|||
#pragma once
|
||||
|
||||
#ifdef INVERTER
|
||||
#define INVERTER_OFF digitalLo(INVERTER_GPIO, INVERTER_PIN)
|
||||
#define INVERTER_ON digitalHi(INVERTER_GPIO, INVERTER_PIN)
|
||||
void inverterSet(bool on);
|
||||
#define INVERTER_OFF inverterSet(false)
|
||||
#define INVERTER_ON inverterSet(true)
|
||||
#else
|
||||
#define INVERTER_OFF do {} while(0)
|
||||
#define INVERTER_ON do {} while(0)
|
||||
|
@ -27,3 +28,5 @@
|
|||
|
||||
void initInverter(void);
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -15,27 +15,105 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
initLeds(void)
|
||||
{
|
||||
struct {
|
||||
GPIO_TypeDef *gpio;
|
||||
gpio_config_t cfg;
|
||||
} gpio_setup[] = {
|
||||
#include "platform.h"
|
||||
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
|
||||
#include "light_led.h"
|
||||
|
||||
static const IO_t leds[] = {
|
||||
#ifdef LED0
|
||||
{
|
||||
.gpio = LED0_GPIO,
|
||||
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
|
||||
},
|
||||
#endif
|
||||
DEFIO_IO(LED0),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
#ifdef LED1
|
||||
|
||||
{
|
||||
.gpio = LED1_GPIO,
|
||||
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
|
||||
},
|
||||
DEFIO_IO(LED1),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
#ifdef LED2
|
||||
DEFIO_IO(LED2),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
}
|
||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
||||
#ifdef LED0_A
|
||||
DEFIO_IO(LED0_A),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
#ifdef LED1_A
|
||||
DEFIO_IO(LED1_A),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
#ifdef LED2_A
|
||||
DEFIO_IO(LED2_A),
|
||||
#else
|
||||
DEFIO_IO(NONE),
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
|
||||
uint8_t ledPolarity = 0
|
||||
#ifdef LED0_INVERTED
|
||||
| BIT(0)
|
||||
#endif
|
||||
#ifdef LED1_INVERTED
|
||||
| BIT(1)
|
||||
#endif
|
||||
#ifdef LED2_INVERTED
|
||||
| BIT(2)
|
||||
#endif
|
||||
#ifdef LED0_A_INVERTED
|
||||
| BIT(3)
|
||||
#endif
|
||||
#ifdef LED1_A_INVERTED
|
||||
| BIT(4)
|
||||
#endif
|
||||
#ifdef LED2_A_INVERTED
|
||||
| BIT(5)
|
||||
#endif
|
||||
;
|
||||
|
||||
uint8_t ledOffset = 0;
|
||||
|
||||
void ledInit(bool alternative_led)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
||||
if (alternative_led)
|
||||
ledOffset = LED_NUMBER;
|
||||
#else
|
||||
UNUSED(alternative_led);
|
||||
#endif
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
LED2_OFF;
|
||||
|
||||
for (i = 0; i < LED_NUMBER; i++) {
|
||||
if (leds[i + ledOffset]) {
|
||||
IOInit(leds[i + ledOffset], OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
||||
}
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
LED2_OFF;
|
||||
}
|
||||
|
||||
void ledToggle(int led)
|
||||
{
|
||||
IOToggle(leds[led + ledOffset]);
|
||||
}
|
||||
|
||||
void ledSet(int led, bool on)
|
||||
{
|
||||
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
||||
}
|
||||
|
|
|
@ -17,56 +17,39 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
struct {
|
||||
GPIO_TypeDef *gpio;
|
||||
uint16_t pin;
|
||||
} led_config[3];
|
||||
#define LED_NUMBER 3
|
||||
|
||||
// Helpful macros
|
||||
#ifdef LED0
|
||||
#define LED0_TOGGLE digitalToggle(led_config[0].gpio, led_config[0].pin)
|
||||
#ifndef LED0_INVERTED
|
||||
#define LED0_OFF digitalHi(led_config[0].gpio, led_config[0].pin)
|
||||
#define LED0_ON digitalLo(led_config[0].gpio, led_config[0].pin)
|
||||
# define LED0_TOGGLE ledToggle(0)
|
||||
# define LED0_OFF ledSet(0, false)
|
||||
# define LED0_ON ledSet(0, true)
|
||||
#else
|
||||
#define LED0_OFF digitalLo(led_config[0].gpio, led_config[0].pin)
|
||||
#define LED0_ON digitalHi(led_config[0].gpio, led_config[0].pin)
|
||||
#endif // inverted
|
||||
#else
|
||||
#define LED0_TOGGLE do {} while(0)
|
||||
#define LED0_OFF do {} while(0)
|
||||
#define LED0_ON do {} while(0)
|
||||
# define LED0_TOGGLE do {} while(0)
|
||||
# define LED0_OFF do {} while(0)
|
||||
# define LED0_ON do {} while(0)
|
||||
#endif
|
||||
|
||||
#ifdef LED1
|
||||
#define LED1_TOGGLE digitalToggle(led_config[1].gpio, led_config[1].pin)
|
||||
#ifndef LED1_INVERTED
|
||||
#define LED1_OFF digitalHi(led_config[1].gpio, led_config[1].pin)
|
||||
#define LED1_ON digitalLo(led_config[1].gpio, led_config[1].pin)
|
||||
# define LED1_TOGGLE ledToggle(1)
|
||||
# define LED1_OFF ledSet(1, false)
|
||||
# define LED1_ON ledSet(1, true)
|
||||
#else
|
||||
#define LED1_OFF digitalLo(led_config[1].gpio, led_config[1].pin)
|
||||
#define LED1_ON digitalHi(led_config[1].gpio, led_config[1].pin)
|
||||
#endif // inverted
|
||||
#else
|
||||
#define LED1_TOGGLE do {} while(0)
|
||||
#define LED1_OFF do {} while(0)
|
||||
#define LED1_ON do {} while(0)
|
||||
# define LED1_TOGGLE do {} while(0)
|
||||
# define LED1_OFF do {} while(0)
|
||||
# define LED1_ON do {} while(0)
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef LED2
|
||||
#define LED2_TOGGLE digitalToggle(led_config[2].gpio, led_config[2].pin)
|
||||
#ifndef LED2_INVERTED
|
||||
#define LED2_OFF digitalHi(led_config[2].gpio, led_config[2].pin)
|
||||
#define LED2_ON digitalLo(led_config[2].gpio, led_config[2].pin)
|
||||
# define LED2_TOGGLE ledToggle(2)
|
||||
# define LED2_OFF ledSet(2, false)
|
||||
# define LED2_ON ledSet(2, true)
|
||||
#else
|
||||
#define LED2_OFF digitalLo(led_config[2].gpio, led_config[2].pin)
|
||||
#define LED2_ON digitalHi(led_config[2].gpio, led_config[2].pin)
|
||||
#endif // inverted
|
||||
#else
|
||||
#define LED2_TOGGLE do {} while(0)
|
||||
#define LED2_OFF do {} while(0)
|
||||
#define LED2_ON do {} while(0)
|
||||
# define LED2_TOGGLE do {} while(0)
|
||||
# define LED2_OFF do {} while(0)
|
||||
# define LED2_ON do {} while(0)
|
||||
#endif
|
||||
|
||||
void ledInit(bool alternative_led);
|
||||
void ledToggle(int led);
|
||||
void ledSet(int led, bool state);
|
||||
|
|
|
@ -1,64 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
|
||||
#include "light_led.h"
|
||||
|
||||
void ledInit(bool alternative_led)
|
||||
{
|
||||
UNUSED(alternative_led);
|
||||
#if defined(LED0) || defined(LED1) || defined(LED2)
|
||||
gpio_config_t cfg;
|
||||
cfg.mode = Mode_Out_PP;
|
||||
cfg.speed = Speed_2MHz;
|
||||
#ifdef LED0
|
||||
RCC_APB2PeriphClockCmd(LED0_PERIPHERAL, ENABLE);
|
||||
led_config[0].gpio = LED0_GPIO;
|
||||
led_config[0].pin = LED0_PIN;
|
||||
cfg.pin = led_config[0].pin;
|
||||
LED0_OFF;
|
||||
gpioInit(led_config[0].gpio, &cfg);
|
||||
#endif
|
||||
#ifdef LED1
|
||||
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
|
||||
led_config[1].gpio = LED1_GPIO;
|
||||
led_config[1].pin = LED1_PIN;
|
||||
cfg.pin = led_config[1].pin;
|
||||
LED1_OFF;
|
||||
gpioInit(led_config[1].gpio, &cfg);
|
||||
#endif
|
||||
#ifdef LED2
|
||||
RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE);
|
||||
led_config[2].gpio = LED2_GPIO;
|
||||
led_config[2].pin = LED2_PIN;
|
||||
cfg.pin = led_config[2].pin;
|
||||
LED2_OFF;
|
||||
gpioInit(led_config[2].gpio, &cfg);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
|
@ -1,88 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
#include "light_led.h"
|
||||
|
||||
void ledInit(bool alternative_led)
|
||||
{
|
||||
#if defined(LED0) || defined(LED1) || defined(LED2)
|
||||
gpio_config_t cfg;
|
||||
cfg.mode = Mode_Out_PP;
|
||||
cfg.speed = Speed_2MHz;
|
||||
#ifdef LED0
|
||||
if (alternative_led) {
|
||||
#ifdef LED0_PERIPHERAL_2
|
||||
RCC_AHBPeriphClockCmd(LED0_PERIPHERAL_2, ENABLE);
|
||||
led_config[0].gpio = LED0_GPIO_2;
|
||||
led_config[0].pin = LED0_PIN_2;
|
||||
#endif
|
||||
} else {
|
||||
RCC_AHBPeriphClockCmd(LED0_PERIPHERAL, ENABLE);
|
||||
led_config[0].gpio = LED0_GPIO;
|
||||
led_config[0].pin = LED0_PIN;
|
||||
}
|
||||
cfg.pin = led_config[0].pin;
|
||||
LED0_OFF;
|
||||
gpioInit(led_config[0].gpio, &cfg);
|
||||
#endif
|
||||
#ifdef LED1
|
||||
if (alternative_led) {
|
||||
#ifdef LED1_PERIPHERAL_2
|
||||
RCC_AHBPeriphClockCmd(LED1_PERIPHERAL_2, ENABLE);
|
||||
led_config[1].gpio = LED1_GPIO_2;
|
||||
led_config[1].pin = LED1_PIN_2;
|
||||
#endif
|
||||
} else {
|
||||
RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE);
|
||||
led_config[1].gpio = LED1_GPIO;
|
||||
led_config[1].pin = LED1_PIN;
|
||||
}
|
||||
cfg.pin = led_config[1].pin;
|
||||
LED1_OFF;
|
||||
gpioInit(led_config[1].gpio, &cfg);
|
||||
#endif
|
||||
#ifdef LED2
|
||||
if (alternative_led) {
|
||||
#ifdef LED2_PERIPHERAL_2
|
||||
RCC_AHBPeriphClockCmd(LED2_PERIPHERAL_2, ENABLE);
|
||||
led_config[2].gpio = LED2_GPIO_2;
|
||||
led_config[2].pin = LED2_PIN_2;
|
||||
#endif
|
||||
} else {
|
||||
RCC_AHBPeriphClockCmd(LED2_PERIPHERAL, ENABLE);
|
||||
led_config[2].gpio = LED2_GPIO;
|
||||
led_config[2].pin = LED2_PIN;
|
||||
}
|
||||
cfg.pin = led_config[2].pin;
|
||||
LED2_OFF;
|
||||
gpioInit(led_config[2].gpio, &cfg);
|
||||
#endif
|
||||
#else
|
||||
UNUSED(alternative_led);
|
||||
#endif
|
||||
}
|
||||
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
|
@ -31,49 +31,39 @@
|
|||
|
||||
#ifdef BEEPER
|
||||
|
||||
void (*systemBeepPtr)(bool onoff) = NULL;
|
||||
static IO_t beeperIO = DEFIO_IO(NONE);
|
||||
static bool beeperInverted = false;
|
||||
|
||||
static uint16_t beeperPin;
|
||||
|
||||
static void beepNormal(bool onoff)
|
||||
{
|
||||
if (onoff) {
|
||||
digitalLo(BEEP_GPIO, beeperPin);
|
||||
} else {
|
||||
digitalHi(BEEP_GPIO, beeperPin);
|
||||
}
|
||||
}
|
||||
|
||||
static void beepInverted(bool onoff)
|
||||
{
|
||||
if (onoff) {
|
||||
digitalHi(BEEP_GPIO, beeperPin);
|
||||
} else {
|
||||
digitalLo(BEEP_GPIO, beeperPin);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void systemBeep(bool onoff)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(onoff);
|
||||
UNUSED(onoff);
|
||||
#else
|
||||
systemBeepPtr(onoff);
|
||||
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
||||
#endif
|
||||
}
|
||||
|
||||
void beeperInit(beeperConfig_t *config)
|
||||
void systemBeepToggle(void)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(config);
|
||||
#else
|
||||
beeperPin = config->gpioPin;
|
||||
initBeeperHardware(config);
|
||||
if (config->isInverted)
|
||||
systemBeepPtr = beepInverted;
|
||||
else
|
||||
systemBeepPtr = beepNormal;
|
||||
BEEP_OFF;
|
||||
#ifdef BEEPER
|
||||
IOToggle(beeperIO);
|
||||
#endif
|
||||
}
|
||||
|
||||
void beeperInit(const beeperConfig_t *config)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(config);
|
||||
#else
|
||||
beeperIO = IOGetByTag(config->ioTag);
|
||||
beeperInverted = config->isInverted;
|
||||
|
||||
if (beeperIO) {
|
||||
IOInit(beeperIO, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP);
|
||||
}
|
||||
systemBeep(false);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -17,25 +17,25 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
||||
#ifdef BEEPER
|
||||
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN)
|
||||
#define BEEP_TOGGLE systemBeepToggle()
|
||||
#define BEEP_OFF systemBeep(false)
|
||||
#define BEEP_ON systemBeep(true)
|
||||
#else
|
||||
#define BEEP_TOGGLE
|
||||
#define BEEP_OFF
|
||||
#define BEEP_ON
|
||||
#define BEEP_TOGGLE do {} while(0)
|
||||
#define BEEP_OFF do {} while(0)
|
||||
#define BEEP_ON do {} while(0)
|
||||
#endif
|
||||
|
||||
typedef struct beeperConfig_s {
|
||||
uint32_t gpioPeripheral;
|
||||
uint16_t gpioPin;
|
||||
GPIO_TypeDef *gpioPort;
|
||||
GPIO_Mode gpioMode;
|
||||
bool isInverted;
|
||||
ioTag_t ioTag;
|
||||
unsigned isInverted : 1;
|
||||
unsigned isOD : 1;
|
||||
} beeperConfig_t;
|
||||
|
||||
void systemBeep(bool onoff);
|
||||
void beeperInit(beeperConfig_t *beeperConfig);
|
||||
void systemBeep(bool on);
|
||||
void systemBeepToggle(void);
|
||||
void beeperInit(const beeperConfig_t *beeperConfig);
|
||||
|
||||
void initBeeperHardware(beeperConfig_t *config);
|
||||
|
|
|
@ -1,46 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
|
||||
#include "sound_beeper.h"
|
||||
|
||||
void initBeeperHardware(beeperConfig_t *config)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(config);
|
||||
#else
|
||||
gpio_config_t gpioConfig = {
|
||||
config->gpioPin,
|
||||
config->gpioMode,
|
||||
Speed_2MHz
|
||||
};
|
||||
|
||||
RCC_APB2PeriphClockCmd(config->gpioPeripheral, ENABLE);
|
||||
|
||||
gpioInit(config->gpioPort, &gpioConfig);
|
||||
#endif
|
||||
}
|
|
@ -1,45 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
#include "sound_beeper.h"
|
||||
|
||||
void initBeeperHardware(beeperConfig_t *config)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(config);
|
||||
#else
|
||||
gpio_config_t gpioConfig = {
|
||||
config->gpioPin,
|
||||
config->gpioMode,
|
||||
Speed_2MHz
|
||||
};
|
||||
|
||||
RCC_AHBPeriphClockCmd(config->gpioPeripheral, ENABLE);
|
||||
|
||||
gpioInit(config->gpioPort, &gpioConfig);
|
||||
#endif
|
||||
}
|
|
@ -353,14 +353,12 @@ void init(void)
|
|||
|
||||
#ifdef BEEPER
|
||||
beeperConfig_t beeperConfig = {
|
||||
.gpioPeripheral = BEEP_PERIPHERAL,
|
||||
.gpioPin = BEEP_PIN,
|
||||
.gpioPort = BEEP_GPIO,
|
||||
.ioTag = IO_TAG(BEEPER),
|
||||
#ifdef BEEPER_INVERTED
|
||||
.gpioMode = Mode_Out_PP,
|
||||
.isOD = false,
|
||||
.isInverted = true
|
||||
#else
|
||||
.gpioMode = Mode_Out_OD,
|
||||
.isOD = true,
|
||||
.isInverted = false
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
#include "platform.h"
|
||||
#include "debug.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
|
@ -58,6 +59,13 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
|
|||
|
||||
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
|
||||
|
||||
#ifdef SPEKTRUM_BIND
|
||||
static IO_t BindPin = DEFIO_IO(NONE);
|
||||
#endif
|
||||
#ifdef HARDWARE_BIND_PLUG
|
||||
static IO_t BindPlug = DEFIO_IO(NONE);
|
||||
#endif
|
||||
|
||||
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
rxRuntimeConfigPtr = rxRuntimeConfig;
|
||||
|
@ -159,16 +167,13 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
|
|||
bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||
{
|
||||
#ifdef HARDWARE_BIND_PLUG
|
||||
gpio_config_t cfg = {
|
||||
BINDPLUG_PIN,
|
||||
Mode_IPU,
|
||||
Speed_2MHz
|
||||
};
|
||||
gpioInit(BINDPLUG_PORT, &cfg);
|
||||
BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN));
|
||||
IOInit(BindPlug, OWNER_SYSTEM, RESOURCE_INPUT);
|
||||
IOConfigGPIO(BindPlug, IOCFG_IPU);
|
||||
|
||||
// Check status of bind plug and exit if not active
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
if (digitalIn(BINDPLUG_PORT, BINDPLUG_PIN)) {
|
||||
if (IORead(BindPlug)) {
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
@ -194,15 +199,12 @@ void spektrumBind(rxConfig_t *rxConfig)
|
|||
|
||||
LED1_ON;
|
||||
|
||||
gpio_config_t cfg = {
|
||||
BIND_PIN,
|
||||
Mode_Out_OD,
|
||||
Speed_2MHz
|
||||
};
|
||||
gpioInit(BIND_PORT, &cfg);
|
||||
BindPin = IOGetByTag(IO_TAG(BIND_PIN));
|
||||
IOInit(BindPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(BindPin, IOCFG_OUT_PP);
|
||||
|
||||
// RX line, set high
|
||||
digitalHi(BIND_PORT, BIND_PIN);
|
||||
IOWrite(BindPin, true);
|
||||
|
||||
// Bind window is around 20-140ms after powerup
|
||||
delay(60);
|
||||
|
@ -213,13 +215,13 @@ void spektrumBind(rxConfig_t *rxConfig)
|
|||
LED0_OFF;
|
||||
LED2_OFF;
|
||||
// RX line, drive low for 120us
|
||||
digitalLo(BIND_PORT, BIND_PIN);
|
||||
IOWrite(BindPin, false);
|
||||
delayMicroseconds(120);
|
||||
|
||||
LED0_ON;
|
||||
LED2_ON;
|
||||
// RX line, drive high for 120us
|
||||
digitalHi(BIND_PORT, BIND_PIN);
|
||||
IOWrite(BindPin, true);
|
||||
delayMicroseconds(120);
|
||||
|
||||
}
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
|
@ -36,15 +36,18 @@ static const char * const hardwareRevisionNames[] = {
|
|||
|
||||
uint8_t hardwareRevision = UNKNOWN;
|
||||
|
||||
static IO_t HWDetectPin = DEFIO_IO(NONE);
|
||||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
gpio_config_t cfg = {HW_PIN, Mode_IPU, Speed_2MHz};
|
||||
RCC_AHBPeriphClockCmd(HW_PERIPHERAL, ENABLE);
|
||||
gpioInit(HW_GPIO, &cfg);
|
||||
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
|
||||
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT);
|
||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||
|
||||
// Check hardware revision
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
if (digitalIn(HW_GPIO, HW_PIN)) {
|
||||
|
||||
if (IORead(HWDetectPin)) {
|
||||
hardwareRevision = AFF3_REV_1;
|
||||
} else {
|
||||
hardwareRevision = AFF3_REV_2;
|
||||
|
|
|
@ -20,29 +20,17 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
|
||||
#define HW_GPIO GPIOB
|
||||
#define HW_PIN Pin_2
|
||||
#define HW_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define HW_PIN PB2
|
||||
|
||||
// LED's V1
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_4 // Blue LEDs - PB4
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_5 // Green LEDs - PB5
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0 PB4 // LED - PB4
|
||||
#define LED1 PB5 // LED - PB5
|
||||
|
||||
// LED's V2
|
||||
#define LED0_GPIO_2 GPIOB
|
||||
#define LED0_PIN_2 Pin_8 // Blue LEDs - PB8
|
||||
#define LED0_PERIPHERAL_2 RCC_AHBPeriph_GPIOB
|
||||
#define LED1_GPIO_2 GPIOB
|
||||
#define LED1_PIN_2 Pin_9 // Green LEDs - PB9
|
||||
#define LED1_PERIPHERAL_2 RCC_AHBPeriph_GPIOB
|
||||
#define LED0_A PB8 // LED - PB8
|
||||
#define LED1_A PB9 // LED - PB9
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_5 // White LEDs - PA5
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define BEEPER PA5 // LED - PA5
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
|
@ -78,10 +66,6 @@
|
|||
|
||||
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
|
||||
#define USE_USART2 // Receiver - RX (PA3)
|
||||
|
@ -160,20 +144,18 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
// alternative defaults for AlienFlight F3 target
|
||||
#define ALIENFLIGHT
|
||||
#define HARDWARE_BIND_PLUG
|
||||
|
||||
// Hardware bind plug at PB12 (Pin 25)
|
||||
#define BINDPLUG_PORT GPIOB
|
||||
#define BINDPLUG_PIN Pin_12
|
||||
#define BINDPLUG_PIN PB12
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
|
|
@ -17,20 +17,12 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED0
|
||||
#define LED0_PIN PB3 // PB3 (LED)
|
||||
|
||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) used as inverter select GPIO
|
||||
#define INVERTER_GPIO GPIOB
|
||||
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
|
||||
#define INVERTER_USART USART1
|
||||
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_15 // PA15 (Beeper)
|
||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define BEEPER PB15 // PA15 (Beeper)
|
||||
|
||||
#define MPU6000_CS_GPIO GPIOA
|
||||
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||
|
@ -115,13 +107,10 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3, PB11 (Flexport)
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define INVERTER
|
||||
#define BEEPER
|
||||
#define DISPLAY
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
|
@ -144,4 +133,4 @@
|
|||
// IO - from schematics
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(14))
|
||||
#define TARGET_IO_PORTC (BIT(14))
|
||||
|
|
|
@ -19,18 +19,12 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "CHF3" // Chebuzz F3
|
||||
|
||||
#define LED0_GPIO GPIOE
|
||||
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED0_PIN PE8 // Blue LEDs - PE8/PE12
|
||||
#define LED0_INVERTED
|
||||
#define LED1_GPIO GPIOE
|
||||
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
||||
#define LED1_INVERTED
|
||||
|
||||
#define BEEP_GPIO GPIOE
|
||||
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 18
|
||||
|
@ -107,10 +101,6 @@
|
|||
|
||||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -168,7 +158,6 @@
|
|||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
|
|
|
@ -20,19 +20,9 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
|
||||
#define LED0_GPIO GPIOC
|
||||
#define LED0_PIN Pin_14 // PC14 (LED)
|
||||
#define LED0
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
|
||||
#define LED1_GPIO GPIOC
|
||||
#define LED1_PIN Pin_13 // PC13 (LED)
|
||||
#define LED1
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
|
||||
#define LED2_GPIO GPIOC
|
||||
#define LED2_PIN Pin_15 // PC15 (LED)
|
||||
#define LED2
|
||||
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOC
|
||||
|
||||
#define LED0_PIN PC14 // PC14 (LED)
|
||||
#define LED1_PIN PC13 // PC13 (LED)
|
||||
#define LED2_PIN PC15 // PC15 (LED)
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6050
|
||||
|
@ -63,8 +53,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
|
||||
#define USE_QUAD_MIXER_ONLY
|
||||
|
@ -84,4 +73,4 @@
|
|||
// IO - assuming all IOs on 48pin package TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
|
|
|
@ -21,21 +21,11 @@
|
|||
#define BST_DEVICE_NAME "COLIBRI RACE"
|
||||
#define BST_DEVICE_NAME_LENGTH 12
|
||||
|
||||
#define LED0_GPIO GPIOC
|
||||
#define LED0_PIN Pin_15
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define LED0_PIN PC15
|
||||
#define LED1_PIN PC14
|
||||
#define LED2_PIN PC13
|
||||
|
||||
#define LED1_GPIO GPIOC
|
||||
#define LED1_PIN Pin_14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define LED2_GPIO GPIOC
|
||||
#define LED2_PIN Pin_13
|
||||
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define BEEP_GPIO GPIOB
|
||||
#define BEEP_PIN Pin_13
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BEEPER PB13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
@ -87,11 +77,6 @@
|
|||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define LED2
|
||||
|
||||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
|
@ -200,4 +185,4 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
|
|
@ -20,23 +20,15 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "DOGE"
|
||||
|
||||
// tqfp48 pin 34
|
||||
#define LED0_GPIO GPIOA
|
||||
#define LED0_PIN Pin_13
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define LED0_PIN PA13
|
||||
|
||||
// tqfp48 pin 37
|
||||
#define LED1_GPIO GPIOA
|
||||
#define LED1_PIN Pin_14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define LED1_PIN PA14
|
||||
|
||||
// tqfp48 pin 38
|
||||
#define LED2_GPIO GPIOA
|
||||
#define LED2_PIN Pin_15
|
||||
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define LED2_PIN Pa15
|
||||
|
||||
#define BEEP_GPIO GPIOB
|
||||
#define BEEP_PIN Pin_2
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// tqfp48 pin 3
|
||||
|
@ -103,11 +95,6 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_SPI_BMP280
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define LED2
|
||||
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
|
@ -193,7 +180,6 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// Use UART3 for speksat
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
|
|
@ -19,16 +19,10 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "EUF1"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_4 // PB4 (LED)
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED0_PIN PB3 // PB3 (LED)
|
||||
#define LED1_PIN PB4 // PB4 (LED)
|
||||
|
||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_GPIO GPIOB
|
||||
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
|
||||
#define MPU6000_CS_GPIO GPIOB
|
||||
|
@ -73,12 +67,8 @@
|
|||
|
||||
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
||||
|
||||
|
||||
#define SONAR
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define DISPLAY
|
||||
#define INVERTER
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -131,11 +121,10 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
// IO - stm32f103RCT6 in 64pin package (TODO)
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
|
|
|
@ -19,10 +19,7 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "IFF3"
|
||||
|
||||
#define LED0
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
||||
|
@ -115,8 +112,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
@ -140,4 +136,4 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
|
|
|
@ -20,21 +20,11 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "LUX"
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define LED0_GPIO GPIOC
|
||||
#define LED0_PIN Pin_15
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define LED0_PIN PC15
|
||||
#define LED1_PIN PC14
|
||||
#define LED2_PIN PC13
|
||||
|
||||
#define LED1_GPIO GPIOC
|
||||
#define LED1_PIN Pin_14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define LED2_GPIO GPIOC
|
||||
#define LED2_PIN Pin_13
|
||||
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define BEEP_GPIO GPIOB
|
||||
#define BEEP_PIN Pin_13
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BEEPER PB13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
@ -68,11 +58,6 @@
|
|||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define LED2
|
||||
|
||||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
|
@ -159,8 +144,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART1, PC5
|
||||
#define BIND_PORT GPIOC
|
||||
#define BIND_PIN Pin_5
|
||||
#define BIND_PIN PC5
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
@ -169,4 +153,4 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
|
|
@ -20,18 +20,11 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab
|
||||
#define USE_CLI
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_5 // Blue LEDs - PB5
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_9 // Green LEDs - PB9
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB5 // Blue LEDs - PB5
|
||||
//#define LED1_PIN PB9 // Green LEDs - PB9
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_0
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define BEEPER PA0
|
||||
#define BEEPER_INVERTED
|
||||
#define BEEPER
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 9
|
||||
|
||||
|
@ -65,8 +58,6 @@
|
|||
//#define MAG
|
||||
//#define USE_MAG_HMC5883
|
||||
|
||||
#define LED0
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -185,8 +176,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PB4
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_4
|
||||
#define BIND_PIN PB4
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
@ -194,4 +184,4 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
|
|
|
@ -22,16 +22,10 @@
|
|||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_4 // PB4 (LED)
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED0_PIN PB3 // PB3 (LED)
|
||||
#define LED1_PIN PB4 // PB4 (LED)
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define BEEPER PA12 // PA12 (Beeper)
|
||||
|
||||
#define BARO_XCLR_GPIO GPIOC
|
||||
#define BARO_XCLR_PIN Pin_13
|
||||
|
@ -39,9 +33,7 @@
|
|||
#define BARO_EOC_PIN Pin_14
|
||||
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
|
||||
|
||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_GPIO GPIOB
|
||||
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
|
||||
// SPI2
|
||||
|
@ -117,10 +109,6 @@
|
|||
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||
|
||||
#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define INVERTER
|
||||
#define DISPLAY
|
||||
|
||||
#define USE_USART1
|
||||
|
@ -185,24 +173,22 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// alternative defaults for AlienWii32 F1 target
|
||||
#ifdef ALIENWII32
|
||||
#ifdef ALIENFLIGHT
|
||||
#undef TARGET_BOARD_IDENTIFIER
|
||||
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienWii32 F1.
|
||||
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1.
|
||||
#undef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define HARDWARE_BIND_PLUG
|
||||
|
||||
// Hardware bind plug at PB5 (Pin 41)
|
||||
#define BINDPLUG_PORT GPIOB
|
||||
#define BINDPLUG_PIN Pin_5
|
||||
#define BINDPLUG_PIN PB5
|
||||
#endif
|
||||
|
||||
// IO - assuming all IOs on 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
|
|
|
@ -19,15 +19,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_12
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BEEP_GPIO GPIOB
|
||||
#define BEEP_PIN Pin_10
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED0_PIN PB12
|
||||
#define BEEPER PB10
|
||||
|
||||
#define GYRO
|
||||
#define ACC
|
||||
|
@ -50,12 +43,11 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
|
|
@ -23,18 +23,12 @@
|
|||
//#define OLIMEXINO_UNCUT_LED2_E_JUMPER
|
||||
|
||||
#ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER
|
||||
#define LED0_GPIO GPIOA
|
||||
#define LED0_PIN Pin_5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define LED0
|
||||
#define LED0_PIN PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
|
||||
#endif
|
||||
|
||||
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
|
||||
// "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit()
|
||||
#define LED1_GPIO GPIOA
|
||||
#define LED1_PIN Pin_1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define LED1
|
||||
#define LED1_PIN PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
|
||||
#endif
|
||||
|
||||
#define GYRO
|
||||
|
@ -118,4 +112,4 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
|
|
@ -19,21 +19,11 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "103R"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define LED0_PIN PB3 // PB3 (LED)
|
||||
#define LED1_PIN PB4 // PB4 (LED)
|
||||
#define LED2_PIN PD2 // PD2 (LED) - Labelled LED4
|
||||
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_4 // PB4 (LED)
|
||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
||||
#define LED2_GPIO GPIOD
|
||||
#define LED2_PIN Pin_2 // PD2 (LED) - Labelled LED4
|
||||
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOD
|
||||
|
||||
#define BEEP_GPIO GPIOA
|
||||
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define BEEPER PA12 // PA12 (Beeper)
|
||||
|
||||
#define BARO_XCLR_GPIO GPIOC
|
||||
#define BARO_XCLR_PIN Pin_13
|
||||
|
@ -41,9 +31,7 @@
|
|||
#define BARO_EOC_PIN Pin_14
|
||||
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
|
||||
|
||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_GPIO GPIOB
|
||||
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
|
||||
#define USE_SPI
|
||||
|
@ -99,11 +87,6 @@
|
|||
#define USE_FLASH_M25P16
|
||||
|
||||
#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define LED2
|
||||
#define INVERTER
|
||||
#define DISPLAY
|
||||
|
||||
#define USE_USART1
|
||||
|
@ -163,4 +146,4 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
|
|
|
@ -19,13 +19,9 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "RMDO" // Ready Made RC DoDo
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
@ -54,8 +50,6 @@
|
|||
#define USE_FLASH_M25P16
|
||||
|
||||
#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -151,8 +145,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -19,13 +19,9 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SING"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER PC15
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
|
||||
|
@ -42,9 +38,6 @@
|
|||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1 // JST-SH Serial - TX (PA9) RX (PA10)
|
||||
#define USE_USART2 // Input - TX (NC) RX (PA15)
|
||||
|
@ -130,8 +123,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA15
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_15
|
||||
#define BIND_PIN PA15
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -19,18 +19,11 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SPKY" // SParKY
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_4 // Blue (Rev 1 & 2) - PB4
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED1_GPIO GPIOB
|
||||
#define LED1_PIN Pin_5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB4 // Blue (Rev 1 & 2) - PB4
|
||||
#define LED1_PIN PB5 // Green (Rev 1) / Red (Rev 2) - PB5
|
||||
|
||||
#define BEEP_GPIO GPIOA //USE PWM10 as beeper signal
|
||||
#define BEEP_PIN Pin_1
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define BEEPER PA1
|
||||
#define BEEPER_INVERTED
|
||||
#define BEEPER
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
|
@ -58,9 +51,6 @@
|
|||
|
||||
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
||||
|
||||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7)
|
||||
#define USE_USART2 // Input - RX (PA3)
|
||||
|
@ -167,8 +157,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
#define BIND_PIN Pin_3
|
||||
#define BIND_PIN PA3
|
||||
|
||||
|
||||
// available IO pins (from schematics)
|
||||
|
|
|
@ -19,13 +19,9 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SRF3"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
@ -61,8 +57,6 @@
|
|||
#define USE_FLASH_M25P16
|
||||
|
||||
#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -160,8 +154,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -19,13 +19,9 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SPEV"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_8
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB8
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
|
||||
|
@ -61,8 +57,6 @@
|
|||
//#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||
|
||||
//#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USB_IO
|
||||
|
||||
|
@ -219,8 +213,7 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -22,13 +22,9 @@
|
|||
// early prototype had slightly different pin mappings.
|
||||
//#define SPRACINGF3MINI_MKII_REVA
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
|
||||
|
@ -64,8 +60,6 @@
|
|||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||
|
||||
#define SONAR
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USB_IO
|
||||
#define USB_CABLE_DETECTION
|
||||
|
@ -225,16 +219,14 @@
|
|||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PORT GPIOB
|
||||
#define BIND_PIN Pin_11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define HARDWARE_BIND_PLUG
|
||||
#define BINDPLUG_PORT BUTTON_B_PORT
|
||||
#define BINDPLUG_PIN BUTTON_B_PIN
|
||||
#define BINDPLUG_PIN PB0
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
|
|
|
@ -19,21 +19,12 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "SDF3" // STM Discovery F3
|
||||
|
||||
#define LED0_GPIO GPIOE
|
||||
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED0_PIN PE8 // Blue LEDs - PE8/PE12
|
||||
#define LED0_INVERTED
|
||||
#define LED1_GPIO GPIOE
|
||||
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED1_PIN PE10 // Orange LEDs - PE10/PE14
|
||||
#define LED1_INVERTED
|
||||
|
||||
#define BEEP_GPIO GPIOE
|
||||
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
||||
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_SPI
|
||||
|
@ -118,10 +109,6 @@
|
|||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -184,4 +171,4 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF 0x00ff
|
||||
#define TARGET_IO_PORTF 0x00ff
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue