mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
merge branch master into osd-improvement-master
This commit is contained in:
commit
b909c70353
138 changed files with 1104 additions and 1533 deletions
|
@ -85,7 +85,7 @@ static inline uint8_t __basepriSetRetVal(uint8_t prio)
|
|||
// ideally this would only protect memory passed as parameter (any type should work), but gcc is curently creating almost full barrier
|
||||
// this macro can be used only ONCE PER LINE, but multiple uses per block are fine
|
||||
|
||||
#if (__GNUC__ > 4)
|
||||
#if (__GNUC__ > 5)
|
||||
#warning "Please verify that ATOMIC_BARRIER works as intended"
|
||||
// increment version number is BARRIER works
|
||||
// TODO - use flag to disable ATOMIC_BARRIER and use full barrier instead
|
||||
|
|
|
@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
|||
putf(putp, ch); written++;
|
||||
} else {
|
||||
char lz = 0;
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
char lng = 0;
|
||||
#endif
|
||||
int w = 0;
|
||||
|
@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
|||
if (ch >= '0' && ch <= '9') {
|
||||
ch = a2i(ch, &fmt, 10, &w);
|
||||
}
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
if (ch == 'l') {
|
||||
ch = *(fmt++);
|
||||
lng = 1;
|
||||
|
@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
|||
case 0:
|
||||
goto abort;
|
||||
case 'u':{
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
if (lng)
|
||||
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
|
||||
else
|
||||
|
@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
|||
break;
|
||||
}
|
||||
case 'd':{
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
if (lng)
|
||||
li2a(va_arg(va, unsigned long int), bf);
|
||||
else
|
||||
|
@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
|||
}
|
||||
case 'x':
|
||||
case 'X':
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
if (lng)
|
||||
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
|
||||
else
|
||||
|
|
|
@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function,
|
|||
something like :
|
||||
|
||||
void putc ( void* p, char c)
|
||||
{
|
||||
while (!SERIAL_PORT_EMPTY) ;
|
||||
SERIAL_PORT_TX_REGISTER = c;
|
||||
}
|
||||
{
|
||||
while (!SERIAL_PORT_EMPTY) ;
|
||||
SERIAL_PORT_TX_REGISTER = c;
|
||||
}
|
||||
|
||||
Before you can call printf you need to initialize it to use your
|
||||
character output function with something like:
|
||||
|
|
|
@ -835,7 +835,7 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
|
||||
#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
|
||||
featureClear(FEATURE_DISPLAY);
|
||||
}
|
||||
|
|
|
@ -17,7 +17,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if FLASH_SIZE <= 128
|
||||
#define MAX_PROFILE_COUNT 2
|
||||
#else
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#endif
|
||||
#define MAX_RATEPROFILES 3
|
||||
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
||||
|
||||
|
|
|
@ -76,7 +76,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
|
|||
UNUSED(SPIx); // FIXME
|
||||
|
||||
mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN));
|
||||
IOInit(mpul3gd20CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(mpul3gd20CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
DISABLE_L3GD20;
|
||||
|
|
|
@ -105,7 +105,7 @@ static inline void mma8451ConfigureInterrupt(void)
|
|||
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
|
||||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
||||
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
||||
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_SYSTEM, RESOURCE_I2C);
|
||||
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
#endif
|
||||
|
||||
|
|
|
@ -244,7 +244,7 @@ void mpuIntExtiInit(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
|
||||
IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
|
||||
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
||||
|
|
|
@ -159,7 +159,7 @@ bool mpu6000SpiDetect(void)
|
|||
#ifdef MPU6000_CS_PIN
|
||||
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
|
||||
#endif
|
||||
IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
||||
|
|
|
@ -69,7 +69,7 @@ static void mpu6500SpiInit(void)
|
|||
}
|
||||
|
||||
mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN));
|
||||
IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(mpuSpi6500CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
|
|
|
@ -191,7 +191,7 @@ bool mpu9250SpiDetect(void)
|
|||
#ifdef MPU9250_CS_PIN
|
||||
mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
|
||||
#endif
|
||||
IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
|
||||
|
|
|
@ -123,7 +123,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i, 0);
|
||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
||||
|
|
|
@ -139,7 +139,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i,0);
|
||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
||||
adcConfig[i].dmaIndex = adcChannelCount++;
|
||||
|
|
|
@ -134,7 +134,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
|
||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
||||
|
|
|
@ -143,7 +143,7 @@ void bmp085InitXclrIO(const bmp085Config_t *config)
|
|||
{
|
||||
if (!xclrIO && config && config->xclrIO) {
|
||||
xclrIO = IOGetByTag(config->xclrIO);
|
||||
IOInit(xclrIO, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(xclrIO, OWNER_BARO, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -65,7 +65,7 @@ void bmp280SpiInit(void)
|
|||
}
|
||||
|
||||
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
|
||||
IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI);
|
||||
IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
|
||||
|
||||
DISABLE_BMP280;
|
||||
|
|
|
@ -385,8 +385,8 @@ void i2cInit(I2CDevice device)
|
|||
IO_t scl = IOGetByTag(i2c->scl);
|
||||
IO_t sda = IOGetByTag(i2c->sda);
|
||||
|
||||
IOInit(scl, OWNER_SYSTEM, RESOURCE_I2C);
|
||||
IOInit(sda, OWNER_SYSTEM, RESOURCE_I2C);
|
||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
||||
|
||||
// Enable RCC
|
||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||
|
|
|
@ -92,7 +92,10 @@ void i2cInit(I2CDevice device)
|
|||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
||||
|
||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
||||
|
||||
I2C_InitTypeDef i2cInit = {
|
||||
|
|
|
@ -113,19 +113,13 @@ void spiInitDevice(SPIDevice device)
|
|||
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
||||
|
||||
#if defined(STM32F303xC) || defined(STM32F4)
|
||||
if (spi->sdcard) {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
|
||||
}
|
||||
else {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
|
||||
}
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
|
||||
|
||||
if (spi->nss)
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz)
|
||||
#else
|
||||
#error "Unknown processor"
|
||||
#endif
|
||||
|
|
|
@ -203,7 +203,7 @@ bool m25p16_init()
|
|||
#ifdef M25P16_CS_PIN
|
||||
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
|
||||
#endif
|
||||
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI);
|
||||
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
DISABLE_M25P16;
|
||||
|
|
|
@ -31,7 +31,7 @@ static const IO_t pin = DEFIO_IO(INVERTER);
|
|||
|
||||
void initInverter(void)
|
||||
{
|
||||
IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterSet(false);
|
||||
|
|
|
@ -53,6 +53,19 @@ const struct ioPortDef_s ioPortDefs[] = {
|
|||
};
|
||||
# endif
|
||||
|
||||
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||
"FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER",
|
||||
"SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD",
|
||||
"BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER"
|
||||
};
|
||||
|
||||
const char * const resourceNames[RESOURCE_TOTAL_COUNT] = {
|
||||
"", // NONE
|
||||
"IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL",
|
||||
"SDA", "SCK","MOSI","MISO","CS","BATTERY","RSSI","EXT","CURRENT"
|
||||
};
|
||||
|
||||
|
||||
ioRec_t* IO_Rec(IO_t io)
|
||||
{
|
||||
return io;
|
||||
|
@ -190,12 +203,12 @@ void IOToggle(IO_t io)
|
|||
}
|
||||
|
||||
// claim IO pin, set owner and resources
|
||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources)
|
||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index)
|
||||
{
|
||||
ioRec_t *ioRec = IO_Rec(io);
|
||||
if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
|
||||
ioRec->owner = owner;
|
||||
ioRec->resourcesUsed |= resources;
|
||||
ioRec->owner = owner;
|
||||
ioRec->resource = resource;
|
||||
ioRec->index = index;
|
||||
}
|
||||
|
||||
void IORelease(IO_t io)
|
||||
|
@ -210,10 +223,10 @@ resourceOwner_t IOGetOwner(IO_t io)
|
|||
return ioRec->owner;
|
||||
}
|
||||
|
||||
resourceType_t IOGetResources(IO_t io)
|
||||
resourceType_t IOGetResource(IO_t io)
|
||||
{
|
||||
ioRec_t *ioRec = IO_Rec(io);
|
||||
return ioRec->resourcesUsed;
|
||||
return ioRec->resource;
|
||||
}
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
|
|
@ -86,7 +86,7 @@ void IOHi(IO_t io);
|
|||
void IOLo(IO_t io);
|
||||
void IOToggle(IO_t io);
|
||||
|
||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources);
|
||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index);
|
||||
void IORelease(IO_t io); // unimplemented
|
||||
resourceOwner_t IOGetOwner(IO_t io);
|
||||
resourceType_t IOGetResources(IO_t io);
|
||||
|
|
|
@ -12,7 +12,8 @@ typedef struct ioRec_s {
|
|||
GPIO_TypeDef *gpio;
|
||||
uint16_t pin;
|
||||
resourceOwner_t owner;
|
||||
resourceType_t resourcesUsed; // TODO!
|
||||
resourceType_t resource;
|
||||
uint8_t index;
|
||||
} ioRec_t;
|
||||
|
||||
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||
|
|
|
@ -82,25 +82,25 @@ uint8_t ledOffset = 0;
|
|||
|
||||
void ledInit(bool alternative_led)
|
||||
{
|
||||
uint32_t i;
|
||||
uint32_t i;
|
||||
|
||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
||||
if (alternative_led)
|
||||
ledOffset = LED_NUMBER;
|
||||
if (alternative_led)
|
||||
ledOffset = LED_NUMBER;
|
||||
#else
|
||||
UNUSED(alternative_led);
|
||||
UNUSED(alternative_led);
|
||||
#endif
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
LED2_OFF;
|
||||
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);
|
||||
}
|
||||
}
|
||||
for (i = 0; i < LED_NUMBER; i++) {
|
||||
if (leds[i + ledOffset]) {
|
||||
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
|
||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
||||
}
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
@ -109,11 +109,11 @@ void ledInit(bool alternative_led)
|
|||
|
||||
void ledToggle(int led)
|
||||
{
|
||||
IOToggle(leds[led + ledOffset]);
|
||||
IOToggle(leds[led + ledOffset]);
|
||||
}
|
||||
|
||||
void ledSet(int led, bool on)
|
||||
{
|
||||
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
||||
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
||||
}
|
||||
|
|
|
@ -48,9 +48,11 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
|
||||
|
||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
||||
|
@ -103,8 +105,6 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE);
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811Initialised = true;
|
||||
setStripColor(&hsv_white);
|
||||
ws2811UpdateStrip();
|
||||
|
|
|
@ -57,9 +57,11 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
||||
|
||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
||||
|
@ -109,8 +111,6 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE);
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811Initialised = true;
|
||||
setStripColor(&hsv_white);
|
||||
ws2811UpdateStrip();
|
||||
|
|
|
@ -67,7 +67,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
||||
|
||||
// Stop timer
|
||||
|
|
|
@ -55,7 +55,8 @@ MAX7456_CHAR_TYPE* max7456_get_screen_buffer(void) {
|
|||
return SCREEN_BUFFER;
|
||||
}
|
||||
|
||||
static uint8_t max7456_send(uint8_t add, uint8_t data) {
|
||||
static uint8_t max7456_send(uint8_t add, uint8_t data)
|
||||
{
|
||||
spiTransferByte(MAX7456_SPI_INSTANCE, add);
|
||||
return spiTransferByte(MAX7456_SPI_INSTANCE, data);
|
||||
}
|
||||
|
@ -157,7 +158,7 @@ void max7456_init(uint8_t video_system)
|
|||
#ifdef MAX7456_SPI_CS_PIN
|
||||
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
|
||||
#endif
|
||||
IOInit(max7456CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(max7456CsPin, OWNER_OSD, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
//Minimum spi clock period for max7456 is 100ns (10Mhz)
|
||||
|
|
|
@ -93,16 +93,6 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void)
|
|||
return &pwmOutputConfiguration;
|
||||
}
|
||||
|
||||
bool CheckGPIOPin(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
|
||||
{
|
||||
return IO_GPIOBYTAG(tag) == gpio && IO_PINBYTAG(tag) == pin;
|
||||
}
|
||||
|
||||
bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
|
||||
{
|
||||
return IO_GPIOBYTAG(tag) == gpio && IO_GPIO_PinSource(IOGetByTag(tag)) == pin;
|
||||
}
|
||||
|
||||
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||
{
|
||||
int i = 0;
|
||||
|
@ -142,9 +132,9 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
continue;
|
||||
#endif
|
||||
|
||||
#if defined(STM32F303xC) && defined(USE_USART3)
|
||||
#if defined(STM32F303xC) && defined(USE_UART3)
|
||||
// skip UART3 ports (PB10/PB11)
|
||||
if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_RX_PIN)))
|
||||
if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN)))
|
||||
continue;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -84,18 +84,15 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
|
|||
}
|
||||
}
|
||||
|
||||
static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode)
|
||||
{
|
||||
IOInit(IOGetByTag(pin), OWNER_PWMOUTPUT_MOTOR, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(IOGetByTag(pin), mode);
|
||||
}
|
||||
|
||||
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value)
|
||||
{
|
||||
pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
|
||||
|
||||
configTimeBase(timerHardware->tim, period, mhz);
|
||||
pwmGPIOConfig(timerHardware->tag, IOCFG_AF_PP);
|
||||
|
||||
IO_t io = IOGetByTag(timerHardware->tag);
|
||||
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
|
||||
IOConfigGPIO(io, IOCFG_AF_PP);
|
||||
|
||||
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
|
||||
|
||||
|
|
|
@ -337,12 +337,6 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
|||
}
|
||||
}
|
||||
|
||||
static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode)
|
||||
{
|
||||
IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT);
|
||||
IOConfigGPIO(IOGetByTag(pin), mode);
|
||||
}
|
||||
|
||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||
{
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||
|
@ -372,7 +366,10 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
|
|||
self->mode = INPUT_MODE_PWM;
|
||||
self->timerHardware = timerHardwarePtr;
|
||||
|
||||
pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode);
|
||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
|
||||
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
||||
|
||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
||||
|
||||
timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ);
|
||||
|
@ -401,7 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
|||
self->mode = INPUT_MODE_PPM;
|
||||
self->timerHardware = timerHardwarePtr;
|
||||
|
||||
pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode);
|
||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(io, timerHardwarePtr->ioMode);
|
||||
|
||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
||||
|
||||
timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ);
|
||||
|
|
|
@ -1,46 +1,52 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define RESOURCE_INDEX(x) x + 1
|
||||
|
||||
typedef enum {
|
||||
OWNER_FREE = 0,
|
||||
OWNER_PWMINPUT,
|
||||
OWNER_PPMINPUT,
|
||||
OWNER_PWMOUTPUT_MOTOR,
|
||||
OWNER_PWMOUTPUT_SERVO,
|
||||
OWNER_SOFTSERIAL_RX,
|
||||
OWNER_SOFTSERIAL_TX,
|
||||
OWNER_SOFTSERIAL_RXTX, // bidirectional pin for softserial
|
||||
OWNER_SOFTSERIAL_AUXTIMER, // timer channel is used for softserial. No IO function on pin
|
||||
OWNER_MOTOR,
|
||||
OWNER_SERVO,
|
||||
OWNER_SOFTSERIAL,
|
||||
OWNER_ADC,
|
||||
OWNER_SERIAL_RX,
|
||||
OWNER_SERIAL_TX,
|
||||
OWNER_SERIAL_RXTX,
|
||||
OWNER_SERIAL,
|
||||
OWNER_PINDEBUG,
|
||||
OWNER_TIMER,
|
||||
OWNER_SONAR,
|
||||
OWNER_SYSTEM,
|
||||
OWNER_SPI,
|
||||
OWNER_I2C,
|
||||
OWNER_SDCARD,
|
||||
OWNER_FLASH,
|
||||
OWNER_USB,
|
||||
OWNER_BEEPER,
|
||||
OWNER_OSD,
|
||||
OWNER_BARO,
|
||||
OWNER_MPU,
|
||||
OWNER_INVERTER,
|
||||
OWNER_LED_STRIP,
|
||||
OWNER_LED,
|
||||
OWNER_RX,
|
||||
OWNER_TX,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_t;
|
||||
|
||||
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
|
||||
|
||||
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)
|
||||
// with mode switching (shared serial ports, ...) this will need some improvement
|
||||
typedef enum {
|
||||
RESOURCE_NONE = 0,
|
||||
RESOURCE_INPUT = 1 << 0,
|
||||
RESOURCE_OUTPUT = 1 << 1,
|
||||
RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT,
|
||||
RESOURCE_TIMER = 1 << 2,
|
||||
RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too
|
||||
RESOURCE_USART = 1 << 4,
|
||||
RESOURCE_ADC = 1 << 5,
|
||||
RESOURCE_EXTI = 1 << 6,
|
||||
RESOURCE_I2C = 1 << 7,
|
||||
RESOURCE_SPI = 1 << 8,
|
||||
RESOURCE_INPUT, RESOURCE_OUTPUT, RESOURCE_IO,
|
||||
RESOURCE_TIMER,
|
||||
RESOURCE_UART_TX, RESOURCE_UART_RX, RESOURCE_UART_TXRX,
|
||||
RESOURCE_EXTI,
|
||||
RESOURCE_I2C_SCL, RESOURCE_I2C_SDA,
|
||||
RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS,
|
||||
RESOURCE_ADC_BATTERY, RESOURCE_ADC_RSSI, RESOURCE_ADC_EXTERNAL1, RESOURCE_ADC_CURRENT,
|
||||
RESOURCE_TOTAL_COUNT
|
||||
} resourceType_t;
|
||||
|
||||
extern const char * const resourceNames[RESOURCE_TOTAL_COUNT];
|
||||
|
|
|
@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void)
|
|||
{
|
||||
#ifdef SDCARD_DETECT_PIN
|
||||
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
||||
IOInit(sdCardDetectPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0);
|
||||
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
|
||||
#endif
|
||||
}
|
||||
|
@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void)
|
|||
{
|
||||
#ifdef SDCARD_DETECT_PIN
|
||||
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
||||
IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT);
|
||||
IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
|
||||
#endif
|
||||
}
|
||||
|
@ -547,7 +547,7 @@ void sdcard_init(bool useDMA)
|
|||
|
||||
#ifdef SDCARD_SPI_CS_PIN
|
||||
sdCardCsPin = IOGetByTag(IO_TAG(SDCARD_SPI_CS_PIN));
|
||||
IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI);
|
||||
IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG);
|
||||
#endif // SDCARD_SPI_CS_PIN
|
||||
|
||||
|
|
|
@ -100,19 +100,20 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
|||
}
|
||||
}
|
||||
|
||||
static void softSerialGPIOConfig(ioTag_t pin, ioConfig_t mode)
|
||||
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||
{
|
||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL_RXTX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(pin), mode);
|
||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
|
||||
#else
|
||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP);
|
||||
#endif
|
||||
}
|
||||
|
||||
void serialInputPortConfig(ioTag_t pin)
|
||||
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||
{
|
||||
#ifdef STM32F1
|
||||
softSerialGPIOConfig(pin, IOCFG_IPU);
|
||||
#else
|
||||
softSerialGPIOConfig(pin, IOCFG_AF_PP_UP);
|
||||
#endif
|
||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
|
||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
|
||||
}
|
||||
|
||||
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
||||
|
@ -164,11 +165,6 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t
|
|||
timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL);
|
||||
}
|
||||
|
||||
static void serialOutputPortConfig(ioTag_t pin)
|
||||
{
|
||||
softSerialGPIOConfig(pin, IOCFG_OUT_PP);
|
||||
}
|
||||
|
||||
static void resetBuffers(softSerial_t *softSerial)
|
||||
{
|
||||
softSerial->port.rxBufferSize = SOFTSERIAL_BUFFER_SIZE;
|
||||
|
@ -219,10 +215,10 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
softSerial->softSerialPortIndex = portIndex;
|
||||
|
||||
softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag);
|
||||
serialOutputPortConfig(softSerial->txTimerHardware->tag);
|
||||
serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex);
|
||||
|
||||
softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag);
|
||||
serialInputPortConfig(softSerial->rxTimerHardware->tag);
|
||||
serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex);
|
||||
|
||||
setTxSignal(softSerial, ENABLE);
|
||||
delay(50);
|
||||
|
@ -271,8 +267,6 @@ void processTxState(softSerial_t *softSerial)
|
|||
softSerial->isTransmittingData = false;
|
||||
}
|
||||
|
||||
|
||||
|
||||
enum {
|
||||
TRAILING,
|
||||
LEADING
|
||||
|
|
|
@ -99,26 +99,26 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
uartPort_t *s = NULL;
|
||||
|
||||
if (USARTx == USART1) {
|
||||
s = serialUSART1(baudRate, mode, options);
|
||||
#ifdef USE_USART2
|
||||
s = serialUART1(baudRate, mode, options);
|
||||
#ifdef USE_UART2
|
||||
} else if (USARTx == USART2) {
|
||||
s = serialUSART2(baudRate, mode, options);
|
||||
s = serialUART2(baudRate, mode, options);
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
} else if (USARTx == USART3) {
|
||||
s = serialUSART3(baudRate, mode, options);
|
||||
s = serialUART3(baudRate, mode, options);
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
} else if (USARTx == UART4) {
|
||||
s = serialUSART4(baudRate, mode, options);
|
||||
s = serialUART4(baudRate, mode, options);
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
} else if (USARTx == UART5) {
|
||||
s = serialUSART5(baudRate, mode, options);
|
||||
s = serialUART5(baudRate, mode, options);
|
||||
#endif
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
} else if (USARTx == USART6) {
|
||||
s = serialUSART6(baudRate, mode, options);
|
||||
s = serialUART6(baudRate, mode, options);
|
||||
#endif
|
||||
|
||||
} else {
|
||||
|
|
|
@ -23,10 +23,10 @@ extern const struct serialPortVTable uartVTable[];
|
|||
|
||||
void uartStartTxDMA(uartPort_t *s);
|
||||
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
|
||||
|
|
|
@ -29,34 +29,28 @@
|
|||
#include <platform.h>
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "nvic.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
static uartPort_t uartPort1;
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
static uartPort_t uartPort2;
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
static uartPort_t uartPort3;
|
||||
#endif
|
||||
|
||||
// Using RX DMA disables the use of receive callbacks
|
||||
#define USE_USART1_RX_DMA
|
||||
|
||||
#if defined(CC3D) // FIXME move board specific code to target.h files.
|
||||
#undef USE_USART1_RX_DMA
|
||||
#endif
|
||||
|
||||
void usartIrqCallback(uartPort_t *s)
|
||||
void uartIrqCallback(uartPort_t *s)
|
||||
{
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
|
@ -83,12 +77,10 @@ void usartIrqCallback(uartPort_t *s)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void USART1_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||
void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
DMA_Cmd(descriptor->channel, DISABLE);
|
||||
|
||||
|
@ -98,15 +90,13 @@ void USART1_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
|||
s->txDMAEmpty = true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
#ifdef USE_UART1
|
||||
// USART1 - Telemetry (RX/TX by DMA)
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
s = &uartPort1;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -121,41 +111,37 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->USARTx = USART1;
|
||||
|
||||
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
s->rxDMAChannel = DMA1_Channel5;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
#endif
|
||||
s->txDMAChannel = DMA1_Channel4;
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
|
||||
// USART1_TX PA9
|
||||
// USART1_RX PA10
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = Pin_9;
|
||||
// UART1_TX PA9
|
||||
// UART1_RX PA10
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TXRX, 1);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TX, 1);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = Pin_10;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL, RESOURCE_UART_RX, 1);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
// DMA TX Interrupt
|
||||
dmaSetHandler(DMA1_CH4_HANDLER, USART1_DMA_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, 0);
|
||||
dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1);
|
||||
|
||||
#ifndef USE_USART1_RX_DMA
|
||||
#ifndef USE_UART1_RX_DMA
|
||||
// RX/TX Interrupt
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
|
@ -169,24 +155,23 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
return s;
|
||||
}
|
||||
|
||||
|
||||
// USART1 Rx/Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
usartIrqCallback(s);
|
||||
uartIrqCallback(s);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort2;
|
||||
|
@ -204,27 +189,23 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
|
||||
// USART2_TX PA2
|
||||
// USART2_RX PA3
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = Pin_2;
|
||||
// UART2_TX PA2
|
||||
// UART2_RX PA3
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TXRX, 2);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TX, 2);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = Pin_3;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -243,19 +224,19 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort2;
|
||||
usartIrqCallback(s);
|
||||
uartIrqCallback(s);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
// USART3
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort3;
|
||||
|
@ -273,29 +254,20 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
#ifdef USART3_APB1_PERIPHERALS
|
||||
RCC_APB1PeriphClockCmd(USART3_APB1_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
#ifdef USART3_APB2_PERIPHERALS
|
||||
RCC_APB2PeriphClockCmd(USART3_APB2_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
||||
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = USART3_TX_PIN;
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = USART3_RX_PIN;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -313,6 +285,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
void USART3_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort3;
|
||||
usartIrqCallback(s);
|
||||
uartIrqCallback(s);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -30,79 +30,73 @@
|
|||
#include <platform.h>
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "nvic.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
// Using RX DMA disables the use of receive callbacks
|
||||
//#define USE_USART1_RX_DMA
|
||||
//#define USE_USART2_RX_DMA
|
||||
//#define USE_USART2_TX_DMA
|
||||
//#define USE_USART3_RX_DMA
|
||||
//#define USE_USART3_TX_DMA
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#ifdef USE_UART1
|
||||
#ifndef UART1_TX_PIN
|
||||
#define UART1_TX_PIN PA9 // PA9
|
||||
#endif
|
||||
#ifndef UART1_RX_PIN
|
||||
#define UART1_RX_PIN PA10 // PA10
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef UART2_GPIO
|
||||
#define UART2_TX_PIN GPIO_Pin_5 // PD5
|
||||
#define UART2_RX_PIN GPIO_Pin_6 // PD6
|
||||
#define UART2_GPIO GPIOD
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource5
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource6
|
||||
#ifdef USE_UART2
|
||||
#ifndef UART2_TX_PIN
|
||||
#define UART2_TX_PIN PD5 // PD5
|
||||
#endif
|
||||
#ifndef UART2_RX_PIN
|
||||
#define UART2_RX_PIN PD6 // PD6
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#ifdef USE_UART3
|
||||
#ifndef UART3_TX_PIN
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#endif
|
||||
#ifndef UART3_RX_PIN
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef UART4_GPIO
|
||||
#define UART4_TX_PIN GPIO_Pin_10 // PC10 (AF5)
|
||||
#define UART4_RX_PIN GPIO_Pin_11 // PC11 (AF5)
|
||||
#define UART4_GPIO_AF GPIO_AF_5
|
||||
#define UART4_GPIO GPIOC
|
||||
#define UART4_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART4_RX_PINSOURCE GPIO_PinSource11
|
||||
#ifdef USE_UART4
|
||||
#ifndef UART4_TX_PIN
|
||||
#define UART4_TX_PIN PC10 // PC10 (AF5)
|
||||
#endif
|
||||
#ifndef UART4_RX_PIN
|
||||
#define UART4_RX_PIN PC11 // PC11 (AF5)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef UART5_GPIO // The real UART5_RX is on PD2, no board is using.
|
||||
#define UART5_TX_PIN GPIO_Pin_12 // PC12 (AF5)
|
||||
#define UART5_RX_PIN GPIO_Pin_12 // PC12 (AF5)
|
||||
#define UART5_GPIO_AF GPIO_AF_5
|
||||
#define UART5_GPIO GPIOC
|
||||
#define UART5_TX_PINSOURCE GPIO_PinSource12
|
||||
#define UART5_RX_PINSOURCE GPIO_PinSource12
|
||||
#ifdef USE_UART5
|
||||
#ifndef UART5_TX_PIN // The real UART5_RX is on PD2, no board is using.
|
||||
#define UART5_TX_PIN PC12 // PC12 (AF5)
|
||||
#endif
|
||||
#ifndef UART5_RX_PIN
|
||||
#define UART5_RX_PIN PC12 // PC12 (AF5)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
static uartPort_t uartPort1;
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
static uartPort_t uartPort2;
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
static uartPort_t uartPort3;
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
static uartPort_t uartPort4;
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
static uartPort_t uartPort5;
|
||||
#endif
|
||||
|
||||
|
@ -118,13 +112,39 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
|
|||
s->txDMAEmpty = true;
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
|
||||
{
|
||||
if (options & SERIAL_BIDIR) {
|
||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
|
||||
(options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD,
|
||||
(options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||
);
|
||||
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, index);
|
||||
IOConfigGPIOAF(tx, ioCfg, af);
|
||||
|
||||
if (!(options & SERIAL_INVERTED))
|
||||
IOLo(tx); // OpenDrain output should be inactive
|
||||
} else {
|
||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
|
||||
IOConfigGPIOAF(tx, ioCfg, af);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
|
||||
IOConfigGPIOAF(rx, ioCfg, af);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_UART1
|
||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
s = &uartPort1;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -136,7 +156,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
|
||||
s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
|
||||
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
s->rxDMAChannel = DMA1_Channel5;
|
||||
#endif
|
||||
s->txDMAChannel = DMA1_Channel4;
|
||||
|
@ -146,39 +166,14 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1);
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||
if(!(options & SERIAL_INVERTED))
|
||||
GPIO_SetBits(UART1_GPIO, UART1_TX_PIN); // OpenDrain output should be inactive
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1);
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART1_RX_PIN;
|
||||
GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, UART1_GPIO_AF);
|
||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
|
||||
dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, 0);
|
||||
|
||||
|
||||
#ifndef USE_USART1_RX_DMA
|
||||
#ifndef USE_UART1_RX_DMA
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
|
||||
|
@ -192,13 +187,12 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART2
|
||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
s = &uartPort2;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -212,53 +206,29 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
|
||||
s->USARTx = USART2;
|
||||
|
||||
#ifdef USE_USART2_RX_DMA
|
||||
#ifdef USE_UART2_RX_DMA
|
||||
s->rxDMAChannel = DMA1_Channel6;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||
#endif
|
||||
#ifdef USE_USART2_TX_DMA
|
||||
#ifdef USE_UART2_TX_DMA
|
||||
s->txDMAChannel = DMA1_Channel7;
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||
#endif
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
||||
|
||||
#if defined(USE_USART2_TX_DMA) || defined(USE_USART2_RX_DMA)
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
#if defined(USE_UART2_TX_DMA) || defined(USE_UART2_RX_DMA)
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
#endif
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2);
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||
if(!(options & SERIAL_INVERTED))
|
||||
GPIO_SetBits(UART2_GPIO, UART2_TX_PIN); // OpenDrain output should be inactive
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART2_RX_PIN;
|
||||
GPIO_PinAFConfig(UART2_GPIO, UART2_RX_PINSOURCE, UART2_GPIO_AF);
|
||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_USART2_TX_DMA
|
||||
#ifdef USE_UART2_TX_DMA
|
||||
// DMA TX Interrupt
|
||||
dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, 0);
|
||||
dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, &uartPort2);
|
||||
#endif
|
||||
|
||||
#ifndef USE_USART2_RX_DMA
|
||||
#ifndef USE_UART2_RX_DMA
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
||||
|
@ -272,13 +242,12 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART3
|
||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
s = &uartPort3;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -292,53 +261,29 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
|
||||
s->USARTx = USART3;
|
||||
|
||||
#ifdef USE_USART3_RX_DMA
|
||||
#ifdef USE_UART3_RX_DMA
|
||||
s->rxDMAChannel = DMA1_Channel3;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||
#endif
|
||||
#ifdef USE_USART3_TX_DMA
|
||||
#ifdef USE_UART3_TX_DMA
|
||||
s->txDMAChannel = DMA1_Channel2;
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||
#endif
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
||||
|
||||
#if defined(USE_USART3_TX_DMA) || defined(USE_USART3_RX_DMA)
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
#if defined(USE_UART3_TX_DMA) || defined(USE_UART3_RX_DMA)
|
||||
RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
#endif
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7, 3);
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
|
||||
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||
if(!(options & SERIAL_INVERTED))
|
||||
GPIO_SetBits(UART3_GPIO, UART3_TX_PIN); // OpenDrain output should be inactive
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
|
||||
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART3_RX_PIN;
|
||||
GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, UART3_GPIO_AF);
|
||||
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_USART3_TX_DMA
|
||||
#ifdef USE_UART3_TX_DMA
|
||||
// DMA TX Interrupt
|
||||
dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, 0);
|
||||
dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, &uartPort3);
|
||||
#endif
|
||||
|
||||
#ifndef USE_USART3_RX_DMA
|
||||
#ifndef USE_UART3_RX_DMA
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
|
||||
|
@ -352,14 +297,13 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART4
|
||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx4Buffer[UART4_TX_BUFFER_SIZE];
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
s = &uartPort4;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -373,33 +317,9 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
|
||||
s->USARTx = UART4;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(UART4), ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN;
|
||||
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||
GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF);
|
||||
GPIO_Init(UART4_GPIO, &GPIO_InitStructure);
|
||||
if(!(options & SERIAL_INVERTED))
|
||||
GPIO_SetBits(UART4_GPIO, UART4_TX_PIN); // OpenDrain output should be inactive
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN;
|
||||
GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF);
|
||||
GPIO_Init(UART4_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART4_RX_PIN;
|
||||
GPIO_PinAFConfig(UART4_GPIO, UART4_RX_PINSOURCE, UART4_GPIO_AF);
|
||||
GPIO_Init(UART4_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5, 4);
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4);
|
||||
|
@ -411,14 +331,13 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART5
|
||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE];
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
s = &uartPort5;
|
||||
s->port.vTable = uartVTable;
|
||||
|
@ -432,33 +351,9 @@ uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
|
||||
s->USARTx = UART5;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(UART5), ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN;
|
||||
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||
GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF);
|
||||
GPIO_Init(UART5_GPIO, &GPIO_InitStructure);
|
||||
if(!(options & SERIAL_INVERTED))
|
||||
GPIO_SetBits(UART5_GPIO, UART5_TX_PIN); // OpenDrain output should be inactive
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN;
|
||||
GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF);
|
||||
GPIO_Init(UART5_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
GPIO_InitStructure.GPIO_Pin = UART5_RX_PIN;
|
||||
GPIO_PinAFConfig(UART5_GPIO, UART5_RX_PINSOURCE, UART5_GPIO_AF);
|
||||
GPIO_Init(UART5_GPIO, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5);
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5);
|
||||
|
@ -502,7 +397,7 @@ void usartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort1;
|
||||
|
@ -511,7 +406,7 @@ void USART1_IRQHandler(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort2;
|
||||
|
@ -520,7 +415,7 @@ void USART2_IRQHandler(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
void USART3_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort3;
|
||||
|
@ -529,7 +424,7 @@ void USART3_IRQHandler(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
void UART4_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort4;
|
||||
|
@ -538,7 +433,7 @@ void UART4_IRQHandler(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
void UART5_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort5;
|
||||
|
|
|
@ -31,14 +31,6 @@
|
|||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
// Using RX DMA disables the use of receive callbacks
|
||||
//#define USE_USART1_RX_DMA
|
||||
//#define USE_USART2_RX_DMA
|
||||
//#define USE_USART3_RX_DMA
|
||||
//#define USE_USART4_RX_DMA
|
||||
//#define USE_USART5_RX_DMA
|
||||
//#define USE_USART6_RX_DMA
|
||||
|
||||
#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
|
||||
|
||||
|
@ -72,20 +64,20 @@ typedef struct uartDevice_s {
|
|||
} uartDevice_t;
|
||||
|
||||
//static uartPort_t uartPort[MAX_UARTS];
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
static uartDevice_t uart1 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
.txDMAStream = DMA2_Stream7,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA2_Stream5,
|
||||
#endif
|
||||
.dev = USART1,
|
||||
.rx = IO_TAG(USART1_RX_PIN),
|
||||
.tx = IO_TAG(USART1_TX_PIN),
|
||||
.rx = IO_TAG(UART1_RX_PIN),
|
||||
.tx = IO_TAG(UART1_TX_PIN),
|
||||
.af = GPIO_AF_USART1,
|
||||
#ifdef USART1_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART1_AHB1_PERIPHERALS,
|
||||
#ifdef UART1_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb2 = RCC_APB2(USART1),
|
||||
.txIrq = DMA2_ST7_HANDLER,
|
||||
|
@ -95,20 +87,20 @@ static uartDevice_t uart1 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
static uartDevice_t uart2 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART2_RX_DMA
|
||||
#ifdef USE_UART2_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream5,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream6,
|
||||
.dev = USART2,
|
||||
.rx = IO_TAG(USART2_RX_PIN),
|
||||
.tx = IO_TAG(USART2_TX_PIN),
|
||||
.rx = IO_TAG(UART2_RX_PIN),
|
||||
.tx = IO_TAG(UART2_TX_PIN),
|
||||
.af = GPIO_AF_USART2,
|
||||
#ifdef USART2_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART2_AHB1_PERIPHERALS,
|
||||
#ifdef UART2_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(USART2),
|
||||
.txIrq = DMA1_ST6_HANDLER,
|
||||
|
@ -118,20 +110,20 @@ static uartDevice_t uart2 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
static uartDevice_t uart3 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART3_RX_DMA
|
||||
#ifdef USE_UART3_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream1,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream3,
|
||||
.dev = USART3,
|
||||
.rx = IO_TAG(USART3_RX_PIN),
|
||||
.tx = IO_TAG(USART3_TX_PIN),
|
||||
.rx = IO_TAG(UART3_RX_PIN),
|
||||
.tx = IO_TAG(UART3_TX_PIN),
|
||||
.af = GPIO_AF_USART3,
|
||||
#ifdef USART3_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART3_AHB1_PERIPHERALS,
|
||||
#ifdef UART3_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(USART3),
|
||||
.txIrq = DMA1_ST3_HANDLER,
|
||||
|
@ -141,20 +133,20 @@ static uartDevice_t uart3 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
static uartDevice_t uart4 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream2,
|
||||
#endif
|
||||
.txDMAStream = DMA1_Stream4,
|
||||
.dev = UART4,
|
||||
.rx = IO_TAG(USART4_RX_PIN),
|
||||
.tx = IO_TAG(USART4_TX_PIN),
|
||||
.rx = IO_TAG(UART4_RX_PIN),
|
||||
.tx = IO_TAG(UART4_TX_PIN),
|
||||
.af = GPIO_AF_UART4,
|
||||
#ifdef USART4_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART4_AHB1_PERIPHERALS,
|
||||
#ifdef UART4_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(UART4),
|
||||
.txIrq = DMA1_ST4_HANDLER,
|
||||
|
@ -164,20 +156,20 @@ static uartDevice_t uart4 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
static uartDevice_t uart5 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_4,
|
||||
#ifdef USE_USART1_RX_DMA
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
.rxDMAStream = DMA1_Stream0,
|
||||
#endif
|
||||
.txDMAStream = DMA2_Stream7,
|
||||
.dev = UART5,
|
||||
.rx = IO_TAG(USART5_RX_PIN),
|
||||
.tx = IO_TAG(USART5_TX_PIN),
|
||||
.rx = IO_TAG(UART5_RX_PIN),
|
||||
.tx = IO_TAG(UART5_TX_PIN),
|
||||
.af = GPIO_AF_UART5,
|
||||
#ifdef USART5_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART5_AHB1_PERIPHERALS,
|
||||
#ifdef UART5_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb1 = RCC_APB1(UART5),
|
||||
.txIrq = DMA2_ST7_HANDLER,
|
||||
|
@ -187,20 +179,20 @@ static uartDevice_t uart5 =
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
static uartDevice_t uart6 =
|
||||
{
|
||||
.DMAChannel = DMA_Channel_5,
|
||||
#ifdef USE_USART6_RX_DMA
|
||||
#ifdef USE_UART6_RX_DMA
|
||||
.rxDMAStream = DMA2_Stream1,
|
||||
#endif
|
||||
.txDMAStream = DMA2_Stream6,
|
||||
.dev = USART6,
|
||||
.rx = IO_TAG(USART6_RX_PIN),
|
||||
.tx = IO_TAG(USART6_TX_PIN),
|
||||
.rx = IO_TAG(UART6_RX_PIN),
|
||||
.tx = IO_TAG(UART6_TX_PIN),
|
||||
.af = GPIO_AF_USART6,
|
||||
#ifdef USART6_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = USART6_AHB1_PERIPHERALS,
|
||||
#ifdef UART6_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
.rcc_apb2 = RCC_APB2(USART6),
|
||||
.txIrq = DMA2_ST6_HANDLER,
|
||||
|
@ -211,39 +203,39 @@ static uartDevice_t uart6 =
|
|||
#endif
|
||||
|
||||
static uartDevice_t* uartHardwareMap[] = {
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
&uart1,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
&uart2,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
&uart3,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
&uart4,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
&uart5,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
&uart6,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
};
|
||||
|
||||
void usartIrqHandler(uartPort_t *s)
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
||||
if (s->port.callback) {
|
||||
|
@ -302,7 +294,7 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
|
|||
}
|
||||
}
|
||||
|
||||
uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
@ -344,17 +336,17 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p
|
|||
RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
||||
}
|
||||
else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_USART);
|
||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
||||
}
|
||||
}
|
||||
|
@ -373,86 +365,86 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p
|
|||
return s;
|
||||
}
|
||||
|
||||
#ifdef USE_USART1
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
#ifdef USE_UART1
|
||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_1, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_1, baudRate, mode, options);
|
||||
}
|
||||
|
||||
// USART1 Rx/Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_2, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_2, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
// USART3
|
||||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_3, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_3, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART3_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
// USART4
|
||||
uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_4, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_4, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void UART4_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
// USART5
|
||||
uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_5, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_5, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void UART5_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
// USART6
|
||||
uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
return serialUSART(UARTDEV_6, baudRate, mode, options);
|
||||
return serialUART(UARTDEV_6, baudRate, mode, options);
|
||||
}
|
||||
|
||||
void USART6_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
||||
usartIrqHandler(s);
|
||||
uartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -181,8 +181,8 @@ serialPort_t *usbVcpOpen(void)
|
|||
vcpPort_t *s;
|
||||
|
||||
#ifdef STM32F4
|
||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO);
|
||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO);
|
||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_INPUT, 0);
|
||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_OUTPUT, 0);
|
||||
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
|
||||
#else
|
||||
Set_System();
|
||||
|
|
|
@ -83,12 +83,12 @@ void hcsr04_init(sonarRange_t *sonarRange)
|
|||
|
||||
// trigger pin
|
||||
triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag);
|
||||
IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT);
|
||||
IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(triggerIO, IOCFG_OUT_PP);
|
||||
|
||||
// echo pin
|
||||
echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag);
|
||||
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT);
|
||||
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
||||
|
||||
#ifdef USE_EXTI
|
||||
|
|
|
@ -61,7 +61,7 @@ void beeperInit(const beeperConfig_t *config)
|
|||
beeperInverted = config->isInverted;
|
||||
|
||||
if (beeperIO) {
|
||||
IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT);
|
||||
IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP);
|
||||
}
|
||||
systemBeep(false);
|
||||
|
|
|
@ -69,7 +69,7 @@ bool isMPUSoftReset(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
checkForBootLoaderRequest();
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
SetSysClock(false);
|
||||
|
||||
|
|
|
@ -83,7 +83,7 @@ bool isMPUSoftReset(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
checkForBootLoaderRequest();
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
// Enable FPU
|
||||
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
|
||||
|
|
|
@ -169,7 +169,7 @@ bool isMPUSoftReset(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
checkForBootLoaderRequest();
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
SetSysClock();
|
||||
|
||||
|
@ -199,15 +199,15 @@ void systemInit(void)
|
|||
void(*bootJump)(void);
|
||||
void checkForBootLoaderRequest(void)
|
||||
{
|
||||
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
|
||||
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
|
||||
|
||||
*((uint32_t *)0x2001FFFC) = 0x0;
|
||||
*((uint32_t *)0x2001FFFC) = 0x0;
|
||||
|
||||
__enable_irq();
|
||||
__set_MSP(0x20001000);
|
||||
__enable_irq();
|
||||
__set_MSP(0x20001000);
|
||||
|
||||
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
|
||||
bootJump();
|
||||
while (1);
|
||||
}
|
||||
bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004));
|
||||
bootJump();
|
||||
while (1);
|
||||
}
|
||||
}
|
|
@ -374,7 +374,7 @@ void timerChClearCCFlag(const timerHardware_t *timHw)
|
|||
// configure timer channel GPIO mode
|
||||
void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
|
||||
{
|
||||
IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER);
|
||||
IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER, 0);
|
||||
IOConfigGPIO(IOGetByTag(timHw->tag), mode);
|
||||
}
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@ static IO_t usbDetectPin = IO_NONE;
|
|||
void usbCableDetectDeinit(void)
|
||||
{
|
||||
#ifdef USB_DETECT_PIN
|
||||
IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE);
|
||||
IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE, 0);
|
||||
IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING);
|
||||
usbDetectPin = IO_NONE;
|
||||
#endif
|
||||
|
@ -47,7 +47,7 @@ void usbCableDetectInit(void)
|
|||
#ifdef USB_DETECT_PIN
|
||||
usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN));
|
||||
|
||||
IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT);
|
||||
IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -53,23 +53,24 @@ static IO_t rtc6705DataPin = IO_NONE;
|
|||
static IO_t rtc6705LePin = IO_NONE;
|
||||
static IO_t rtc6705ClkPin = IO_NONE;
|
||||
|
||||
void rtc6705_soft_spi_init(void) {
|
||||
|
||||
void rtc6705_soft_spi_init(void)
|
||||
{
|
||||
rtc6705DataPin = IOGetByTag(IO_TAG(RTC6705_SPIDATA_PIN));
|
||||
rtc6705LePin = IOGetByTag(IO_TAG(RTC6705_SPILE_PIN));
|
||||
rtc6705ClkPin = IOGetByTag(IO_TAG(RTC6705_SPICLK_PIN));
|
||||
|
||||
IOInit(rtc6705DataPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(rtc6705DataPin, OWNER_TX, RESOURCE_SPI_MOSI, 0);
|
||||
IOConfigGPIO(rtc6705DataPin, IOCFG_OUT_PP);
|
||||
|
||||
IOInit(rtc6705LePin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(rtc6705LePin, OWNER_TX, RESOURCE_SPI_CS, 0);
|
||||
IOConfigGPIO(rtc6705LePin, IOCFG_OUT_PP);
|
||||
|
||||
IOInit(rtc6705ClkPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(rtc6705ClkPin, OWNER_TX, RESOURCE_SPI_SCK, 0);
|
||||
IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP);
|
||||
}
|
||||
|
||||
static void rtc6705_write_register(uint8_t addr, uint32_t data) {
|
||||
static void rtc6705_write_register(uint8_t addr, uint32_t data)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
RTC6705_SPILE_OFF;
|
||||
|
@ -107,7 +108,8 @@ static void rtc6705_write_register(uint8_t addr, uint32_t data) {
|
|||
}
|
||||
|
||||
|
||||
void rtc6705_soft_spi_set_channel(uint16_t channel_freq) {
|
||||
void rtc6705_soft_spi_set_channel(uint16_t channel_freq)
|
||||
{
|
||||
|
||||
uint32_t freq = (uint32_t)channel_freq * 1000;
|
||||
uint32_t N, A;
|
||||
|
@ -119,7 +121,8 @@ void rtc6705_soft_spi_set_channel(uint16_t channel_freq) {
|
|||
rtc6705_write_register(1, (N << 7) | A);
|
||||
}
|
||||
|
||||
void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) {
|
||||
void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power)
|
||||
{
|
||||
rtc6705_write_register(7, (reduce_power ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT));
|
||||
}
|
||||
|
||||
|
|
|
@ -52,12 +52,12 @@ extern uint8_t motorCount;
|
|||
****************************************************************************
|
||||
*** G_Tune ***
|
||||
****************************************************************************
|
||||
G_Tune Mode
|
||||
This is the multiwii implementation of ZERO-PID Algorithm
|
||||
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
|
||||
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
|
||||
G_Tune Mode
|
||||
This is the multiwii implementation of ZERO-PID Algorithm
|
||||
http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html
|
||||
The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com)
|
||||
|
||||
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
|
||||
You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution.
|
||||
*/
|
||||
|
||||
/*
|
||||
|
@ -107,13 +107,13 @@ void init_Gtune(pidProfile_t *pidProfileToTune)
|
|||
uint8_t i;
|
||||
|
||||
pidProfile = pidProfileToTune;
|
||||
if (pidProfile->pidController == 2) {
|
||||
floatPID = true; // LuxFloat is using float values for PID settings
|
||||
} else {
|
||||
floatPID = false;
|
||||
}
|
||||
updateDelayCycles();
|
||||
for (i = 0; i < 3; i++) {
|
||||
if (pidProfile->pidController == 2) {
|
||||
floatPID = true; // LuxFloat is using float values for PID settings
|
||||
} else {
|
||||
floatPID = false;
|
||||
}
|
||||
updateDelayCycles();
|
||||
for (i = 0; i < 3; i++) {
|
||||
if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning
|
||||
pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter
|
||||
}
|
||||
|
|
|
@ -666,9 +666,10 @@ void stopMotors(void)
|
|||
delay(50); // give the timers and ESCs a chance to react.
|
||||
}
|
||||
|
||||
void StopPwmAllMotors()
|
||||
void stopPwmAllMotors()
|
||||
{
|
||||
pwmShutdownPulsesForAllMotors(motorCount);
|
||||
delayMicroseconds(1500);
|
||||
}
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
|
@ -901,7 +902,7 @@ void mixTable(void)
|
|||
|
||||
/*
|
||||
case MIXER_GIMBAL:
|
||||
servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH);
|
||||
servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH);
|
||||
servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL);
|
||||
break;
|
||||
*/
|
||||
|
|
|
@ -215,4 +215,4 @@ void mixTable(void);
|
|||
void syncMotors(bool enabled);
|
||||
void writeMotors(void);
|
||||
void stopMotors(void);
|
||||
void StopPwmAllMotors(void);
|
||||
void stopPwmAllMotors(void);
|
||||
|
|
|
@ -172,7 +172,7 @@ typedef struct beeperTableEntry_s {
|
|||
{ BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 16, NULL, "SYSTEM_INIT") },
|
||||
{ BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") },
|
||||
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERRED") },
|
||||
};
|
||||
|
||||
|
@ -308,7 +308,7 @@ void beeperUpdate(void)
|
|||
if (!beeperIsOn) {
|
||||
beeperIsOn = 1;
|
||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||
if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
|
||||
if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
|
||||
BEEP_ON;
|
||||
warningLedEnable();
|
||||
warningLedRefresh();
|
||||
|
|
|
@ -29,7 +29,7 @@ typedef enum {
|
|||
BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix
|
||||
BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats)
|
||||
BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats)
|
||||
BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB ****
|
||||
BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB ****
|
||||
BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled
|
||||
BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position
|
||||
BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation
|
||||
|
@ -40,7 +40,7 @@ typedef enum {
|
|||
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
|
||||
BEEPER_USB, // Some boards have beeper powered USB connected
|
||||
|
||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||
BEEPER_PREFERENCE, // Save prefered beeper configuration
|
||||
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
|
||||
} beeperMode_e;
|
||||
|
|
|
@ -239,7 +239,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
// only RX is needed for NMEA-style GPS
|
||||
#if !defined(COLIBRI_RACE) || !defined(LUX_RACE)
|
||||
if (gpsConfig->provider == GPS_NMEA)
|
||||
mode &= ~MODE_TX;
|
||||
mode &= ~MODE_TX;
|
||||
#endif
|
||||
|
||||
// no callback - buffer will be consumed in gpsThread()
|
||||
|
@ -256,47 +256,47 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
void gpsInitNmea(void)
|
||||
{
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
uint32_t now;
|
||||
uint32_t now;
|
||||
#endif
|
||||
switch(gpsData.state) {
|
||||
case GPS_INITIALIZING:
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, 4800);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
// print our FIXED init string for the baudrate we want to be at
|
||||
serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
// we're now (hopefully) at the correct rate, next state will switch to it
|
||||
gpsSetState(GPS_CHANGE_BAUD);
|
||||
}
|
||||
break;
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, 4800);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
// print our FIXED init string for the baudrate we want to be at
|
||||
serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
// we're now (hopefully) at the correct rate, next state will switch to it
|
||||
gpsSetState(GPS_CHANGE_BAUD);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case GPS_CHANGE_BAUD:
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
#else
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
#endif
|
||||
gpsSetState(GPS_RECEIVING_DATA);
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
}
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -273,16 +273,16 @@ const ledConfig_t defaultLedStripConfig[] = {
|
|||
};
|
||||
#elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG)
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
|
||||
};
|
||||
#else
|
||||
const ledConfig_t defaultLedStripConfig[] = {
|
||||
|
@ -370,8 +370,8 @@ static const uint16_t functionMappings[FUNCTION_COUNT] = {
|
|||
LED_FUNCTION_FLIGHT_MODE,
|
||||
LED_FUNCTION_ARM_STATE,
|
||||
LED_FUNCTION_THROTTLE,
|
||||
LED_FUNCTION_THRUST_RING,
|
||||
LED_FUNCTION_COLOR
|
||||
LED_FUNCTION_THRUST_RING,
|
||||
LED_FUNCTION_COLOR
|
||||
};
|
||||
|
||||
// grid offsets
|
||||
|
@ -938,7 +938,7 @@ static void applyLedAnimationLayer(void)
|
|||
void updateLedStrip(void)
|
||||
{
|
||||
|
||||
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
||||
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1115,8 +1115,8 @@ void ledStripEnable(void)
|
|||
|
||||
static void ledStripDisable(void)
|
||||
{
|
||||
setStripColor(&hsv_black);
|
||||
setStripColor(&hsv_black);
|
||||
|
||||
ws2811UpdateStrip();
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -607,7 +607,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
|||
switch(adjustmentFunction) {
|
||||
case ADJUSTMENT_RATE_PROFILE:
|
||||
if (getCurrentControlRateProfile() != position) {
|
||||
changeControlRateProfile(position);
|
||||
changeControlRateProfile(position);
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
|
||||
applied = true;
|
||||
}
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#include "drivers/serial_softserial.h"
|
||||
#endif
|
||||
|
||||
#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) || defined(USE_USART4) || defined(USE_USART5) || defined(USE_USART6)
|
||||
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6)
|
||||
#include "drivers/serial_uart.h"
|
||||
#endif
|
||||
|
||||
|
@ -60,22 +60,22 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
|||
#ifdef USE_VCP
|
||||
SERIAL_PORT_USB_VCP,
|
||||
#endif
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
SERIAL_PORT_USART1,
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
SERIAL_PORT_USART2,
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
SERIAL_PORT_USART3,
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
SERIAL_PORT_USART4,
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
SERIAL_PORT_USART5,
|
||||
#endif
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
SERIAL_PORT_USART6,
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
|
@ -273,7 +273,7 @@ serialPort_t *openSerialPort(
|
|||
portMode_t mode,
|
||||
portOptions_t options)
|
||||
{
|
||||
#if (!defined(USE_VCP) && !defined(USE_USART1) && !defined(USE_USART2) && !defined(USE_USART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1))
|
||||
#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1))
|
||||
UNUSED(callback);
|
||||
UNUSED(baudRate);
|
||||
UNUSED(mode);
|
||||
|
@ -294,32 +294,32 @@ serialPort_t *openSerialPort(
|
|||
serialPort = usbVcpOpen();
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART1
|
||||
#ifdef USE_UART1
|
||||
case SERIAL_PORT_USART1:
|
||||
serialPort = uartOpen(USART1, callback, baudRate, mode, options);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART2
|
||||
#ifdef USE_UART2
|
||||
case SERIAL_PORT_USART2:
|
||||
serialPort = uartOpen(USART2, callback, baudRate, mode, options);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART3
|
||||
#ifdef USE_UART3
|
||||
case SERIAL_PORT_USART3:
|
||||
serialPort = uartOpen(USART3, callback, baudRate, mode, options);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART4
|
||||
#ifdef USE_UART4
|
||||
case SERIAL_PORT_USART4:
|
||||
serialPort = uartOpen(UART4, callback, baudRate, mode, options);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART5
|
||||
#ifdef USE_UART5
|
||||
case SERIAL_PORT_USART5:
|
||||
serialPort = uartOpen(UART5, callback, baudRate, mode, options);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_USART6
|
||||
#ifdef USE_UART6
|
||||
case SERIAL_PORT_USART6:
|
||||
serialPort = uartOpen(USART6, callback, baudRate, mode, options);
|
||||
break;
|
||||
|
|
|
@ -89,7 +89,7 @@ static uint8_t ckSumOut;
|
|||
static void StkSendByte(uint8_t dat)
|
||||
{
|
||||
ckSumOut ^= dat;
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (dat & 0x01) {
|
||||
// 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
|
||||
ESC_SET_HI;
|
||||
|
@ -248,9 +248,9 @@ static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t add
|
|||
StkSendByte(4); // NumTX
|
||||
StkSendByte(4); // NumRX
|
||||
StkSendByte(0); // RxStartAdr
|
||||
StkSendByte(subcmd); // {TxData} Cmd
|
||||
StkSendByte(subcmd); // {TxData} Cmd
|
||||
StkSendByte(addr >> 8); // {TxData} AdrHi
|
||||
StkSendByte(addr & 0xff); // {TxData} AdrLow
|
||||
StkSendByte(addr & 0xff); // {TxData} AdrLow
|
||||
StkSendByte(0); // {TxData} 0
|
||||
StkSendPacketFooter();
|
||||
if (StkRcvPacket(stkInBuf, sizeof(stkInBuf))) { // NumRX + 3
|
||||
|
|
|
@ -2566,18 +2566,18 @@ static void cliRateProfile(char *cmdline) {
|
|||
|
||||
static void cliReboot(void)
|
||||
{
|
||||
cliRebootEx(false);
|
||||
cliRebootEx(false);
|
||||
}
|
||||
|
||||
static void cliRebootEx(bool bootLoader)
|
||||
{
|
||||
cliPrint("\r\nRebooting");
|
||||
cliPrint("\r\nRebooting");
|
||||
bufWriterFlush(cliWriter);
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
if (bootLoader) {
|
||||
systemResetToBootloader();
|
||||
return;
|
||||
systemResetToBootloader();
|
||||
return;
|
||||
}
|
||||
systemReset();
|
||||
}
|
||||
|
@ -3074,55 +3074,30 @@ void cliProcess(void)
|
|||
}
|
||||
}
|
||||
|
||||
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||
"FREE",
|
||||
"PWM IN",
|
||||
"PPM IN",
|
||||
"MOTOR",
|
||||
"SERVO",
|
||||
"SOFTSERIAL RX",
|
||||
"SOFTSERIAL TX",
|
||||
"SOFTSERIAL RXTX", // bidirectional pin for softserial
|
||||
"SOFTSERIAL AUXTIMER", // timer channel is used for softserial. No IO function on pin
|
||||
"ADC",
|
||||
"SERIAL RX",
|
||||
"SERIAL TX",
|
||||
"SERIAL RXTX",
|
||||
"PINDEBUG",
|
||||
"TIMER",
|
||||
"SONAR",
|
||||
"SYSTEM",
|
||||
"SDCARD",
|
||||
"FLASH",
|
||||
"USB",
|
||||
"BEEPER",
|
||||
"OSD",
|
||||
"BARO",
|
||||
};
|
||||
|
||||
static void cliResource(char *cmdline)
|
||||
{
|
||||
UNUSED(cmdline);
|
||||
cliPrintf("IO:\r\n");
|
||||
cliPrintf("IO:\r\n----------------------\r\n");
|
||||
for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) {
|
||||
const char* owner;
|
||||
char buff[15];
|
||||
if (ioRecs[i].owner < ARRAYLEN(ownerNames)) {
|
||||
owner = ownerNames[ioRecs[i].owner];
|
||||
owner = ownerNames[ioRecs[i].owner];
|
||||
|
||||
const char* resource;
|
||||
resource = resourceNames[ioRecs[i].resource];
|
||||
|
||||
if (ioRecs[i].index > 0) {
|
||||
cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
|
||||
} else {
|
||||
cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
|
||||
}
|
||||
else {
|
||||
sprintf(buff, "O=%d", ioRecs[i].owner);
|
||||
owner = buff;
|
||||
}
|
||||
cliPrintf("%c%02d: %19s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner);
|
||||
}
|
||||
}
|
||||
|
||||
void cliDfu(char *cmdLine)
|
||||
{
|
||||
UNUSED(cmdLine);
|
||||
cliPrint("\r\nRestarting in DFU mode");
|
||||
cliRebootEx(true);
|
||||
UNUSED(cmdLine);
|
||||
cliPrint("\r\nRestarting in DFU mode");
|
||||
cliRebootEx(true);
|
||||
}
|
||||
|
||||
void cliInit(serialConfig_t *serialConfig)
|
||||
|
|
|
@ -1967,7 +1967,7 @@ void mspProcess(void)
|
|||
|
||||
if (isRebootScheduled) {
|
||||
waitForSerialPortToFinishTransmitting(candidatePort->port);
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
// On real flight controllers, systemReset() will do a soft reset of the device,
|
||||
// reloading the program. But to support offline testing this flag needs to be
|
||||
// cleared so that the software doesn't continuously attempt to reboot itself.
|
||||
|
|
|
@ -76,7 +76,7 @@ static uint8_t locked = 0;
|
|||
|
||||
void vtxInit(void)
|
||||
{
|
||||
rtc6705Init();
|
||||
rtc6705Init();
|
||||
if (masterConfig.vtx_mode == 0) {
|
||||
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
|
||||
} else if (masterConfig.vtx_mode == 1) {
|
||||
|
|
|
@ -17,11 +17,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define VTX_BAND_MIN 1
|
||||
#define VTX_BAND_MAX 5
|
||||
#define VTX_CHANNEL_MIN 1
|
||||
#define VTX_CHANNEL_MAX 8
|
||||
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
|
||||
#define VTX_BAND_MIN 1
|
||||
#define VTX_BAND_MAX 5
|
||||
#define VTX_CHANNEL_MIN 1
|
||||
#define VTX_CHANNEL_MAX 8
|
||||
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
|
||||
|
||||
typedef struct vtxChannelActivationCondition_s {
|
||||
uint8_t auxChannelIndex;
|
||||
|
|
|
@ -166,7 +166,7 @@ void init(void)
|
|||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||
|
||||
// initialize IO (needed for all IO operations)
|
||||
IOInitGlobal();
|
||||
IOInitGlobal();
|
||||
|
||||
debugMode = masterConfig.debug_mode;
|
||||
|
||||
|
@ -275,16 +275,16 @@ void init(void)
|
|||
pwm_params.airplane = true;
|
||||
else
|
||||
pwm_params.airplane = false;
|
||||
#if defined(USE_USART2) && defined(STM32F10X)
|
||||
#if defined(USE_UART2) && defined(STM32F10X)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
#ifdef STM32F303xC
|
||||
pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
|
||||
#endif
|
||||
#if defined(USE_USART2) && defined(STM32F40_41xxx)
|
||||
#if defined(USE_UART2) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
#if defined(USE_USART6) && defined(STM32F40_41xxx)
|
||||
#if defined(USE_UART6) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6);
|
||||
#endif
|
||||
pwm_params.useVbat = feature(FEATURE_VBAT);
|
||||
|
@ -335,12 +335,6 @@ void init(void)
|
|||
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
|
||||
|
||||
/*
|
||||
// TODO is this needed here? enables at the end
|
||||
if (!feature(FEATURE_ONESHOT125))
|
||||
motorControlEnable = true;
|
||||
|
||||
*/
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
|
@ -363,7 +357,7 @@ void init(void)
|
|||
#endif
|
||||
#ifdef CC3D
|
||||
if (masterConfig.use_buzzer_p6 == 1)
|
||||
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
||||
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
||||
#endif
|
||||
|
||||
beeperInit(&beeperConfig);
|
||||
|
|
|
@ -591,10 +591,10 @@ void updateRSSIPWM(void)
|
|||
// Read value of AUX channel as rssi
|
||||
pwmRssi = rcData[rxConfig->rssi_channel - 1];
|
||||
|
||||
// RSSI_Invert option
|
||||
if (rxConfig->rssi_ppm_invert) {
|
||||
pwmRssi = ((2000 - pwmRssi) + 1000);
|
||||
}
|
||||
// RSSI_Invert option
|
||||
if (rxConfig->rssi_ppm_invert) {
|
||||
pwmRssi = ((2000 - pwmRssi) + 1000);
|
||||
}
|
||||
|
||||
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
|
||||
rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f);
|
||||
|
|
|
@ -184,7 +184,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
|
|||
{
|
||||
#ifdef HARDWARE_BIND_PLUG
|
||||
BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN));
|
||||
IOInit(BindPlug, OWNER_SYSTEM, RESOURCE_INPUT);
|
||||
IOInit(BindPlug, OWNER_RX, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(BindPlug, IOCFG_IPU);
|
||||
|
||||
// Check status of bind plug and exit if not active
|
||||
|
@ -216,7 +216,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
|||
LED1_ON;
|
||||
|
||||
BindPin = IOGetByTag(IO_TAG(BIND_PIN));
|
||||
IOInit(BindPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOInit(BindPin, OWNER_RX, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(BindPin, IOCFG_OUT_PP);
|
||||
|
||||
// RX line, set high
|
||||
|
@ -245,7 +245,7 @@ void spektrumBind(rxConfig_t *rxConfig)
|
|||
#ifndef HARDWARE_BIND_PLUG
|
||||
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
||||
// Don't reset if hardware bind plug is present
|
||||
// Reset only when autoreset is enabled
|
||||
// Reset only when autoreset is enabled
|
||||
if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
|
||||
rxConfig->spektrum_sat_bind = 0;
|
||||
saveConfigAndNotify();
|
||||
|
|
|
@ -71,7 +71,7 @@
|
|||
// 2200µs -> 0xFFF
|
||||
// Total range is: 2200 - 800 = 1400 <==> 4095
|
||||
// Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
|
||||
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
|
||||
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
|
||||
|
||||
static bool xBusFrameReceived = false;
|
||||
static bool xBusDataIncoming = false;
|
||||
|
|
|
@ -139,7 +139,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
|
|||
{
|
||||
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
|
||||
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
|
||||
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
|
||||
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -117,7 +117,7 @@ typedef enum {
|
|||
|
||||
|
||||
bool isBaroReady(void) {
|
||||
return baroReady;
|
||||
return baroReady;
|
||||
}
|
||||
|
||||
uint32_t baroUpdate(void)
|
||||
|
|
|
@ -213,7 +213,7 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea
|
|||
}
|
||||
|
||||
fix12_t calculateVbatPidCompensation(void) {
|
||||
fix12_t batteryScaler;
|
||||
fix12_t batteryScaler;
|
||||
if (batteryConfig->vbatPidCompensation && feature(FEATURE_VBAT) && batteryCellCount > 1) {
|
||||
uint16_t maxCalculatedVoltage = batteryConfig->vbatmaxcellvoltage * batteryCellCount;
|
||||
batteryScaler = qConstruct(maxCalculatedVoltage, constrain(vbat, maxCalculatedVoltage - batteryConfig->vbatmaxcellvoltage, maxCalculatedVoltage));
|
||||
|
|
|
@ -418,20 +418,20 @@ static void detectBaro(baroSensor_e baroHardwareToUse)
|
|||
|
||||
#ifdef USE_BARO_BMP085
|
||||
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
|
||||
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
|
||||
static const bmp085Config_t defaultBMP085Config = {
|
||||
.xclrIO = IO_TAG(BARO_XCLR_PIN),
|
||||
.eocIO = IO_TAG(BARO_EOC_PIN),
|
||||
};
|
||||
bmp085Config = &defaultBMP085Config;
|
||||
static const bmp085Config_t defaultBMP085Config = {
|
||||
.xclrIO = IO_TAG(BARO_XCLR_PIN),
|
||||
.eocIO = IO_TAG(BARO_EOC_PIN),
|
||||
};
|
||||
bmp085Config = &defaultBMP085Config;
|
||||
#endif
|
||||
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision == NAZE32) {
|
||||
bmp085Disable(bmp085Config);
|
||||
}
|
||||
if (hardwareRevision == NAZE32) {
|
||||
bmp085Disable(bmp085Config);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
@ -455,7 +455,7 @@ static void detectBaro(baroSensor_e baroHardwareToUse)
|
|||
break;
|
||||
}
|
||||
#endif
|
||||
; // fallthough
|
||||
; // fallthough
|
||||
case BARO_BMP280:
|
||||
#ifdef USE_BARO_BMP280
|
||||
if (bmp280Detect(&baro)) {
|
||||
|
@ -503,7 +503,7 @@ static void detectMag(magSensor_e magHardwareToUse)
|
|||
.intTag = IO_TAG(MAG_INT_EXTI)
|
||||
};
|
||||
|
||||
hmc5883Config = &extiHmc5883Config;
|
||||
hmc5883Config = &extiHmc5883Config;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -40,7 +40,7 @@ static IO_t HWDetectPin = IO_NONE;
|
|||
void detectHardwareRevision(void)
|
||||
{
|
||||
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
|
||||
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT);
|
||||
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||
|
||||
// Check hardware revision
|
||||
|
|
|
@ -84,7 +84,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
// USART3 RX/TX
|
||||
// RX conflicts with PPM port
|
||||
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11
|
||||
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12
|
||||
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, UART3_RX (AF7) - PWM11
|
||||
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, UART3_TX (AF7) - PWM12
|
||||
};
|
||||
|
||||
|
|
|
@ -69,32 +69,19 @@
|
|||
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
|
||||
#define USE_USART2 // Receiver - RX (PA3)
|
||||
#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
||||
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)
|
||||
#define USE_UART2 // Receiver - RX (PA3)
|
||||
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_6 // PB6
|
||||
#define UART1_RX_PIN GPIO_Pin_7 // PB7
|
||||
#define UART1_GPIO GPIOB
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||
#define UART1_TX_PIN PB6 // PB6
|
||||
#define UART1_RX_PIN PB7 // PB7
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_2 // PA2
|
||||
#define UART2_RX_PIN GPIO_Pin_3 // PA3
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource2
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource3
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART2_TX_PIN PA2 // PA2
|
||||
#define UART2_RX_PIN PA3 // PA3
|
||||
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||
|
|
|
@ -97,26 +97,26 @@
|
|||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_USART1
|
||||
#define USART1_RX_PIN PA10
|
||||
#define USART1_TX_PIN PA9
|
||||
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
|
||||
#define USE_USART2
|
||||
#define USART2_RX_PIN PA3
|
||||
#define USART2_TX_PIN PA2 //inverter
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2 //inverter
|
||||
|
||||
//#define USE_USART3
|
||||
//#define USART3_RX_PIN PB11
|
||||
//#define USART3_TX_PIN PB10
|
||||
//#define USE_UART3
|
||||
//#define UART3_RX_PIN PB11
|
||||
//#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_USART4
|
||||
#define USART4_RX_PIN PC10
|
||||
#define USART4_TX_PIN PC11
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC10
|
||||
#define UART4_TX_PIN PC11
|
||||
|
||||
//#define USE_USART5
|
||||
//#define USART5_RX_PIN PD2
|
||||
//#define USART5_TX_PIN PC12
|
||||
//#define USE_UART5
|
||||
//#define UART5_RX_PIN PD2
|
||||
//#define UART5_TX_PIN PC12
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
|
|
|
@ -95,20 +95,26 @@
|
|||
//#define VBUS_SENSING_PIN PA8
|
||||
//#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_USART1
|
||||
#define USART1_RX_PIN PA10
|
||||
#define USART1_TX_PIN PA9
|
||||
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
|
||||
#define USE_USART3
|
||||
#define USART3_RX_PIN PB11
|
||||
#define USART3_TX_PIN PB10
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_USART6
|
||||
#define USART6_RX_PIN PC7
|
||||
#define USART6_TX_PIN PC6
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM3
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_HARDWARE 0
|
||||
|
@ -160,3 +166,4 @@
|
|||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9))
|
||||
|
||||
|
|
|
@ -69,20 +69,21 @@
|
|||
#define USE_MAG_HMC5883
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
#undef USE_UART1_RX_DMA
|
||||
#endif
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM3
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
|
||||
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
#define USART3_GPIO GPIOB
|
||||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
|
@ -93,8 +93,8 @@
|
|||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define USE_I2C
|
||||
|
@ -111,7 +111,7 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
|
||||
|
||||
|
|
|
@ -35,8 +35,8 @@
|
|||
|
||||
#define BRUSHED_MOTORS
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
|
||||
#define SERIAL_PORT_COUNT 2
|
||||
|
||||
|
|
|
@ -32,11 +32,6 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
@ -44,6 +39,13 @@
|
|||
#define SPI1_SCK_PIN PB3
|
||||
#define SPI1_MISO_PIN PB4
|
||||
#define SPI1_MOSI_PIN PB5
|
||||
#define SPI1_NSS_PIN PA4
|
||||
|
||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define MPU6000_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
|
@ -75,31 +77,19 @@
|
|||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_4
|
||||
#define UART1_RX_PIN GPIO_Pin_5
|
||||
#define UART1_GPIO GPIOC
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource4
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource5
|
||||
#define UART1_TX_PIN PC4
|
||||
#define UART1_RX_PIN PC5
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14
|
||||
#define UART2_RX_PIN GPIO_Pin_15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
#define UART2_TX_PIN PA14
|
||||
#define UART2_RX_PIN PA15
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10
|
||||
#define UART3_RX_PIN GPIO_Pin_11
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
|
|
@ -33,14 +33,6 @@
|
|||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// tqfp48 pin 3
|
||||
#define MPU6500_CS_PIN PC14
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
// tqfp48 pin 25
|
||||
#define BMP280_CS_PIN PB12
|
||||
#define BMP280_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
@ -51,18 +43,31 @@
|
|||
#define SPI1_MISO_PIN PB4
|
||||
// tqfp48 pin 41
|
||||
#define SPI1_MOSI_PIN PB5
|
||||
// tqfp48 pin 3
|
||||
#define SPI1_NSS_PIN PC14
|
||||
|
||||
// tqfp48 pin 26
|
||||
#define SPI2_SCK_PIN PB13
|
||||
// tqfp48 pin 27
|
||||
#define SPI2_MISO_PIN PB14
|
||||
// tqfp48 pin 28
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
// tqfp48 pin 25
|
||||
#define SPI2_NSS_PIN PB12
|
||||
|
||||
// tqfp48 pin 3
|
||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
// tqfp48 pin 25
|
||||
#define BMP280_CS_PIN SPI2_NSS_PIN
|
||||
#define BMP280_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_SHARED
|
||||
#define M25P16_CS_PIN PC15
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
#define M25P16_CS_PIN PC15
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
// timer definitions in drivers/timer.c
|
||||
// channel mapping in drivers/pwm_mapping.c
|
||||
|
@ -90,37 +95,19 @@
|
|||
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
// tqfp48 pin 42
|
||||
#define UART1_TX_PIN GPIO_Pin_6
|
||||
// tqfp48 pin 43
|
||||
#define UART1_RX_PIN GPIO_Pin_7
|
||||
#define UART1_GPIO GPIOB
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
// tqfp48 pin 12
|
||||
#define UART2_TX_PIN GPIO_Pin_2
|
||||
// tqfp48 pin 13
|
||||
#define UART2_RX_PIN GPIO_Pin_3
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource2
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource3
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
// tqfp48 pin 21
|
||||
#define UART3_TX_PIN GPIO_Pin_10
|
||||
// tqfp48 pin 22
|
||||
#define UART3_RX_PIN GPIO_Pin_11
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
|
|
@ -76,8 +76,8 @@
|
|||
|
||||
#define DISPLAY
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
|
|
@ -95,7 +95,7 @@
|
|||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
|
@ -107,36 +107,20 @@
|
|||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#endif
|
||||
#define UART1_TX_PIN PA9 // PA9
|
||||
#define UART1_RX_PIN PA10 // PA10
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
#define UART2_TX_PIN PA14 // PA14
|
||||
#define UART2_RX_PIN PA15 // PA15
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#endif
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM3
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 1
|
||||
|
|
|
@ -106,18 +106,18 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_USART1
|
||||
#define USART1_RX_PIN PA10
|
||||
#define USART1_TX_PIN PA9
|
||||
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
|
||||
#define USE_USART3
|
||||
#define USART3_RX_PIN PB11
|
||||
#define USART3_TX_PIN PB10
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_USART6
|
||||
#define USART6_RX_PIN PC7
|
||||
#define USART6_TX_PIN PC6
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
|
||||
|
||||
|
|
|
@ -99,8 +99,8 @@ const uint16_t airPWM[] = {
|
|||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
|
|
|
@ -44,35 +44,19 @@
|
|||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#endif
|
||||
#define UART1_TX_PIN PA9 // PA9
|
||||
#define UART1_RX_PIN PA10 // PA10
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
#define UART2_TX_PIN PA14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA15 // PA15
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#endif
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
|
|
@ -23,8 +23,9 @@
|
|||
|
||||
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
|
||||
|
||||
#define LED0 PB1
|
||||
#define LED0 PB1
|
||||
#define BEEPER PB13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
|
||||
|
@ -43,32 +44,20 @@
|
|||
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#define UART1_TX_PIN PA9 // PA9
|
||||
#define UART1_RX_PIN PA10 // PA10
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_3
|
||||
#define UART2_RX_PIN GPIO_Pin_4
|
||||
#define UART2_GPIO GPIOB
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource3
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource4
|
||||
#define UART2_TX_PIN PB3
|
||||
#define UART2_RX_PIN PB4
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
|
|
@ -29,17 +29,16 @@
|
|||
#define BEEPER PB13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define MPU6500_CS_GPIO GPIOA
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define SPI1_SCK_PIN PB3
|
||||
#define SPI1_MISO_PIN PB4
|
||||
#define SPI1_MOSI_PIN PB5
|
||||
#define SPI1_NSS_PIN PA4
|
||||
|
||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
|
@ -58,31 +57,19 @@
|
|||
#define USB_IO
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_4
|
||||
#define UART1_RX_PIN GPIO_Pin_5
|
||||
#define UART1_GPIO GPIOC
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource4
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource5
|
||||
#define UART1_TX_PIN PC4
|
||||
#define UART1_RX_PIN PC5
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14
|
||||
#define UART2_RX_PIN GPIO_Pin_15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
#define UART2_TX_PIN PA14
|
||||
#define UART2_RX_PIN PA15
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10
|
||||
#define UART3_RX_PIN GPIO_Pin_11
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
|
|
@ -63,45 +63,24 @@
|
|||
//#define USE_MAG_HMC5883
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_6 // PB6
|
||||
#define UART1_RX_PIN GPIO_Pin_7 // PB7
|
||||
#define UART1_GPIO GPIOB
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||
#define UART1_TX_PIN PB6 // PB6
|
||||
#define UART1_RX_PIN PB7 // PB7
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_3 // PB3
|
||||
#define UART2_RX_PIN GPIO_Pin_4 // PB4
|
||||
#define UART2_GPIO GPIOB
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource3
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource4
|
||||
#define UART2_TX_PIN PB3 // PB3
|
||||
#define UART2_RX_PIN PB4 // PB4
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||
|
||||
#define I2C2_SCL_GPIO GPIOA
|
||||
#define I2C2_SCL_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SCL_PIN PA9
|
||||
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
|
||||
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#define I2C2_SDA_GPIO GPIOA
|
||||
#define I2C2_SDA_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SDA_PIN PA10
|
||||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
#define I2C2_SCL PA9
|
||||
#define I2C2_SDA PA10
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
|
|
@ -119,9 +119,9 @@
|
|||
|
||||
#define DISPLAY
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
@ -134,11 +134,8 @@
|
|||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||
|
||||
// USART3 only on NAZE32_SP - Flex Port
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
#define USART3_GPIO GPIOB
|
||||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
#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 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
|
||||
#define LED1 PA1 // D3, PA1/UART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
|
||||
#endif
|
||||
|
||||
#define GYRO
|
||||
|
@ -62,8 +62,8 @@
|
|||
#define SONAR_ECHO_PIN PB1
|
||||
#define SONAR_TRIGGER_PIN PB0
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
|
|
@ -97,8 +97,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1
|
||||
|
||||
// UART3 RX/TX
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7)
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
|
||||
|
||||
// LED Strip Pad
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
|
||||
|
|
|
@ -70,36 +70,20 @@
|
|||
#define USB_DETECT_PIN PB5
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#ifndef UART1_GPIO
|
||||
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||
#define UART1_GPIO GPIOA
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||
#endif
|
||||
#define UART1_TX_PIN PA9 // PA9
|
||||
#define UART1_RX_PIN PA10 // PA10
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
#define UART2_TX_PIN PA14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN PA15 // PA15
|
||||
|
||||
#ifndef UART3_GPIO
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#endif
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM2
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
||||
|
@ -152,7 +136,7 @@
|
|||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
|
|
|
@ -49,31 +49,19 @@
|
|||
#define MPU6000_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN GPIO_Pin_6 // PB6
|
||||
#define UART1_RX_PIN GPIO_Pin_7 // PB7
|
||||
#define UART1_GPIO GPIOB
|
||||
#define UART1_GPIO_AF GPIO_AF_7
|
||||
#define UART1_TX_PINSOURCE GPIO_PinSource6
|
||||
#define UART1_RX_PINSOURCE GPIO_PinSource7
|
||||
#define UART1_TX_PIN PB6 // PB6
|
||||
#define UART1_RX_PIN PB7 // PB7
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_3 // PB3
|
||||
#define UART2_RX_PIN GPIO_Pin_4 // PB4
|
||||
#define UART2_GPIO GPIOB
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource3
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource4
|
||||
#define UART2_TX_PIN PB3 // PB3
|
||||
#define UART2_RX_PIN PB4 // PB4
|
||||
|
||||
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||
#define UART3_GPIO_AF GPIO_AF_7
|
||||
#define UART3_GPIO GPIOB
|
||||
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
|
|
@ -89,8 +89,8 @@
|
|||
|
||||
#define DISPLAY
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
|
|
@ -1,4 +1,7 @@
|
|||
F1_TARGETS += $(TARGET)
|
||||
256K_TARGETS += $(TARGET)
|
||||
FLASH_SIZE = 256
|
||||
|
||||
FEATURES = ONBOARDFLASH HIGHEND
|
||||
|
||||
DEVICE_FLAGS = -DSTM32F10X_HD
|
||||
|
|
|
@ -74,18 +74,18 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
|
||||
#define USE_USART1
|
||||
#define USART1_RX_PIN PA10
|
||||
#define USART1_TX_PIN PA9
|
||||
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
|
||||
#define USE_USART3
|
||||
#define USART3_RX_PIN PB11
|
||||
#define USART3_TX_PIN PB10
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_USART6
|
||||
#define USART6_RX_PIN PC7
|
||||
#define USART6_TX_PIN PC6
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
|
||||
|
||||
|
|
|
@ -62,13 +62,13 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA9
|
||||
|
||||
#define USE_USART1
|
||||
#define USART1_RX_PIN PB7
|
||||
#define USART1_TX_PIN PB6
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PB7
|
||||
#define UART1_TX_PIN PB6
|
||||
|
||||
#define USE_USART2
|
||||
#define USART2_RX_PIN PA3
|
||||
#define USART2_TX_PIN PA2
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2
|
||||
|
||||
|
|
|
@ -99,8 +99,8 @@ const uint16_t airPWM[] = {
|
|||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue