mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge pull request #10967 from SteveCEvans/remove_f1_f3
Remove F1 and F3 support
This commit is contained in:
commit
a90a783c41
847 changed files with 77 additions and 498437 deletions
|
@ -1,25 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash_1m.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F103RG Device with
|
||||
** 1MByte FLASH, 96KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1020K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0803F000, LENGTH = 4K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,26 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F103CB Device with
|
||||
** 128KByte FLASH, 20KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 126K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0801F800, LENGTH = 2K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
REGION_ALIAS("CCM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,26 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F103CB Device with
|
||||
** 128KByte FLASH, 20KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
/* First 12K (0x3000 bytes) used for OP Bootloader, last 2K used for config storage */
|
||||
FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 114K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0801F800, LENGTH = 2K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,25 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F103RC Device with
|
||||
** 256KByte FLASH, 48KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 252K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0803F000, LENGTH = 4K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 48K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,25 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F103C8 Device with
|
||||
** 64KByte FLASH, 20KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 62K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0800F800, LENGTH = 2K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,26 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F30x Device with
|
||||
** 128KByte FLASH and 40KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 126K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0801F800, LENGTH = 2K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K
|
||||
CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 8K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", CCM)
|
||||
REGION_ALIAS("FASTRAM", CCM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,26 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F30x Device with
|
||||
** 256KByte FLASH and 40KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 252K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0803F000, LENGTH = 4K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K
|
||||
CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 8K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", CCM)
|
||||
REGION_ALIAS("FASTRAM", CCM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -1,28 +0,0 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F303xD/E Device
|
||||
** FLASH 512KByte
|
||||
** SRAM 64KByte
|
||||
** CCM 16KByte
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Specify the memory areas. */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 508K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x0807F000, LENGTH = 4K
|
||||
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 16K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", CCM)
|
||||
REGION_ALIAS("FASTRAM", CCM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
|
@ -25,14 +25,6 @@
|
|||
|
||||
#include "build_config.h"
|
||||
|
||||
#ifdef STM32F1
|
||||
#warning STM32F1 based targets are unsupported as of Betaflight 3.3.
|
||||
#endif
|
||||
|
||||
#ifdef STM32F3
|
||||
#warning STM32F3 based targets are unsupported as of Betaflight 4.1.
|
||||
#endif
|
||||
|
||||
#ifdef USE_CLI_DEBUG_PRINT
|
||||
#warning Do not use USE_CLI_DEBUG_PRINT for production builds.
|
||||
#endif
|
||||
|
@ -41,10 +33,6 @@ mcuTypeId_e getMcuTypeId(void)
|
|||
{
|
||||
#if defined(SIMULATOR_BUILD)
|
||||
return MCU_TYPE_SIMULATOR;
|
||||
#elif defined(STM32F1)
|
||||
return MCU_TYPE_F103;
|
||||
#elif defined(STM32F3)
|
||||
return MCU_TYPE_F303;
|
||||
#elif defined(STM32F40_41xxx)
|
||||
return MCU_TYPE_F40X;
|
||||
#elif defined(STM32F411xE)
|
||||
|
|
|
@ -43,8 +43,6 @@
|
|||
|
||||
typedef enum {
|
||||
MCU_TYPE_SIMULATOR = 0,
|
||||
MCU_TYPE_F103,
|
||||
MCU_TYPE_F303,
|
||||
MCU_TYPE_F40X,
|
||||
MCU_TYPE_F411,
|
||||
MCU_TYPE_F446,
|
||||
|
|
|
@ -177,12 +177,8 @@ bool cliMode = false;
|
|||
|
||||
static serialPort_t *cliPort = NULL;
|
||||
|
||||
#ifdef STM32F1
|
||||
#define CLI_IN_BUFFER_SIZE 128
|
||||
#else
|
||||
// Space required to set array parameters
|
||||
#define CLI_IN_BUFFER_SIZE 256
|
||||
#endif
|
||||
#define CLI_OUT_BUFFER_SIZE 64
|
||||
|
||||
static bufWriter_t *cliWriter = NULL;
|
||||
|
|
|
@ -41,16 +41,8 @@ uint8_t eepromData[EEPROM_SIZE];
|
|||
#endif
|
||||
// @todo this is not strictly correct for F4/F7, where sector sizes are variable
|
||||
#if !defined(FLASH_PAGE_SIZE)
|
||||
// F1
|
||||
# if defined(STM32F10X_MD)
|
||||
# define FLASH_PAGE_SIZE (0x400)
|
||||
# elif defined(STM32F10X_HD)
|
||||
# define FLASH_PAGE_SIZE (0x800)
|
||||
// F3
|
||||
# elif defined(STM32F303xC)
|
||||
# define FLASH_PAGE_SIZE (0x800)
|
||||
// F4
|
||||
# elif defined(STM32F40_41xxx)
|
||||
#if defined(STM32F40_41xxx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
||||
# elif defined (STM32F411xE)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
|
||||
|
@ -111,11 +103,7 @@ void config_streamer_start(config_streamer_t *c, uintptr_t base, int size)
|
|||
#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH)
|
||||
// NOP
|
||||
#elif defined(CONFIG_IN_FLASH)
|
||||
#if defined(STM32F10X)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
#elif defined(STM32F303)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
|
||||
#elif defined(STM32F7)
|
||||
// NOP
|
||||
|
@ -506,11 +494,7 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t
|
|||
}
|
||||
#else // !STM32H7 && !STM32F7 && !STM32G4
|
||||
if (c->address % FLASH_PAGE_SIZE == 0) {
|
||||
#if defined(STM32F4)
|
||||
const FLASH_Status status = FLASH_EraseSector(getFLASHSectorForEEPROM(), VoltageRange_3); //0x08080000 to 0x080A0000
|
||||
#else // STM32F3, STM32F1
|
||||
const FLASH_Status status = FLASH_ErasePage(c->address);
|
||||
#endif
|
||||
if (status != FLASH_COMPLETE) {
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -115,16 +115,9 @@ bool adcVerifyPin(ioTag_t tag, ADCDevice device)
|
|||
}
|
||||
|
||||
for (int map = 0 ; map < ADC_TAG_MAP_COUNT ; map++) {
|
||||
#if defined(STM32F1)
|
||||
UNUSED(device);
|
||||
if ((adcTagMap[map].tag == tag)) {
|
||||
return true;
|
||||
}
|
||||
#else
|
||||
if ((adcTagMap[map].tag == tag) && (adcTagMap[map].devices & (1 << device))) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
return false;
|
||||
|
|
|
@ -39,17 +39,13 @@
|
|||
#else
|
||||
#define ADC_TAG_MAP_COUNT 47
|
||||
#endif
|
||||
#elif defined(STM32F3)
|
||||
#define ADC_TAG_MAP_COUNT 39
|
||||
#else
|
||||
#define ADC_TAG_MAP_COUNT 10
|
||||
#endif
|
||||
|
||||
typedef struct adcTagMap_s {
|
||||
ioTag_t tag;
|
||||
#if !defined(STM32F1) // F1 pins have uniform connection to ADC instances
|
||||
uint8_t devices;
|
||||
#endif
|
||||
uint32_t channel;
|
||||
#if defined(STM32H7) || defined(STM32G4)
|
||||
uint8_t channelOrdinal;
|
||||
|
|
|
@ -37,9 +37,7 @@ typedef enum I2CDevice {
|
|||
I2CDEV_4,
|
||||
} I2CDevice;
|
||||
|
||||
#if defined(STM32F1) || defined(STM32F3)
|
||||
#define I2CDEV_COUNT 2
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
#define I2CDEV_COUNT 3
|
||||
#elif defined(STM32F7)
|
||||
#define I2CDEV_COUNT 4
|
||||
|
|
|
@ -39,8 +39,6 @@ typedef struct i2cPinDef_s {
|
|||
|
||||
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
|
||||
#define I2CPINDEF(pin, af) { DEFIO_TAG_E(pin), af }
|
||||
#elif defined(STM32F1)
|
||||
#define I2CPINDEF(pin, af) { DEFIO_TAG_E(pin) }
|
||||
#else
|
||||
#define I2CPINDEF(pin) { DEFIO_TAG_E(pin) }
|
||||
#endif
|
||||
|
@ -51,15 +49,13 @@ typedef struct i2cHardware_s {
|
|||
i2cPinDef_t sclPins[I2C_PIN_SEL_MAX];
|
||||
i2cPinDef_t sdaPins[I2C_PIN_SEL_MAX];
|
||||
rccPeriphTag_t rcc;
|
||||
#if !defined(STM32F303xC)
|
||||
uint8_t ev_irq;
|
||||
uint8_t er_irq;
|
||||
#endif
|
||||
} i2cHardware_t;
|
||||
|
||||
extern const i2cHardware_t i2cHardware[];
|
||||
|
||||
#if defined(STM32F1) || defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
typedef struct i2cState_s {
|
||||
volatile bool error;
|
||||
volatile bool busy;
|
||||
|
@ -86,7 +82,7 @@ typedef struct i2cDevice_s {
|
|||
uint16_t clockSpeed;
|
||||
|
||||
// MCU/Driver dependent member follows
|
||||
#if defined(STM32F1) || defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
i2cState_t state;
|
||||
#endif
|
||||
#ifdef USE_HAL_DRIVER
|
||||
|
|
|
@ -1,310 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_I2C) && !defined(SOFT_I2C)
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/rcc.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_i2c_impl.h"
|
||||
#include "drivers/bus_i2c_timing.h"
|
||||
|
||||
#define IOCFG_I2C_PU IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP)
|
||||
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL)
|
||||
|
||||
#define I2C_GPIO_AF GPIO_AF_4
|
||||
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
|
||||
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
{
|
||||
.device = I2CDEV_1,
|
||||
.reg = I2C1,
|
||||
.sclPins = { I2CPINDEF(PA15), I2CPINDEF(PB6), I2CPINDEF(PB8) },
|
||||
.sdaPins = { I2CPINDEF(PA14), I2CPINDEF(PB7), I2CPINDEF(PB9) },
|
||||
.rcc = RCC_APB1(I2C1),
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_2
|
||||
{
|
||||
.device = I2CDEV_2,
|
||||
.reg = I2C2,
|
||||
.sclPins = { I2CPINDEF(PA9), I2CPINDEF(PF6) },
|
||||
.sdaPins = { I2CPINDEF(PA10) },
|
||||
.rcc = RCC_APB1(I2C2),
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
i2cDevice_t i2cDevice[I2CDEV_COUNT];
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
// I2C TimeoutUserCallback
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
uint32_t i2cTimeoutUserCallback(void)
|
||||
{
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return;
|
||||
}
|
||||
|
||||
i2cDevice_t *pDev = &i2cDevice[device];
|
||||
const i2cHardware_t *hw = pDev->hardware;
|
||||
|
||||
if (!hw) {
|
||||
return;
|
||||
}
|
||||
|
||||
I2C_TypeDef *I2Cx = pDev->reg;
|
||||
|
||||
IO_t scl = pDev->scl;
|
||||
IO_t sda = pDev->sda;
|
||||
|
||||
RCC_ClockCmd(hw->rcc, ENABLE);
|
||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_4);
|
||||
|
||||
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||
IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_4);
|
||||
|
||||
I2C_InitTypeDef i2cInit = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_OwnAddress1 = 0x00,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_Timing = i2cClockTIMINGR(SystemCoreClock, pDev->clockSpeed, 0)
|
||||
};
|
||||
|
||||
I2C_Init(I2Cx, &i2cInit);
|
||||
|
||||
I2C_StretchClockCmd(I2Cx, ENABLE);
|
||||
|
||||
I2C_Cmd(I2Cx, ENABLE);
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
|
||||
{
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return false;
|
||||
}
|
||||
|
||||
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
|
||||
|
||||
if (!I2Cx) {
|
||||
return false;
|
||||
}
|
||||
|
||||
addr_ <<= 1;
|
||||
|
||||
timeUs_t timeoutStartUs;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TCR flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Write data to TXDR */
|
||||
I2C_SendData(I2Cx, data);
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return false;
|
||||
}
|
||||
|
||||
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
|
||||
|
||||
if (!I2Cx) {
|
||||
return false;
|
||||
}
|
||||
|
||||
addr_ <<= 1;
|
||||
|
||||
timeUs_t timeoutStartUs;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TC flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
|
||||
|
||||
/* Wait until all data are received */
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(I2Cx);
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
timeoutStartUs = microsISR();
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= I2C_TIMEOUT_US) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||
{
|
||||
bool status = true;
|
||||
|
||||
for (uint8_t i = 0; i < len_; i++) {
|
||||
status &= i2cWrite(device, addr_, reg_ + i, data[i]);
|
||||
}
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
return i2cRead(device, addr_, reg, len, buf);
|
||||
}
|
||||
|
||||
bool i2cBusy(I2CDevice device, bool *error)
|
||||
{
|
||||
UNUSED(device);
|
||||
UNUSED(error);
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
|
@ -119,7 +119,7 @@ bool spiInit(SPIDevice device)
|
|||
#endif
|
||||
|
||||
case SPIDEV_3:
|
||||
#if defined(USE_SPI_DEVICE_3) && !defined(STM32F1)
|
||||
#if defined(USE_SPI_DEVICE_3)
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F3)
|
||||
#if defined(STM32F4)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
|
||||
|
@ -39,11 +39,6 @@
|
|||
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
|
||||
#elif defined(STM32F1)
|
||||
#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_PP, GPIO_Speed_50MHz)
|
||||
#endif
|
||||
|
||||
// De facto standard mode
|
||||
|
@ -71,9 +66,7 @@ typedef enum SPIDevice {
|
|||
SPIDEV_6
|
||||
} SPIDevice;
|
||||
|
||||
#if defined(STM32F1)
|
||||
#define SPIDEV_COUNT 2
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
#define SPIDEV_COUNT 3
|
||||
#elif defined(STM32F7)
|
||||
#define SPIDEV_COUNT 4
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#define SPI_TIMEOUT_US 10000
|
||||
|
||||
#if defined(STM32F1) || defined(STM32F3) || defined(STM32F4) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32G4)
|
||||
#define MAX_SPI_PIN_SEL 2
|
||||
#elif defined(STM32F7)
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
|
|
|
@ -38,112 +38,6 @@
|
|||
#include "pg/bus_spi.h"
|
||||
|
||||
const spiHardware_t spiHardware[] = {
|
||||
#ifdef STM32F1
|
||||
// Remapping is not supported and corresponding lines are commented out.
|
||||
// There also is some errata that may prevent these assignments from working:
|
||||
// http://www.st.com/content/ccc/resource/technical/document/errata_sheet/7d/02/75/64/17/fc/4d/fd/CD00190234.pdf/files/CD00190234.pdf/jcr:content/translations/en.CD00190234.pdf
|
||||
{
|
||||
.device = SPIDEV_1,
|
||||
.reg = SPI1,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA5) },
|
||||
// { DEFIO_TAG_E(PB3) },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA6) },
|
||||
// { DEFIO_TAG_E(PB4) },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA7) },
|
||||
// { DEFIO_TAG_E(PB5) },
|
||||
},
|
||||
.rcc = RCC_APB2(SPI1),
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_2,
|
||||
.reg = SPI2,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PB13) },
|
||||
// { DEFIO_TAG_E(PB3) },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PB14) },
|
||||
// { DEFIO_TAG_E(PB4) },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PB15) },
|
||||
// { DEFIO_TAG_E(PB5) },
|
||||
},
|
||||
.rcc = RCC_APB1(SPI2),
|
||||
},
|
||||
#endif
|
||||
#ifdef STM32F3
|
||||
|
||||
#ifndef GPIO_AF_SPI1
|
||||
#define GPIO_AF_SPI1 GPIO_AF_5
|
||||
#endif
|
||||
#ifndef GPIO_AF_SPI2
|
||||
#define GPIO_AF_SPI2 GPIO_AF_5
|
||||
#endif
|
||||
#ifndef GPIO_AF_SPI3
|
||||
#define GPIO_AF_SPI3 GPIO_AF_6
|
||||
#endif
|
||||
|
||||
{
|
||||
.device = SPIDEV_1,
|
||||
.reg = SPI1,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA5) },
|
||||
{ DEFIO_TAG_E(PB3) },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA6) },
|
||||
{ DEFIO_TAG_E(PB4) },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA7) },
|
||||
{ DEFIO_TAG_E(PB5) },
|
||||
},
|
||||
.af = GPIO_AF_SPI1,
|
||||
.rcc = RCC_APB2(SPI1),
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_2,
|
||||
.reg = SPI2,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PB13) },
|
||||
{ DEFIO_TAG_E(PB3) },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PB14) },
|
||||
{ DEFIO_TAG_E(PB4) },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PB15) },
|
||||
{ DEFIO_TAG_E(PB5) },
|
||||
},
|
||||
.af = GPIO_AF_SPI2,
|
||||
.rcc = RCC_APB1(SPI2),
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_3,
|
||||
.reg = SPI3,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PB3) },
|
||||
{ DEFIO_TAG_E(PC10) },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PB4) },
|
||||
{ DEFIO_TAG_E(PC11) },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PB5) },
|
||||
{ DEFIO_TAG_E(PC12) },
|
||||
},
|
||||
.af = GPIO_AF_SPI3,
|
||||
.rcc = RCC_APB1(SPI3),
|
||||
},
|
||||
#endif
|
||||
#ifdef STM32F4
|
||||
{
|
||||
.device = SPIDEV_1,
|
||||
|
|
|
@ -129,11 +129,7 @@ void cameraControlInit(void)
|
|||
return;
|
||||
}
|
||||
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(cameraControlRuntime.io, IOCFG_AF_PP);
|
||||
#else
|
||||
IOConfigGPIOAF(cameraControlRuntime.io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
#endif
|
||||
IOConfigGPIOAF(cameraControlRuntime.io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
|
||||
pwmOutConfig(&cameraControlRuntime.channel, timerHardware, timerClock(TIM6), CAMERA_CONTROL_PWM_RESOLUTION, 0, cameraControlRuntime.inverted);
|
||||
|
||||
|
|
|
@ -40,13 +40,6 @@ dmaChannelDescriptor_t dmaDescriptors[DMA_LAST_HANDLER] = {
|
|||
DEFINE_DMA_CHANNEL(DMA1, 5, 16),
|
||||
DEFINE_DMA_CHANNEL(DMA1, 6, 20),
|
||||
DEFINE_DMA_CHANNEL(DMA1, 7, 24),
|
||||
#if defined(STM32F3) || defined(STM32F10X_CL)
|
||||
DEFINE_DMA_CHANNEL(DMA2, 1, 0),
|
||||
DEFINE_DMA_CHANNEL(DMA2, 2, 4),
|
||||
DEFINE_DMA_CHANNEL(DMA2, 3, 8),
|
||||
DEFINE_DMA_CHANNEL(DMA2, 4, 12),
|
||||
DEFINE_DMA_CHANNEL(DMA2, 5, 16),
|
||||
#endif
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -61,14 +54,6 @@ DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_CH5_HANDLER)
|
|||
DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_CH6_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_CH7_HANDLER)
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F10X_CL)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_CH1_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_CH2_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_CH3_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER)
|
||||
#endif
|
||||
|
||||
#define RETURN_TCIF_FLAG(s, d, n) if (s == DMA ## d ## _Channel ## n) return DMA ## d ## _FLAG_TC ## n
|
||||
|
||||
uint32_t dmaFlag_IT_TCIF(const dmaResource_t *channel)
|
||||
|
|
|
@ -169,16 +169,7 @@ typedef enum {
|
|||
DMA1_CH5_HANDLER,
|
||||
DMA1_CH6_HANDLER,
|
||||
DMA1_CH7_HANDLER,
|
||||
#if defined(STM32F3) || defined(STM32F10X_CL)
|
||||
DMA2_CH1_HANDLER,
|
||||
DMA2_CH2_HANDLER,
|
||||
DMA2_CH3_HANDLER,
|
||||
DMA2_CH4_HANDLER,
|
||||
DMA2_CH5_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA2_CH5_HANDLER
|
||||
#else
|
||||
DMA_LAST_HANDLER = DMA1_CH7_HANDLER
|
||||
#endif
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 7) + 1)
|
||||
|
@ -201,11 +192,7 @@ typedef enum {
|
|||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#if defined(USE_CCM_CODE) && defined(STM32F3)
|
||||
#define DMA_HANDLER_CODE CCM_CODE
|
||||
#else
|
||||
#define DMA_HANDLER_CODE
|
||||
#endif
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) DMA_HANDLER_CODE void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
|
||||
|
@ -253,9 +240,6 @@ typedef enum {
|
|||
// Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0
|
||||
#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNDTR = (uint16_t)(__COUNTER__))
|
||||
#else
|
||||
#if defined(STM32F1)
|
||||
#define DMA_CCR_EN 1 // Not defined anywhere ...
|
||||
#endif
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
|
||||
#define DMAx_SetMemoryAddress(reg, address) ((DMA_ARCH_TYPE *)(reg))->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]
|
||||
#endif
|
||||
|
|
|
@ -464,93 +464,6 @@ static const dmaTimerMapping_t dmaTimerMapping[] = {
|
|||
{ TIM8, TC(CH3), { DMA(2, 2, 0), DMA(2, 4, 7) } },
|
||||
{ TIM8, TC(CH4), { DMA(2, 7, 7) } },
|
||||
};
|
||||
#undef TC
|
||||
#undef DMA
|
||||
|
||||
#else // STM32F3
|
||||
// The embedded ADC24_DMA_REMAP conditional should be removed
|
||||
// when (and if) F3 is going generic.
|
||||
#define DMA(d, c) { DMA_CODE(d, 0, c), (dmaResource_t *)DMA ## d ## _Channel ## c }
|
||||
static const dmaPeripheralMapping_t dmaPeripheralMapping[18] = {
|
||||
#ifdef USE_SPI
|
||||
{ DMA_PERIPH_SPI_MOSI, SPIDEV_1, { DMA(1, 3) } },
|
||||
{ DMA_PERIPH_SPI_MISO, SPIDEV_1, { DMA(1, 2) } },
|
||||
{ DMA_PERIPH_SPI_MOSI, SPIDEV_2, { DMA(1, 5) } },
|
||||
{ DMA_PERIPH_SPI_MISO, SPIDEV_2, { DMA(1, 4) } },
|
||||
{ DMA_PERIPH_SPI_MOSI, SPIDEV_3, { DMA(2, 2) } },
|
||||
{ DMA_PERIPH_SPI_MISO, SPIDEV_3, { DMA(2, 1) } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_ADC
|
||||
{ DMA_PERIPH_ADC, ADCDEV_1, { DMA(1, 1) } },
|
||||
#ifdef ADC24_DMA_REMAP
|
||||
{ DMA_PERIPH_ADC, ADCDEV_2, { DMA(2, 3) } },
|
||||
#else
|
||||
{ DMA_PERIPH_ADC, ADCDEV_2, { DMA(2, 1) } },
|
||||
#endif
|
||||
{ DMA_PERIPH_ADC, ADCDEV_3, { DMA(2, 5) } },
|
||||
#ifdef ADC24_DMA_REMAP
|
||||
{ DMA_PERIPH_ADC, ADCDEV_4, { DMA(2, 4) } },
|
||||
#else
|
||||
{ DMA_PERIPH_ADC, ADCDEV_4, { DMA(2, 2) } },
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_1, { DMA(1, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_1, { DMA(1, 5) } },
|
||||
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_2, { DMA(1, 7) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_2, { DMA(1, 6) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_3, { DMA(1, 2) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_3, { DMA(1, 3) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_4, { DMA(2, 5) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_4, { DMA(2, 3) } },
|
||||
};
|
||||
#endif
|
||||
|
||||
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)
|
||||
|
||||
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
||||
// Generated from 'timer_def.h'
|
||||
{ TIM1, TC(CH1), { DMA(1, 2) } },
|
||||
{ TIM1, TC(CH2), { DMA(1, 3) } },
|
||||
{ TIM1, TC(CH3), { DMA(1, 6) } },
|
||||
{ TIM1, TC(CH4), { DMA(1, 4) } },
|
||||
|
||||
{ TIM2, TC(CH1), { DMA(1, 5) } },
|
||||
{ TIM2, TC(CH2), { DMA(1, 7) } },
|
||||
{ TIM2, TC(CH3), { DMA(1, 1) } },
|
||||
{ TIM2, TC(CH4), { DMA(1, 7) } },
|
||||
|
||||
{ TIM3, TC(CH1), { DMA(1, 6) } },
|
||||
{ TIM3, TC(CH3), { DMA(1, 2) } },
|
||||
{ TIM3, TC(CH4), { DMA(1, 3) } },
|
||||
|
||||
{ TIM4, TC(CH1), { DMA(1, 1) } },
|
||||
{ TIM4, TC(CH2), { DMA(1, 4) } },
|
||||
{ TIM4, TC(CH3), { DMA(1, 5) } },
|
||||
|
||||
{ TIM8, TC(CH1), { DMA(2, 3) } },
|
||||
{ TIM8, TC(CH2), { DMA(2, 5) } },
|
||||
{ TIM8, TC(CH3), { DMA(2, 1) } },
|
||||
{ TIM8, TC(CH4), { DMA(2, 2) } },
|
||||
|
||||
{ TIM15, TC(CH1), { DMA(1, 5) } },
|
||||
|
||||
#ifdef REMAP_TIM16_DMA
|
||||
{ TIM16, TC(CH1), { DMA(1, 6) } },
|
||||
#else
|
||||
{ TIM16, TC(CH1), { DMA(1, 3) } },
|
||||
#endif
|
||||
|
||||
#ifdef REMAP_TIM17_DMA
|
||||
{ TIM17, TC(CH1), { DMA(1, 7) } },
|
||||
#else
|
||||
{ TIM17, TC(CH1), { DMA(1, 1) } },
|
||||
#endif
|
||||
};
|
||||
|
||||
#undef TC
|
||||
#undef DMA
|
||||
#endif
|
||||
|
|
|
@ -762,7 +762,7 @@ motorDevice_t *dshotBitbangDevInit(const motorDevConfig_t *motorConfig, uint8_t
|
|||
bbMotors[motorIndex].pinIndex = pinIndex;
|
||||
bbMotors[motorIndex].io = io;
|
||||
bbMotors[motorIndex].output = output;
|
||||
#if defined(STM32F4) || defined(STM32F3)
|
||||
#if defined(STM32F4)
|
||||
bbMotors[motorIndex].iocfg = IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, bbPuPdMode);
|
||||
#elif defined(STM32F7) || defined(STM32G4) || defined(STM32H7)
|
||||
bbMotors[motorIndex].iocfg = IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, bbPuPdMode);
|
||||
|
|
|
@ -71,7 +71,7 @@ motorDevice_t *dshotPwmDevInit(const struct motorDevConfig_s *motorConfig, uint1
|
|||
#define DSHOT_DMA_BUFFER_ATTRIBUTE // None
|
||||
#endif
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define DSHOT_DMA_BUFFER_UNIT uint32_t
|
||||
#else
|
||||
#define DSHOT_DMA_BUFFER_UNIT uint8_t
|
||||
|
|
|
@ -36,13 +36,13 @@ typedef struct {
|
|||
|
||||
extiChannelRec_t extiChannelRecs[16];
|
||||
|
||||
// IRQ grouping, same on F103, F303, F40x, F7xx, H7xx and G4xx.
|
||||
// IRQ grouping, same on F40x, F7xx, H7xx and G4xx.
|
||||
#define EXTI_IRQ_GROUPS 7
|
||||
// 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
|
||||
static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 };
|
||||
static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
|
||||
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
|
||||
EXTI0_IRQn,
|
||||
EXTI1_IRQn,
|
||||
|
@ -52,16 +52,6 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
|
|||
EXTI9_5_IRQn,
|
||||
EXTI15_10_IRQn
|
||||
};
|
||||
#elif defined(STM32F3)
|
||||
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
|
||||
EXTI0_IRQn,
|
||||
EXTI1_IRQn,
|
||||
EXTI2_TS_IRQn,
|
||||
EXTI3_IRQn,
|
||||
EXTI4_IRQn,
|
||||
EXTI9_5_IRQn,
|
||||
EXTI15_10_IRQn
|
||||
};
|
||||
#else
|
||||
# warning "Unknown CPU"
|
||||
#endif
|
||||
|
@ -71,7 +61,7 @@ static uint32_t triggerLookupTable[] = {
|
|||
[BETAFLIGHT_EXTI_TRIGGER_RISING] = GPIO_MODE_IT_RISING,
|
||||
[BETAFLIGHT_EXTI_TRIGGER_FALLING] = GPIO_MODE_IT_FALLING,
|
||||
[BETAFLIGHT_EXTI_TRIGGER_BOTH] = GPIO_MODE_IT_RISING_FALLING
|
||||
#elif defined(STM32F1) || defined(STM32F3) || defined(STM32F4)
|
||||
#elif defined(STM32F4)
|
||||
[BETAFLIGHT_EXTI_TRIGGER_RISING] = EXTI_Trigger_Rising,
|
||||
[BETAFLIGHT_EXTI_TRIGGER_FALLING] = EXTI_Trigger_Falling,
|
||||
[BETAFLIGHT_EXTI_TRIGGER_BOTH] = EXTI_Trigger_Rising_Falling
|
||||
|
@ -95,11 +85,7 @@ static uint32_t triggerLookupTable[] = {
|
|||
|
||||
void EXTIInit(void)
|
||||
{
|
||||
#if defined(STM32F1)
|
||||
// enable AFIO for EXTI support
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
||||
#endif
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||
#ifdef REMAP_TIM16_DMA
|
||||
|
@ -150,11 +136,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf
|
|||
#else
|
||||
IOConfigGPIO(io, config);
|
||||
|
||||
#if defined(STM32F10X)
|
||||
GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io));
|
||||
#elif defined(STM32F303xC)
|
||||
SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
|
||||
#else
|
||||
# warning "Unknown CPU"
|
||||
|
@ -198,7 +180,7 @@ void EXTIRelease(IO_t io)
|
|||
|
||||
void EXTIEnable(IO_t io)
|
||||
{
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
uint32_t extiLine = IO_EXTI_Line(io);
|
||||
|
||||
if (!extiLine) {
|
||||
|
@ -206,17 +188,6 @@ void EXTIEnable(IO_t io)
|
|||
}
|
||||
|
||||
EXTI_REG_IMR |= extiLine;
|
||||
#elif defined(STM32F303xC)
|
||||
|
||||
int extiLine = IO_EXTI_Line(io);
|
||||
|
||||
if (extiLine < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
// assume extiLine < 32 (valid for all EXTI pins)
|
||||
|
||||
EXTI_REG_IMR |= 1 << extiLine;
|
||||
#else
|
||||
# error "Unknown CPU"
|
||||
#endif
|
||||
|
@ -225,7 +196,7 @@ void EXTIEnable(IO_t io)
|
|||
|
||||
void EXTIDisable(IO_t io)
|
||||
{
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
uint32_t extiLine = IO_EXTI_Line(io);
|
||||
|
||||
if (!extiLine) {
|
||||
|
@ -234,17 +205,6 @@ void EXTIDisable(IO_t io)
|
|||
|
||||
EXTI_REG_IMR &= ~extiLine;
|
||||
EXTI_REG_PR = extiLine;
|
||||
#elif defined(STM32F303xC)
|
||||
|
||||
int extiLine = IO_EXTI_Line(io);
|
||||
|
||||
if (extiLine < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
// assume extiLine < 32 (valid for all EXTI pins)
|
||||
|
||||
EXTI_REG_IMR &= ~(1 << extiLine);
|
||||
#else
|
||||
# error "Unknown CPU"
|
||||
#endif
|
||||
|
@ -277,10 +237,8 @@ void EXTI_IRQHandler(uint32_t mask)
|
|||
|
||||
_EXTI_IRQ_HANDLER(EXTI0_IRQHandler, 0x0001);
|
||||
_EXTI_IRQ_HANDLER(EXTI1_IRQHandler, 0x0002);
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
_EXTI_IRQ_HANDLER(EXTI2_IRQHandler, 0x0004);
|
||||
#elif defined(STM32F3)
|
||||
_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler, 0x0004);
|
||||
#else
|
||||
# warning "Unknown CPU"
|
||||
#endif
|
||||
|
|
|
@ -31,38 +31,7 @@ struct ioPortDef_s {
|
|||
rccPeriphTag_t rcc;
|
||||
};
|
||||
|
||||
#if defined(STM32F1)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_APB2(IOPA) },
|
||||
{ RCC_APB2(IOPB) },
|
||||
{ RCC_APB2(IOPC) },
|
||||
{ RCC_APB2(IOPD) },
|
||||
{ RCC_APB2(IOPE) },
|
||||
{
|
||||
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
||||
RCC_APB2(IOPF),
|
||||
#else
|
||||
0,
|
||||
#endif
|
||||
},
|
||||
{
|
||||
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
|
||||
RCC_APB2(IOPG),
|
||||
#else
|
||||
0,
|
||||
#endif
|
||||
},
|
||||
};
|
||||
#elif defined(STM32F3)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB(GPIOA) },
|
||||
{ RCC_AHB(GPIOB) },
|
||||
{ RCC_AHB(GPIOC) },
|
||||
{ RCC_AHB(GPIOD) },
|
||||
{ RCC_AHB(GPIOE) },
|
||||
{ RCC_AHB(GPIOF) },
|
||||
};
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB1(GPIOA) },
|
||||
{ RCC_AHB1(GPIOB) },
|
||||
|
@ -166,10 +135,8 @@ uint32_t IO_EXTI_Line(IO_t io)
|
|||
if (!io) {
|
||||
return 0;
|
||||
}
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
return 1 << IO_GPIOPinIdx(io);
|
||||
#elif defined(STM32F3)
|
||||
return IO_GPIOPinIdx(io);
|
||||
#elif defined(SIMULATOR_BUILD)
|
||||
return 0;
|
||||
#else
|
||||
|
@ -315,26 +282,7 @@ bool IOIsFreeOrPreinit(IO_t io)
|
|||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef init = {
|
||||
.GPIO_Pin = IO_Pin(io),
|
||||
.GPIO_Speed = cfg & 0x03,
|
||||
.GPIO_Mode = cfg & 0x7c,
|
||||
};
|
||||
GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
#elif defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32H7) || defined(STM32G4)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
|
@ -389,7 +337,7 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
|||
LL_GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
#elif defined(STM32F4)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
|
|
|
@ -36,20 +36,7 @@
|
|||
// expand pinid to to ioTag_t
|
||||
#define IO_TAG(pinid) DEFIO_TAG(pinid)
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
||||
// mode is using only bits 6-2
|
||||
#define IO_CONFIG(mode, speed) ((mode) | (speed))
|
||||
|
||||
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_2MHz)
|
||||
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_2MHz)
|
||||
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_2MHz)
|
||||
#define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_2MHz)
|
||||
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz)
|
||||
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz)
|
||||
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz)
|
||||
|
||||
#elif defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
|
||||
//speed is packed inside modebits 5 and 2,
|
||||
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
|
||||
|
@ -67,7 +54,7 @@
|
|||
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
|
||||
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_HIGH, GPIO_PULLUP)
|
||||
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
#elif defined(STM32F4)
|
||||
|
||||
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
|
||||
|
||||
|
@ -122,7 +109,7 @@ bool IOIsFreeOrPreinit(IO_t io);
|
|||
IO_t IOGetByTag(ioTag_t tag);
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg);
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -44,7 +44,7 @@ int IO_GPIOPinIdx(IO_t io);
|
|||
int IO_GPIO_PinSource(IO_t io);
|
||||
int IO_GPIO_PortSource(IO_t io);
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
int IO_EXTI_PortSourceGPIO(IO_t io);
|
||||
int IO_EXTI_PinSource(IO_t io);
|
||||
#endif
|
||||
|
|
|
@ -57,9 +57,7 @@
|
|||
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
|
||||
DMA_RW_AXI __attribute__((aligned(32))) uint32_t ledStripDMABuffer[WS2811_DMA_BUF_CACHE_ALIGN_LENGTH];
|
||||
#else
|
||||
#if defined(STM32F1) || defined(STM32F3)
|
||||
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#elif defined(STM32F7)
|
||||
#if defined(STM32F7)
|
||||
FAST_DATA_ZERO_INIT uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#elif defined(STM32H7)
|
||||
DMA_RAM uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
|
|
|
@ -51,12 +51,8 @@
|
|||
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
|
||||
extern uint32_t ledStripDMABuffer[WS2811_DMA_BUF_CACHE_ALIGN_LENGTH];
|
||||
#else
|
||||
#if defined(STM32F1) || defined(STM32F3)
|
||||
extern uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#else
|
||||
extern uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define WS2811_TIMER_MHZ 48
|
||||
#define WS2811_CARRIER_HZ 800000
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#include "light_ws2811strip.h"
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
#if defined(STM32F4) || defined(STM32F3) || defined(STM32F1)
|
||||
#if defined(STM32F4)
|
||||
static dmaResource_t *dmaRef = NULL;
|
||||
#else
|
||||
#error "No MCU definition in light_ws2811strip_stdperiph.c"
|
||||
|
@ -115,11 +115,7 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
|||
|
||||
ws2811IO = IOGetByTag(ioTag);
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
|
||||
#else
|
||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
||||
#endif
|
||||
|
||||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||
|
||||
|
@ -192,13 +188,6 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
|||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
|
||||
#elif defined(STM32F3) || defined(STM32F1)
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
#endif
|
||||
|
||||
#if defined(USE_WS2811_SINGLE_COLOUR)
|
||||
|
|
|
@ -234,11 +234,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
|||
motors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
#if defined(STM32F1)
|
||||
IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
||||
#else
|
||||
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
#endif
|
||||
|
||||
/* standard PWM outputs */
|
||||
// margin of safety is 4 periods when unsynced
|
||||
|
@ -309,11 +305,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
|||
break;
|
||||
}
|
||||
|
||||
#if defined(STM32F1)
|
||||
IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
|
||||
#else
|
||||
IOConfigGPIOAF(servos[servoIndex].io, IOCFG_AF_PP, timer->alternateFunction);
|
||||
#endif
|
||||
|
||||
pwmOutConfig(&servos[servoIndex].channel, timer, PWM_TIMER_1MHZ, PWM_TIMER_1MHZ / servoConfig->servoPwmRate, servoConfig->servoCenterPulse, 0);
|
||||
servos[servoIndex].enabled = true;
|
||||
|
|
|
@ -38,8 +38,6 @@
|
|||
#include "drivers/system.h"
|
||||
#if defined(STM32F4)
|
||||
#include "stm32f4xx.h"
|
||||
#elif defined(STM32F3)
|
||||
#include "stm32f30x.h"
|
||||
#endif
|
||||
|
||||
#include "pwm_output.h"
|
||||
|
@ -98,18 +96,11 @@ FAST_CODE void pwmDshotSetDirectionOutput(
|
|||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
#if defined(STM32F3)
|
||||
pDmaInit->DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
#else
|
||||
pDmaInit->DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
#endif
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
#if defined(STM32F3)
|
||||
pDmaInit->DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
pDmaInit->DMA_M2M = DMA_M2M_Disable;
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
pDmaInit->DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
#endif
|
||||
}
|
||||
|
@ -120,11 +111,7 @@ FAST_CODE void pwmDshotSetDirectionOutput(
|
|||
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
#if defined(STM32F3)
|
||||
CCM_CODE
|
||||
#else
|
||||
FAST_CODE
|
||||
#endif
|
||||
static void pwmDshotSetDirectionInput(
|
||||
motorDmaOutput_t * const motor
|
||||
)
|
||||
|
@ -147,10 +134,7 @@ static void pwmDshotSetDirectionInput(
|
|||
|
||||
TIM_ICInit(timer, &motor->icInitStruct);
|
||||
|
||||
#if defined(STM32F3)
|
||||
motor->dmaInitStruct.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
motor->dmaInitStruct.DMA_M2M = DMA_M2M_Disable;
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
motor->dmaInitStruct.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
#endif
|
||||
|
||||
|
@ -188,12 +172,7 @@ void pwmCompleteDshotMotorUpdate(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(STM32F3)
|
||||
CCM_CODE
|
||||
#else
|
||||
FAST_CODE
|
||||
#endif
|
||||
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||
|
@ -375,10 +354,6 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
if (useBurstDshot) {
|
||||
motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0];
|
||||
|
||||
#if defined(STM32F3)
|
||||
DMAINIT.DMA_MemoryBaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
||||
DMAINIT.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
#else
|
||||
DMAINIT.DMA_Channel = timerHardware->dmaTimUPChannel;
|
||||
DMAINIT.DMA_Memory0BaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
||||
DMAINIT.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
|
@ -386,7 +361,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
DMAINIT.DMA_FIFOThreshold = DMA_FIFOThreshold_Full;
|
||||
DMAINIT.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
||||
DMAINIT.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||
#endif
|
||||
|
||||
DMAINIT.DMA_PeripheralBaseAddr = (uint32_t)&timerHardware->tim->DMAR;
|
||||
DMAINIT.DMA_BufferSize = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
|
||||
DMAINIT.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
|
@ -400,11 +375,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
{
|
||||
motor->dmaBuffer = &dshotDmaBuffer[motorIndex][0];
|
||||
|
||||
#if defined(STM32F3)
|
||||
DMAINIT.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer;
|
||||
DMAINIT.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMAINIT.DMA_M2M = DMA_M2M_Disable;
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
DMAINIT.DMA_Channel = dmaChannel;
|
||||
DMAINIT.DMA_Memory0BaseAddr = (uint32_t)motor->dmaBuffer;
|
||||
DMAINIT.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
|
|
|
@ -39,8 +39,6 @@
|
|||
#include "drivers/timer.h"
|
||||
#if defined(STM32F4)
|
||||
#include "stm32f4xx.h"
|
||||
#elif defined(STM32F3)
|
||||
#include "stm32f30x.h"
|
||||
#endif
|
||||
|
||||
#include "pwm_output.h"
|
||||
|
|
|
@ -113,11 +113,6 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
|
|||
}
|
||||
#else
|
||||
switch (tag) {
|
||||
#if defined(STM32F3) || defined(STM32F1)
|
||||
case RCC_AHB:
|
||||
RCC_AHBPeriphClockCmd(mask, NewState);
|
||||
break;
|
||||
#endif
|
||||
case RCC_APB2:
|
||||
RCC_APB2PeriphClockCmd(mask, NewState);
|
||||
break;
|
||||
|
@ -213,11 +208,6 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
|
|||
#else
|
||||
|
||||
switch (tag) {
|
||||
#if defined(STM32F3) || defined(STM32F10X_CL)
|
||||
case RCC_AHB:
|
||||
RCC_AHBPeriphResetCmd(mask, NewState);
|
||||
break;
|
||||
#endif
|
||||
case RCC_APB2:
|
||||
RCC_APB2PeriphResetCmd(mask, NewState);
|
||||
break;
|
||||
|
|
|
@ -386,11 +386,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
|
|||
|
||||
IO_t io = IOGetByTag(pwmConfig->ioTags[channel]);
|
||||
IOInit(io, OWNER_PWMINPUT, RESOURCE_INDEX(channel));
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(io, IOCFG_IPD);
|
||||
#else
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timer->alternateFunction);
|
||||
#endif
|
||||
timerConfigure(timer, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_1MHZ);
|
||||
timerChCCHandlerInit(&port->edgeCb, pwmEdgeCallback);
|
||||
timerChOvrHandlerInit(&port->overflowCb, pwmOverflowCallback);
|
||||
|
@ -443,11 +439,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig)
|
|||
|
||||
IO_t io = IOGetByTag(ppmConfig->ioTag);
|
||||
IOInit(io, OWNER_PPMINPUT, 0);
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(io, IOCFG_IPD);
|
||||
#else
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timer->alternateFunction);
|
||||
#endif
|
||||
|
||||
timerConfigure(timer, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_1MHZ);
|
||||
timerChCCHandlerInit(&port->edgeCb, ppmEdgeCallback);
|
||||
|
|
|
@ -192,11 +192,7 @@ static void escSerialGPIOConfig(const timerHardware_t *timhw, ioConfig_t cfg)
|
|||
|
||||
static void escSerialInputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||
{
|
||||
#ifdef STM32F10X
|
||||
escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU);
|
||||
#else
|
||||
escSerialGPIOConfig(timerHardwarePtr, IOCFG_AF_PP_UP);
|
||||
#endif
|
||||
timerChClearCCFlag(timerHardwarePtr);
|
||||
timerChITConfig(timerHardwarePtr,ENABLE);
|
||||
}
|
||||
|
|
|
@ -34,78 +34,7 @@
|
|||
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
// Backward compatibility for exisiting targets
|
||||
|
||||
// F1 targets don't explicitly define pins.
|
||||
|
||||
#ifdef STM32F1
|
||||
#ifdef USE_UART1
|
||||
#ifndef UART1_RX_PIN
|
||||
#define UART1_RX_PIN PA10
|
||||
#endif
|
||||
#ifndef UART1_TX_PIN
|
||||
#define UART1_TX_PIN PA9
|
||||
#endif
|
||||
#endif // USE_UART1
|
||||
|
||||
#ifdef USE_UART2
|
||||
#ifndef UART2_RX_PIN
|
||||
#define UART2_RX_PIN PA3
|
||||
#endif
|
||||
#ifndef UART2_TX_PIN
|
||||
#define UART2_TX_PIN PA2
|
||||
#endif
|
||||
#endif // USE_UART2
|
||||
#endif // STM32F1
|
||||
|
||||
// XXX Is there an F3 target that does not define UART pins?
|
||||
|
||||
#ifdef STM32F3
|
||||
#ifdef USE_UART1
|
||||
#ifndef UART1_TX_PIN
|
||||
#define UART1_TX_PIN PA9
|
||||
#endif
|
||||
#ifndef UART1_RX_PIN
|
||||
#define UART1_RX_PIN PA10
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2
|
||||
#ifndef UART2_TX_PIN
|
||||
#define UART2_TX_PIN PD5
|
||||
#endif
|
||||
#ifndef UART2_RX_PIN
|
||||
#define UART2_RX_PIN PD6
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3
|
||||
#ifndef UART3_TX_PIN
|
||||
#define UART3_TX_PIN PB10
|
||||
#endif
|
||||
#ifndef UART3_RX_PIN
|
||||
#define UART3_RX_PIN PB11
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4
|
||||
#ifndef UART4_TX_PIN
|
||||
#define UART4_TX_PIN PC10
|
||||
#endif
|
||||
#ifndef UART4_RX_PIN
|
||||
#define UART4_RX_PIN PC11
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART5
|
||||
#ifndef UART5_TX_PIN
|
||||
#define UART5_TX_PIN PC12
|
||||
#endif
|
||||
#ifndef UART5_RX_PIN
|
||||
#define UART5_RX_PIN PD2
|
||||
#endif
|
||||
#endif
|
||||
#endif // STM32F3
|
||||
// Backward compatibility for existing targets
|
||||
|
||||
// Default pin (NONE).
|
||||
|
||||
|
|
|
@ -130,19 +130,11 @@ static void serialEnableCC(softSerial_t *softSerial)
|
|||
static void serialInputPortActivate(softSerial_t *softSerial)
|
||||
{
|
||||
if (softSerial->port.options & SERIAL_INVERTED) {
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_IPD);
|
||||
#else
|
||||
const uint8_t pinConfig = (softSerial->port.options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_PP : IOCFG_AF_PP_PD;
|
||||
IOConfigGPIOAF(softSerial->rxIO, pinConfig, softSerial->timerHardware->alternateFunction);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_IPU);
|
||||
#else
|
||||
const uint8_t pinConfig = (softSerial->port.options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_PP : IOCFG_AF_PP_UP;
|
||||
IOConfigGPIOAF(softSerial->rxIO, pinConfig, softSerial->timerHardware->alternateFunction);
|
||||
#endif
|
||||
}
|
||||
|
||||
softSerial->rxActive = true;
|
||||
|
@ -170,26 +162,18 @@ static void serialInputPortDeActivate(softSerial_t *softSerial)
|
|||
|
||||
static void serialOutputPortActivate(softSerial_t *softSerial)
|
||||
{
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_OUT_PP);
|
||||
#else
|
||||
if (softSerial->exTimerHardware)
|
||||
IOConfigGPIOAF(softSerial->txIO, IOCFG_OUT_PP, softSerial->exTimerHardware->alternateFunction);
|
||||
else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_OUT_PP);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void serialOutputPortDeActivate(softSerial_t *softSerial)
|
||||
{
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_IN_FLOATING);
|
||||
#else
|
||||
if (softSerial->exTimerHardware)
|
||||
IOConfigGPIOAF(softSerial->txIO, IOCFG_IN_FLOATING, softSerial->exTimerHardware->alternateFunction);
|
||||
else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_IN_FLOATING);
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
||||
|
|
|
@ -54,7 +54,7 @@
|
|||
#elif defined(STM32F7)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
|
||||
#define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
|
||||
#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F1)
|
||||
#elif defined(STM32F4)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE // NONE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE // NONE
|
||||
#else
|
||||
|
|
|
@ -76,7 +76,7 @@ static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
#if !(defined(STM32F1) || defined(STM32F4))
|
||||
#if !(defined(STM32F4))
|
||||
static void uartConfigurePinSwap(uartPort_t *uartPort)
|
||||
{
|
||||
uartDevice_t *uartDevice = uartFindDevice(uartPort);
|
||||
|
|
|
@ -22,25 +22,7 @@
|
|||
|
||||
// Configuration constants
|
||||
|
||||
#if defined(STM32F1)
|
||||
#define UARTDEV_COUNT_MAX 3
|
||||
#define UARTHARDWARE_MAX_PINS 3
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#elif defined(STM32F3)
|
||||
#define UARTDEV_COUNT_MAX 5
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
#define UARTDEV_COUNT_MAX 6
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
|
@ -222,7 +204,7 @@ typedef struct uartDevice_s {
|
|||
uartPinDef_t tx;
|
||||
volatile uint8_t *rxBuffer;
|
||||
volatile uint8_t *txBuffer;
|
||||
#if !(defined(STM32F1) || defined(STM32F4)) // Older CPUs don't support pin swap.
|
||||
#if !defined(STM32F4) // Don't support pin swap.
|
||||
bool pinSwap;
|
||||
#endif
|
||||
} uartDevice_t;
|
||||
|
@ -243,10 +225,10 @@ void uartConfigureDma(uartDevice_t *uartdev);
|
|||
|
||||
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define UART_REG_RXD(base) ((base)->RDR)
|
||||
#define UART_REG_TXD(base) ((base)->TDR)
|
||||
#elif defined(STM32F1) || defined(STM32F4)
|
||||
#elif defined(STM32F4)
|
||||
#define UART_REG_RXD(base) ((base)->DR)
|
||||
#define UART_REG_TXD(base) ((base)->DR)
|
||||
#endif
|
||||
|
|
|
@ -53,7 +53,7 @@ void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
|||
const uartHardware_t *hardware = &uartHardware[hindex];
|
||||
const UARTDevice_e device = hardware->device;
|
||||
|
||||
#if !(defined(STM32F1) || defined(STM32F4)) // Older CPUs don't support pin swap.
|
||||
#if !defined(STM32F4) // Don't support pin swap.
|
||||
uartdev->pinSwap = false;
|
||||
#endif
|
||||
for (int pindex = 0 ; pindex < UARTHARDWARE_MAX_PINS ; pindex++) {
|
||||
|
@ -66,7 +66,7 @@ void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
|||
}
|
||||
|
||||
|
||||
#if !(defined(STM32F1) || defined(STM32F4))
|
||||
#if !defined(STM32F4)
|
||||
// Check for swapped pins
|
||||
if (pSerialPinConfig->ioTagTx[device] && (pSerialPinConfig->ioTagTx[device] == hardware->rxPins[pindex].pin)) {
|
||||
uartdev->tx = hardware->rxPins[pindex];
|
||||
|
|
|
@ -49,7 +49,7 @@
|
|||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
|
||||
#if !defined(USE_INVERTER)
|
||||
UNUSED(uartPort);
|
||||
#else
|
||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
|
@ -60,19 +60,6 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
|||
enableInverter(uartPort->USARTx, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef STM32F303xC
|
||||
uint32_t inversionPins = 0;
|
||||
|
||||
if (uartPort->port.mode & MODE_TX) {
|
||||
inversionPins |= USART_InvPin_Tx;
|
||||
}
|
||||
if (uartPort->port.mode & MODE_RX) {
|
||||
inversionPins |= USART_InvPin_Rx;
|
||||
}
|
||||
|
||||
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -85,12 +72,7 @@ void uartReconfigure(uartPort_t *uartPort)
|
|||
|
||||
// according to the stm32 documentation wordlen has to be 9 for parity bits
|
||||
// this does not seem to matter for rx but will give bad data on tx!
|
||||
// This seems to cause RX to break on STM32F1, see https://github.com/betaflight/betaflight/pull/1654
|
||||
if (
|
||||
#if defined(STM32F1)
|
||||
false &&
|
||||
#endif
|
||||
(uartPort->port.options & SERIAL_PARITY_EVEN)) {
|
||||
if (uartPort->port.options & SERIAL_PARITY_EVEN) {
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_9b;
|
||||
} else {
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
|
|
|
@ -1,226 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
* Authors:
|
||||
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||
* Dominic Clifton/Hydra - Various cleanups for Cleanflight
|
||||
* Bill Nesbitt - Code from AutoQuad
|
||||
* Hamasaki/Timecop - Initial baseflight code
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_UART
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/rcc.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
# define UART1_RX_DMA_CHANNEL DMA1_Channel5
|
||||
#else
|
||||
# define UART1_RX_DMA_CHANNEL 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART1_TX_DMA
|
||||
# define UART1_TX_DMA_CHANNEL DMA1_Channel4
|
||||
#else
|
||||
# define UART1_TX_DMA_CHANNEL 0
|
||||
#endif
|
||||
|
||||
#define UART2_RX_DMA_CHANNEL 0
|
||||
#define UART2_TX_DMA_CHANNEL 0
|
||||
#define UART3_RX_DMA_CHANNEL 0
|
||||
#define UART3_TX_DMA_CHANNEL 0
|
||||
|
||||
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||
#ifdef USE_UART1
|
||||
{
|
||||
.device = UARTDEV_1,
|
||||
.reg = USART1,
|
||||
.rxDMAResource = (dmaResource_t *)UART1_RX_DMA_CHANNEL,
|
||||
.txDMAResource = (dmaResource_t *)UART1_TX_DMA_CHANNEL,
|
||||
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) } },
|
||||
.txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) } },
|
||||
//.af = GPIO_AF_USART1,
|
||||
.rcc = RCC_APB2(USART1),
|
||||
.irqn = USART1_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART1,
|
||||
.txBuffer = uart1TxBuffer,
|
||||
.rxBuffer = uart1RxBuffer,
|
||||
.txBufferSize = sizeof(uart1TxBuffer),
|
||||
.rxBufferSize = sizeof(uart1RxBuffer),
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_UART2
|
||||
{
|
||||
.device = UARTDEV_2,
|
||||
.reg = USART2,
|
||||
.rxDMAResource = (dmaResource_t *)UART2_RX_DMA_CHANNEL,
|
||||
.txDMAResource = (dmaResource_t *)UART2_TX_DMA_CHANNEL,
|
||||
.rxPins = { { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PD6) } },
|
||||
.txPins = { { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PD5) } },
|
||||
//.af = GPIO_AF_USART2,
|
||||
.rcc = RCC_APB1(USART2),
|
||||
.irqn = USART2_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART2,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART2,
|
||||
.txBuffer = uart2TxBuffer,
|
||||
.rxBuffer = uart2RxBuffer,
|
||||
.txBufferSize = sizeof(uart2TxBuffer),
|
||||
.rxBufferSize = sizeof(uart2RxBuffer),
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_UART3
|
||||
{
|
||||
.device = UARTDEV_3,
|
||||
.reg = USART3,
|
||||
.rxDMAResource = (dmaResource_t *)UART3_RX_DMA_CHANNEL,
|
||||
.txDMAResource = (dmaResource_t *)UART3_TX_DMA_CHANNEL,
|
||||
.rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PD9) }, { DEFIO_TAG_E(PC11) } },
|
||||
.txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PD8) }, { DEFIO_TAG_E(PC10) } },
|
||||
//.af = GPIO_AF_USART3,
|
||||
.rcc = RCC_APB1(USART3),
|
||||
.irqn = USART3_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART3,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART3,
|
||||
.txBuffer = uart3TxBuffer,
|
||||
.rxBuffer = uart3RxBuffer,
|
||||
.txBufferSize = sizeof(uart3TxBuffer),
|
||||
.rxBufferSize = sizeof(uart3RxBuffer),
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
xDMA_Cmd(descriptor->ref, DISABLE); // XXX F1 needs this!!!
|
||||
|
||||
uartTryStartTxDMA(s);
|
||||
}
|
||||
|
||||
// XXX Should serialUART be consolidated?
|
||||
|
||||
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
{
|
||||
uartDevice_t *uartdev = uartDevmap[device];
|
||||
if (!uartdev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
uartPort_t *s = &uartdev->port;
|
||||
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
const uartHardware_t *hardware = uartdev->hardware;
|
||||
|
||||
s->USARTx = hardware->reg;
|
||||
|
||||
s->port.rxBuffer = hardware->rxBuffer;
|
||||
s->port.txBuffer = hardware->txBuffer;
|
||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||
s->port.txBufferSize = hardware->txBufferSize;
|
||||
|
||||
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||
|
||||
uartConfigureDma(uartdev);
|
||||
|
||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||
IO_t txIO = IOGetByTag(uartdev->tx.pin);
|
||||
|
||||
if (options & SERIAL_BIDIR) {
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIO(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIO(txIO, IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||
IOConfigGPIO(rxIO, IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
// RX/TX Interrupt
|
||||
if (!hardware->rxDMAResource || !hardware->txDMAResource) {
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_RXNE && !s->rxDMAResource) {
|
||||
// If we registered a callback, pass crap there
|
||||
if (s->port.rxCallback) {
|
||||
s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData);
|
||||
} else {
|
||||
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR;
|
||||
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||
s->port.rxBufferHead = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail++];
|
||||
if (s->port.txBufferTail >= s->port.txBufferSize) {
|
||||
s->port.txBufferTail = 0;
|
||||
}
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_IDLE) {
|
||||
if (s->port.idleCallback) {
|
||||
s->port.idleCallback();
|
||||
}
|
||||
|
||||
const uint32_t read_to_clear = s->USARTx->DR;
|
||||
(void) read_to_clear;
|
||||
}
|
||||
}
|
||||
#endif // USE_UART
|
|
@ -1,320 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
* Authors:
|
||||
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||
* Dominic Clifton - Port baseflight STM32F10x to STM32F30x for cleanflight
|
||||
* J. Ihlein - Code from FocusFlight32
|
||||
* Bill Nesbitt - Code from AutoQuad
|
||||
* Hamasaki/Timecop - Initial baseflight code
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_UART
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/rcc.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
// XXX Will DMA eventually be configurable?
|
||||
// XXX Do these belong here?
|
||||
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
# define UART1_RX_DMA DMA1_Channel5
|
||||
#else
|
||||
# define UART1_RX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART1_TX_DMA
|
||||
# define UART1_TX_DMA DMA1_Channel4
|
||||
#else
|
||||
# define UART1_TX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2_RX_DMA
|
||||
# define UART2_RX_DMA DMA1_Channel6
|
||||
#else
|
||||
# define UART2_RX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2_TX_DMA
|
||||
# define UART2_TX_DMA DMA1_Channel7
|
||||
#else
|
||||
# define UART2_TX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3_RX_DMA
|
||||
# define UART3_RX_DMA DMA1_Channel3
|
||||
#else
|
||||
# define UART3_RX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3_TX_DMA
|
||||
# define UART3_TX_DMA DMA1_Channel2
|
||||
#else
|
||||
# define UART3_TX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4_RX_DMA
|
||||
# define UART4_RX_DMA DMA2_Channel3
|
||||
#else
|
||||
# define UART4_RX_DMA 0
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4_TX_DMA
|
||||
# define UART4_TX_DMA DMA2_Channel5
|
||||
#else
|
||||
# define UART4_TX_DMA 0
|
||||
#endif
|
||||
|
||||
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||
#ifdef USE_UART1
|
||||
{
|
||||
.device = UARTDEV_1,
|
||||
.reg = USART1,
|
||||
.rxDMAResource = (dmaResource_t *)UART1_RX_DMA,
|
||||
.txDMAResource = (dmaResource_t *)UART1_TX_DMA,
|
||||
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) }, { DEFIO_TAG_E(PC5) }, { DEFIO_TAG_E(PE1) } },
|
||||
.txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) }, { DEFIO_TAG_E(PC4) }, { DEFIO_TAG_E(PE0) } },
|
||||
.rcc = RCC_APB2(USART1),
|
||||
.af = GPIO_AF_7,
|
||||
.irqn = USART1_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART1_RXDMA,
|
||||
.txBuffer = uart1TxBuffer,
|
||||
.rxBuffer = uart1RxBuffer,
|
||||
.txBufferSize = sizeof(uart1TxBuffer),
|
||||
.rxBufferSize = sizeof(uart1RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2
|
||||
{
|
||||
.device = UARTDEV_2,
|
||||
.reg = USART2,
|
||||
.rxDMAResource = (dmaResource_t *)UART2_RX_DMA,
|
||||
.txDMAResource = (dmaResource_t *)UART2_TX_DMA,
|
||||
.rxPins = { { DEFIO_TAG_E(PA15) }, { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PB4) }, { DEFIO_TAG_E(PD6) } },
|
||||
.txPins = { { DEFIO_TAG_E(PA14) }, { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PB3) }, { DEFIO_TAG_E(PD5) } },
|
||||
.rcc = RCC_APB1(USART2),
|
||||
.af = GPIO_AF_7,
|
||||
.irqn = USART2_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART2_RXDMA,
|
||||
.txBuffer = uart2TxBuffer,
|
||||
.rxBuffer = uart2RxBuffer,
|
||||
.txBufferSize = sizeof(uart2TxBuffer),
|
||||
.rxBufferSize = sizeof(uart2RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3
|
||||
{
|
||||
.device = UARTDEV_3,
|
||||
.reg = USART3,
|
||||
.rxDMAResource = (dmaResource_t *)UART3_RX_DMA,
|
||||
.txDMAResource = (dmaResource_t *)UART3_TX_DMA,
|
||||
.rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
|
||||
.txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
|
||||
.rcc = RCC_APB1(USART3),
|
||||
.af = GPIO_AF_7,
|
||||
.irqn = USART3_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART3_RXDMA,
|
||||
.txBuffer = uart3TxBuffer,
|
||||
.rxBuffer = uart3RxBuffer,
|
||||
.txBufferSize = sizeof(uart3TxBuffer),
|
||||
.rxBufferSize = sizeof(uart3RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4
|
||||
// UART4 XXX Not tested (yet!?) Need 303RC, e.g. LUX for testing
|
||||
{
|
||||
.device = UARTDEV_4,
|
||||
.reg = UART4,
|
||||
.rxDMAResource = (dmaResource_t *)0, // XXX UART4_RX_DMA !?
|
||||
.txDMAResource = (dmaResource_t *)0, // XXX UART4_TX_DMA !?
|
||||
.rxPins = { { DEFIO_TAG_E(PC11) } },
|
||||
.txPins = { { DEFIO_TAG_E(PC10) } },
|
||||
.rcc = RCC_APB1(UART4),
|
||||
.af = GPIO_AF_5,
|
||||
.irqn = UART4_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART4_RXDMA,
|
||||
.txBuffer = uart4TxBuffer,
|
||||
.rxBuffer = uart4RxBuffer,
|
||||
.txBufferSize = sizeof(uart4TxBuffer),
|
||||
.rxBufferSize = sizeof(uart4RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART5
|
||||
// UART5 XXX Not tested (yet!?) Need 303RC; e.g. LUX for testing
|
||||
{
|
||||
.device = UARTDEV_5,
|
||||
.reg = UART5,
|
||||
.rxDMAResource = (dmaResource_t *)0,
|
||||
.txDMAResource = (dmaResource_t *)0,
|
||||
.rxPins = { { DEFIO_TAG_E(PD2) } },
|
||||
.txPins = { { DEFIO_TAG_E(PC12) } },
|
||||
.rcc = RCC_APB1(UART5),
|
||||
.af = GPIO_AF_5,
|
||||
.irqn = UART5_IRQn,
|
||||
.txPriority = NVIC_PRIO_SERIALUART5,
|
||||
.rxPriority = NVIC_PRIO_SERIALUART5,
|
||||
.txBuffer = uart5TxBuffer,
|
||||
.rxBuffer = uart5RxBuffer,
|
||||
.txBufferSize = sizeof(uart5TxBuffer),
|
||||
.rxBufferSize = sizeof(uart5RxBuffer),
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
xDMA_Cmd(descriptor->ref, DISABLE);
|
||||
|
||||
uartTryStartTxDMA(s);
|
||||
}
|
||||
|
||||
void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_e mode, portOptions_e options, uint8_t af, uint8_t index)
|
||||
{
|
||||
if ((options & SERIAL_BIDIR) && txIO) {
|
||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
|
||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_OType_PP : GPIO_OType_OD,
|
||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||
);
|
||||
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
|
||||
IOConfigGPIOAF(txIO, ioCfg, af);
|
||||
|
||||
if (!(options & SERIAL_INVERTED))
|
||||
IOLo(txIO); // 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) && txIO) {
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
|
||||
IOConfigGPIOAF(txIO, ioCfg, af);
|
||||
}
|
||||
|
||||
if ((mode & MODE_RX) && rxIO) {
|
||||
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(index));
|
||||
IOConfigGPIOAF(rxIO, ioCfg, af);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// XXX Should serialUART be consolidated?
|
||||
|
||||
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
{
|
||||
uartDevice_t *uartDev = uartDevmap[device];
|
||||
if (!uartDev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
uartPort_t *s = &(uartDev->port);
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
const uartHardware_t *hardware = uartDev->hardware;
|
||||
|
||||
s->USARTx = hardware->reg;
|
||||
|
||||
|
||||
s->port.rxBuffer = hardware->rxBuffer;
|
||||
s->port.txBuffer = hardware->txBuffer;
|
||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||
s->port.txBufferSize = hardware->txBufferSize;
|
||||
|
||||
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||
|
||||
uartConfigureDma(uartDev);
|
||||
|
||||
serialUARTInitIO(IOGetByTag(uartDev->tx.pin), IOGetByTag(uartDev->rx.pin), mode, options, hardware->af, device);
|
||||
|
||||
if (!s->rxDMAResource || !s->txDMAResource) {
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
uint32_t ISR = s->USARTx->ISR;
|
||||
|
||||
if (!s->rxDMAResource && (ISR & USART_FLAG_RXNE)) {
|
||||
if (s->port.rxCallback) {
|
||||
s->port.rxCallback(s->USARTx->RDR, s->port.rxCallbackData);
|
||||
} else {
|
||||
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
|
||||
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||
s->port.rxBufferHead = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (!s->txDMAResource && (ISR & USART_FLAG_TXE)) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail++]);
|
||||
if (s->port.txBufferTail >= s->port.txBufferSize) {
|
||||
s->port.txBufferTail = 0;
|
||||
}
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
if (ISR & USART_FLAG_ORE)
|
||||
{
|
||||
USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
|
||||
}
|
||||
|
||||
if (ISR & USART_FLAG_IDLE) {
|
||||
if (s->port.idleCallback) {
|
||||
s->port.idleCallback();
|
||||
}
|
||||
|
||||
USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE);
|
||||
}
|
||||
}
|
||||
#endif // USE_UART
|
|
@ -67,11 +67,7 @@ static void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
|
|||
if (beeperIO && timer) {
|
||||
beeperPwm.io = beeperIO;
|
||||
IOInit(beeperPwm.io, OWNER_BEEPER, 0);
|
||||
#if defined(STM32F1)
|
||||
IOConfigGPIO(beeperPwm.io, IOCFG_AF_PP);
|
||||
#else
|
||||
IOConfigGPIOAF(beeperPwm.io, IOCFG_AF_PP, timer->alternateFunction);
|
||||
#endif
|
||||
freqBeep = frequency;
|
||||
pwmOutConfig(&beeperPwm.channel, timer, PWM_TIMER_1MHZ, PWM_TIMER_1MHZ / freqBeep, (PWM_TIMER_1MHZ / freqBeep) / 2, 0);
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
#include "system.h"
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
// See "RM CoreSight Architecture Specification"
|
||||
// B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register"
|
||||
// "E1.2.11 LAR, Lock Access Register"
|
||||
|
@ -71,7 +71,7 @@ void cycleCounterInit(void)
|
|||
ITM->LAR = DWT_LAR_UNLOCK_VALUE;
|
||||
#elif defined(STM32F7)
|
||||
DWT->LAR = DWT_LAR_UNLOCK_VALUE;
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
#elif defined(STM32F4)
|
||||
// Note: DWT_Type does not contain LAR member.
|
||||
#define DWT_LAR
|
||||
__O uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0);
|
||||
|
|
|
@ -1,124 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
|
||||
// from system_stm32f10x.c
|
||||
void SetSysClock(bool overclock);
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
// Generate system reset
|
||||
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
|
||||
}
|
||||
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType)
|
||||
{
|
||||
UNUSED(requestType);
|
||||
|
||||
// 1FFFF000 -> 20000200 -> SP
|
||||
// 1FFFF004 -> 1FFFF021 -> PC
|
||||
|
||||
*((uint32_t *)0x20004FF0) = 0xDEADBEEF; // 20KB STM32F103
|
||||
systemReset();
|
||||
}
|
||||
|
||||
static void checkForBootLoaderRequest(void)
|
||||
{
|
||||
void(*bootJump)(void);
|
||||
|
||||
if (*((uint32_t *)0x20004FF0) == 0xDEADBEEF) {
|
||||
|
||||
*((uint32_t *)0x20004FF0) = 0x0;
|
||||
|
||||
__enable_irq();
|
||||
__set_MSP(*((uint32_t *)0x1FFFF000));
|
||||
|
||||
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFFF004));
|
||||
bootJump();
|
||||
while (1);
|
||||
}
|
||||
}
|
||||
|
||||
void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||
{
|
||||
}
|
||||
|
||||
bool isMPUSoftReset(void)
|
||||
{
|
||||
if (cachedRccCsrValue & RCC_CSR_SFTRSTF)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
void systemInit(void)
|
||||
{
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
SetSysClock(false);
|
||||
|
||||
#if defined(OPBL)
|
||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
||||
extern void *isr_vector_table_base;
|
||||
|
||||
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
|
||||
#endif
|
||||
// Configure NVIC preempt/priority groups
|
||||
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
||||
|
||||
// Turn on clocks for stuff we use
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
||||
|
||||
// cache RCC->CSR value to use it in isMPUSoftReset() and others
|
||||
cachedRccCsrValue = RCC->CSR;
|
||||
RCC_ClearFlag();
|
||||
|
||||
enableGPIOPowerUsageAndNoiseReductions();
|
||||
|
||||
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
|
||||
// See issue https://github.com/cleanflight/cleanflight/issues/1433
|
||||
GPIO_InitTypeDef GPIO_InitStructure = {
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz
|
||||
};
|
||||
|
||||
GPIOA->BSRR = GPIO_InitStructure.GPIO_Pin;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
// Turn off JTAG port 'cause we're using the GPIO for leds
|
||||
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
|
||||
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
|
||||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
}
|
|
@ -1,107 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
|
||||
#define BOOTLOADER_MAGIC 0xDEADBEEF
|
||||
// 40KB SRAM STM32F30X
|
||||
#define BOOT_TARGET_REGISTER ((uint32_t *)0x20009FFC)
|
||||
|
||||
#define DEFAULT_STACK_POINTER ((uint32_t *)0x1FFFD800)
|
||||
#define SYSTEM_MEMORY_RESET_VECTOR ((uint32_t *) 0x1FFFD804)
|
||||
|
||||
void SetSysClock();
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
// Generate system reset
|
||||
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
|
||||
}
|
||||
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType)
|
||||
{
|
||||
UNUSED(requestType);
|
||||
// 1FFFF000 -> 20000200 -> SP
|
||||
// 1FFFF004 -> 1FFFF021 -> PC
|
||||
|
||||
*BOOT_TARGET_REGISTER = BOOTLOADER_MAGIC;
|
||||
|
||||
systemReset();
|
||||
}
|
||||
|
||||
|
||||
void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||
{
|
||||
}
|
||||
|
||||
bool isMPUSoftReset(void)
|
||||
{
|
||||
if (cachedRccCsrValue & RCC_CSR_SFTRSTF)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
static void checkForBootLoaderRequest(void)
|
||||
{
|
||||
if (*BOOT_TARGET_REGISTER == BOOTLOADER_MAGIC) {
|
||||
|
||||
*BOOT_TARGET_REGISTER = 0x0;
|
||||
|
||||
__enable_irq();
|
||||
__set_MSP(*DEFAULT_STACK_POINTER);
|
||||
|
||||
((void(*)(void))(*SYSTEM_MEMORY_RESET_VECTOR))();
|
||||
|
||||
while (1);
|
||||
}
|
||||
}
|
||||
|
||||
void systemInit(void)
|
||||
{
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
// Enable FPU
|
||||
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
|
||||
SetSysClock();
|
||||
|
||||
// Configure NVIC preempt/priority groups
|
||||
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
||||
|
||||
// cache RCC->CSR value to use it in isMPUSoftReset() and others
|
||||
cachedRccCsrValue = RCC->CSR;
|
||||
RCC_ClearFlag();
|
||||
|
||||
enableGPIOPowerUsageAndNoiseReductions();
|
||||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
}
|
|
@ -346,11 +346,6 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
timerNVICConfigure(irq);
|
||||
// HACK - enable second IRQ on timers that need it
|
||||
switch (irq) {
|
||||
#if defined(STM32F10X)
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_IRQn);
|
||||
break;
|
||||
#endif
|
||||
#if defined (STM32F40_41xxx) || defined(STM32F411xE)
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
|
||||
|
@ -360,16 +355,6 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
case TIM8_CC_IRQn:
|
||||
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
|
||||
break;
|
||||
#endif
|
||||
#ifdef STM32F303xC
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_TIM16_IRQn);
|
||||
break;
|
||||
#endif
|
||||
#if defined(STM32F10X_XL)
|
||||
case TIM8_CC_IRQn:
|
||||
timerNVICConfigure(TIM8_UP_IRQn);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -771,9 +756,6 @@ static inline void timUpdateHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig
|
|||
|
||||
#if USED_TIMERS & TIM_N(1)
|
||||
_TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
|
||||
# if defined(STM32F10X)
|
||||
_TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
|
||||
# endif
|
||||
# if defined(STM32F40_41xxx) || defined (STM32F411xE)
|
||||
# if USED_TIMERS & TIM_N(10)
|
||||
_TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
|
||||
|
@ -781,13 +763,6 @@ _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
|
|||
_TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
|
||||
# endif
|
||||
# endif
|
||||
# ifdef STM32F303xC
|
||||
# if USED_TIMERS & TIM_N(16)
|
||||
_TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
|
||||
# else
|
||||
_TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 1); // timer16 is not used
|
||||
# endif
|
||||
# endif
|
||||
#endif
|
||||
#if USED_TIMERS & TIM_N(2)
|
||||
_TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
|
||||
|
@ -820,11 +795,7 @@ _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler, 7);
|
|||
|
||||
#if USED_TIMERS & TIM_N(8)
|
||||
_TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
|
||||
# if defined(STM32F10X_XL)
|
||||
_TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
|
||||
# else // f10x_hd, f30x
|
||||
_TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
|
||||
# endif
|
||||
# if defined(STM32F40_41xxx)
|
||||
# if USED_TIMERS & TIM_N(13)
|
||||
_TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
|
||||
|
@ -850,9 +821,6 @@ _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler, 14);
|
|||
#if USED_TIMERS & TIM_N(15)
|
||||
_TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
|
||||
#endif
|
||||
#if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
|
||||
_TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 16); // only timer16 is used, not timer1
|
||||
#endif
|
||||
#if USED_TIMERS & TIM_N(17)
|
||||
_TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
|
||||
#endif
|
||||
|
|
|
@ -37,16 +37,11 @@
|
|||
|
||||
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST) || defined(SIMULATOR_BUILD)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST) || defined(SIMULATOR_BUILD)
|
||||
typedef uint32_t timCCR_t;
|
||||
typedef uint32_t timCCER_t;
|
||||
typedef uint32_t timSR_t;
|
||||
typedef uint32_t timCNT_t;
|
||||
#elif defined(STM32F1)
|
||||
typedef uint16_t timCCR_t;
|
||||
typedef uint16_t timCCER_t;
|
||||
typedef uint16_t timSR_t;
|
||||
typedef uint16_t timCNT_t;
|
||||
#else
|
||||
#error "Unknown CPU defined"
|
||||
#endif
|
||||
|
@ -91,7 +86,7 @@ typedef struct timerHardware_s {
|
|||
uint8_t channel;
|
||||
timerUsageFlag_e usageFlags;
|
||||
uint8_t output;
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
uint8_t alternateFunction;
|
||||
#endif
|
||||
|
||||
|
@ -122,17 +117,7 @@ typedef enum {
|
|||
TIMER_OUTPUT_N_CHANNEL = (1 << 1),
|
||||
} timerFlag_e;
|
||||
|
||||
#ifdef STM32F1
|
||||
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
||||
#elif defined(STM32F10X_HD) || defined(STM32F10X_CL)
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 7
|
||||
#else
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 4
|
||||
#endif
|
||||
#elif defined(STM32F3)
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 10
|
||||
#elif defined(STM32F411xE)
|
||||
#if defined(STM32F411xE)
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 10
|
||||
#elif defined(STM32F4)
|
||||
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
||||
|
@ -154,11 +139,7 @@ extern const timerHardware_t timerHardware[];
|
|||
|
||||
|
||||
#if defined(USE_TIMER_MGMT)
|
||||
#if defined(STM32F3)
|
||||
|
||||
#define FULL_TIMER_CHANNEL_COUNT 88
|
||||
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
|
||||
#if defined(STM32F411xE)
|
||||
#define FULL_TIMER_CHANNEL_COUNT 59
|
||||
|
@ -193,14 +174,6 @@ extern const timerHardware_t fullTimerHardware[];
|
|||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12) | TIM_N(13) | TIM_N(14) )
|
||||
#endif
|
||||
|
||||
#elif defined(STM32F3)
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
|
||||
#elif defined(STM32F1)
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
||||
|
||||
#elif defined(STM32H7)
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(12) | TIM_N(13) | TIM_N(14) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||
|
|
|
@ -143,266 +143,7 @@
|
|||
#define DEF_TIM_OUTPUT(ch) CONCAT(DEF_TIM_OUTPUT__, DEF_TIM_CH_GET(ch))
|
||||
#define DEF_TIM_OUTPUT__D(chan_n, n_channel) PP_IIF(n_channel, TIMER_OUTPUT_N_CHANNEL, TIMER_OUTPUT_NONE)
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
||||
#define DEF_TIM(tim, chan, pin, flags, out) { \
|
||||
tim, \
|
||||
TIMER_GET_IO_TAG(pin), \
|
||||
DEF_TIM_CHANNEL(CH_ ## chan), \
|
||||
flags, \
|
||||
(DEF_TIM_OUTPUT(CH_ ## chan) | out) \
|
||||
DEF_TIM_DMA_COND(/* add comma */ , \
|
||||
DEF_TIM_DMA_CHANNEL(TCH_## tim ## _ ## chan) \
|
||||
) \
|
||||
} \
|
||||
/**/
|
||||
|
||||
#define DEF_TIM_CHANNEL(ch) CONCAT(DEF_TIM_CHANNEL__, DEF_TIM_CH_GET(ch))
|
||||
#define DEF_TIM_CHANNEL__D(chan_n, n_channel) TIM_Channel_ ## chan_n
|
||||
|
||||
#define DEF_TIM_DMA_CHANNEL(timch) CONCAT(DEF_TIM_DMA_CHANNEL__, DEF_TIM_DMA_GET(0, timch))
|
||||
#define DEF_TIM_DMA_CHANNEL__D(dma_n, chan_n) DMA ## dma_n ## _Channel ## chan_n
|
||||
#define DEF_TIM_DMA_CHANNEL__NONE NULL
|
||||
|
||||
/* add F1 DMA mappings here */
|
||||
// D(dma_n, channel_n)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH1 D(1, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH2 NONE
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH3 D(1, 6)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH4 D(1, 4)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH1 D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH2 D(1, 7)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH3 D(1, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH4 D(1, 7)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH1 D(1, 6)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH2 NONE
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH3 D(1, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH4 D(1, 3)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH1 D(1, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH2 D(1, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH3 D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH4 NONE
|
||||
|
||||
#elif defined(STM32F3)
|
||||
|
||||
#define DEF_TIM(tim, chan, pin, flags, out) { \
|
||||
tim, \
|
||||
TIMER_GET_IO_TAG(pin), \
|
||||
DEF_TIM_CHANNEL(CH_ ## chan), \
|
||||
flags, \
|
||||
(DEF_TIM_OUTPUT(CH_ ## chan) | out), \
|
||||
DEF_TIM_AF(TCH_## tim ## _ ## chan, pin) \
|
||||
DEF_TIM_DMA_COND(/* add comma */ , \
|
||||
DEF_TIM_DMA_CHANNEL(TCH_## tim ## _ ## chan) \
|
||||
) \
|
||||
DEF_TIM_DMA_COND(/* add comma */ , \
|
||||
DEF_TIM_DMA_CHANNEL(TCH_## tim ## _UP), \
|
||||
DEF_TIM_DMA_HANDLER(TCH_## tim ## _UP) \
|
||||
) \
|
||||
} \
|
||||
/**/
|
||||
|
||||
#define DEF_TIM_CHANNEL(ch) CONCAT(DEF_TIM_CHANNEL__, DEF_TIM_CH_GET(ch))
|
||||
#define DEF_TIM_CHANNEL__D(chan_n, n_channel) TIM_Channel_ ## chan_n
|
||||
|
||||
#define DEF_TIM_AF(timch, pin) CONCAT(DEF_TIM_AF__, DEF_TIM_AF_GET(timch, pin))
|
||||
#define DEF_TIM_AF__D(af_n) GPIO_AF_ ## af_n
|
||||
|
||||
#define DEF_TIM_DMA_CHANNEL(timch) CONCAT(DEF_TIM_DMA_CHANNEL__, DEF_TIM_DMA_GET(0, timch))
|
||||
#define DEF_TIM_DMA_CHANNEL__D(dma_n, chan_n) (dmaResource_t *)DMA ## dma_n ## _Channel ## chan_n
|
||||
#define DEF_TIM_DMA_CHANNEL__NONE NULL
|
||||
|
||||
#define DEF_TIM_DMA_HANDLER(timch) CONCAT(DEF_TIM_DMA_HANDLER__, DEF_TIM_DMA_GET(0, timch))
|
||||
#define DEF_TIM_DMA_HANDLER__D(dma_n, chan_n) DMA ## dma_n ## _CH ## chan_n ## _HANDLER
|
||||
#define DEF_TIM_DMA_HANDLER__NONE 0
|
||||
|
||||
|
||||
/* add the DMA mappings here */
|
||||
// D(dma_n, channel_n)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH1 D(1, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH2 D(1, 3)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH4 D(1, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_TRIG D(1, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_COM D(1, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_CH3 D(1, 6)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH3 D(1, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH1 D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH2 D(1, 7)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_CH4 D(1, 7)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH2 NONE
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH3 D(1, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH4 D(1, 3)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_CH1 D(1, 6)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_TRIG D(1, 6)
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH1 D(1, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH2 D(1, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH3 D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_CH4 NONE
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_CH1 D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_CH2 NONE
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_UP D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_TRIG D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_COM D(1, 5)
|
||||
|
||||
#ifdef REMAP_TIM16_DMA
|
||||
#define DEF_TIM_DMA__BTCH_TIM16_CH1 D(1, 6)
|
||||
#else
|
||||
#define DEF_TIM_DMA__BTCH_TIM16_CH1 D(1, 3)
|
||||
#endif
|
||||
|
||||
#ifdef REMAP_TIM17_DMA
|
||||
#define DEF_TIM_DMA__BTCH_TIM17_CH1 D(1, 7)
|
||||
#else
|
||||
#define DEF_TIM_DMA__BTCH_TIM17_CH1 D(1, 1)
|
||||
#endif
|
||||
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_CH3 D(2, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_CH4 D(2, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_TRIG D(2, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_COM D(2, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_CH1 D(2, 3)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_CH2 D(2, 5)
|
||||
|
||||
// TIM_UP table
|
||||
#define DEF_TIM_DMA__BTCH_TIM1_UP D(1, 5)
|
||||
#define DEF_TIM_DMA__BTCH_TIM2_UP D(1, 2)
|
||||
#define DEF_TIM_DMA__BTCH_TIM3_UP D(1, 3)
|
||||
#define DEF_TIM_DMA__BTCH_TIM4_UP D(1, 7)
|
||||
#define DEF_TIM_DMA__BTCH_TIM6_UP D(2, 3)
|
||||
#define DEF_TIM_DMA__BTCH_TIM7_UP D(2, 4)
|
||||
#define DEF_TIM_DMA__BTCH_TIM8_UP D(2, 1)
|
||||
#define DEF_TIM_DMA__BTCH_TIM15_UP D(1, 5)
|
||||
#ifdef REMAP_TIM16_DMA
|
||||
#define DEF_TIM_DMA__BTCH_TIM16_UP D(1, 6)
|
||||
#else
|
||||
#define DEF_TIM_DMA__BTCH_TIM16_UP D(1, 3)
|
||||
#endif
|
||||
#ifdef REMAP_TIM17_DMA
|
||||
#define DEF_TIM_DMA__BTCH_TIM17_UP D(1, 7)
|
||||
#else
|
||||
#define DEF_TIM_DMA__BTCH_TIM17_UP D(1, 1)
|
||||
#endif
|
||||
|
||||
// AF table
|
||||
|
||||
#define DEF_TIM_AF__PA0__TCH_TIM2_CH1 D(1)
|
||||
#define DEF_TIM_AF__PA1__TCH_TIM2_CH2 D(1)
|
||||
#define DEF_TIM_AF__PA2__TCH_TIM2_CH3 D(1)
|
||||
#define DEF_TIM_AF__PA3__TCH_TIM2_CH4 D(1)
|
||||
#define DEF_TIM_AF__PA5__TCH_TIM2_CH1 D(1)
|
||||
#define DEF_TIM_AF__PA6__TCH_TIM16_CH1 D(1)
|
||||
#define DEF_TIM_AF__PA7__TCH_TIM17_CH1 D(1)
|
||||
#define DEF_TIM_AF__PA12__TCH_TIM16_CH1 D(1)
|
||||
#define DEF_TIM_AF__PA13__TCH_TIM16_CH1N D(1)
|
||||
#define DEF_TIM_AF__PA15__TCH_TIM2_CH1 D(1)
|
||||
|
||||
#define DEF_TIM_AF__PA4__TCH_TIM3_CH2 D(2)
|
||||
#define DEF_TIM_AF__PA6__TCH_TIM3_CH1 D(2)
|
||||
#define DEF_TIM_AF__PA7__TCH_TIM3_CH2 D(2)
|
||||
#define DEF_TIM_AF__PA15__TCH_TIM8_CH1 D(2)
|
||||
|
||||
#define DEF_TIM_AF__PA7__TCH_TIM8_CH1N D(4)
|
||||
|
||||
#define DEF_TIM_AF__PA14__TCH_TIM8_CH2 D(5)
|
||||
|
||||
#define DEF_TIM_AF__PA7__TCH_TIM1_CH1N D(6)
|
||||
#define DEF_TIM_AF__PA8__TCH_TIM1_CH1 D(6)
|
||||
#define DEF_TIM_AF__PA9__TCH_TIM1_CH2 D(6)
|
||||
#define DEF_TIM_AF__PA10__TCH_TIM1_CH3 D(6)
|
||||
#define DEF_TIM_AF__PA11__TCH_TIM1_CH1N D(6)
|
||||
#define DEF_TIM_AF__PA12__TCH_TIM1_CH2N D(6)
|
||||
|
||||
#define DEF_TIM_AF__PA1__TCH_TIM15_CH1N D(9)
|
||||
#define DEF_TIM_AF__PA2__TCH_TIM15_CH1 D(9)
|
||||
#define DEF_TIM_AF__PA3__TCH_TIM15_CH2 D(9)
|
||||
|
||||
#define DEF_TIM_AF__PA9__TCH_TIM2_CH3 D(10)
|
||||
#define DEF_TIM_AF__PA10__TCH_TIM2_CH4 D(10)
|
||||
#define DEF_TIM_AF__PA11__TCH_TIM4_CH1 D(10)
|
||||
#define DEF_TIM_AF__PA12__TCH_TIM4_CH2 D(10)
|
||||
#define DEF_TIM_AF__PA13__TCH_TIM4_CH3 D(10)
|
||||
#define DEF_TIM_AF__PA11__TCH_TIM1_CH4 D(11)
|
||||
|
||||
#define DEF_TIM_AF__PB3__TCH_TIM2_CH2 D(1)
|
||||
#define DEF_TIM_AF__PB4__TCH_TIM16_CH1 D(1)
|
||||
#define DEF_TIM_AF__PB6__TCH_TIM16_CH1N D(1)
|
||||
#define DEF_TIM_AF__PB7__TCH_TIM17_CH1N D(1)
|
||||
#define DEF_TIM_AF__PB8__TCH_TIM16_CH1 D(1)
|
||||
#define DEF_TIM_AF__PB9__TCH_TIM17_CH1 D(1)
|
||||
#define DEF_TIM_AF__PB10__TCH_TIM2_CH3 D(1)
|
||||
#define DEF_TIM_AF__PB11__TCH_TIM2_CH4 D(1)
|
||||
#define DEF_TIM_AF__PB14__TCH_TIM15_CH1 D(1)
|
||||
#define DEF_TIM_AF__PB15__TCH_TIM15_CH2 D(1)
|
||||
|
||||
#define DEF_TIM_AF__PB0__TCH_TIM3_CH3 D(2)
|
||||
#define DEF_TIM_AF__PB1__TCH_TIM3_CH4 D(2)
|
||||
#define DEF_TIM_AF__PB4__TCH_TIM3_CH1 D(2)
|
||||
#define DEF_TIM_AF__PB5__TCH_TIM3_CH2 D(2)
|
||||
#define DEF_TIM_AF__PB6__TCH_TIM4_CH1 D(2)
|
||||
#define DEF_TIM_AF__PB7__TCH_TIM4_CH2 D(2)
|
||||
#define DEF_TIM_AF__PB8__TCH_TIM4_CH3 D(2)
|
||||
#define DEF_TIM_AF__PB9__TCH_TIM4_CH4 D(2)
|
||||
#define DEF_TIM_AF__PB15__TCH_TIM15_CH1N D(2)
|
||||
|
||||
#define DEF_TIM_AF__PB5__TCH_TIM8_CH3N D(3)
|
||||
|
||||
#define DEF_TIM_AF__PB0__TCH_TIM8_CH2N D(4)
|
||||
#define DEF_TIM_AF__PB1__TCH_TIM8_CH3N D(4)
|
||||
#define DEF_TIM_AF__PB3__TCH_TIM8_CH1N D(4)
|
||||
#define DEF_TIM_AF__PB4__TCH_TIM8_CH2N D(4)
|
||||
#define DEF_TIM_AF__PB15__TCH_TIM1_CH3N D(4)
|
||||
|
||||
#define DEF_TIM_AF__PB6__TCH_TIM8_CH1 D(5)
|
||||
|
||||
#define DEF_TIM_AF__PB0__TCH_TIM1_CH2N D(6)
|
||||
#define DEF_TIM_AF__PB1__TCH_TIM1_CH3N D(6)
|
||||
#define DEF_TIM_AF__PB13__TCH_TIM1_CH1N D(6)
|
||||
#define DEF_TIM_AF__PB14__TCH_TIM1_CH2N D(6)
|
||||
|
||||
#define DEF_TIM_AF__PB5__TCH_TIM17_CH1 D(10)
|
||||
#define DEF_TIM_AF__PB7__TCH_TIM3_CH4 D(10)
|
||||
#define DEF_TIM_AF__PB8__TCH_TIM8_CH2 D(10)
|
||||
#define DEF_TIM_AF__PB9__TCH_TIM8_CH3 D(10)
|
||||
|
||||
#define DEF_TIM_AF__PC6__TCH_TIM3_CH1 D(2)
|
||||
#define DEF_TIM_AF__PC7__TCH_TIM3_CH2 D(2)
|
||||
#define DEF_TIM_AF__PC8__TCH_TIM3_CH3 D(2)
|
||||
#define DEF_TIM_AF__PC9__TCH_TIM3_CH4 D(2)
|
||||
|
||||
#define DEF_TIM_AF__PC6__TCH_TIM8_CH1 D(4)
|
||||
#define DEF_TIM_AF__PC7__TCH_TIM8_CH2 D(4)
|
||||
#define DEF_TIM_AF__PC8__TCH_TIM8_CH3 D(4)
|
||||
#define DEF_TIM_AF__PC9__TCH_TIM8_CH4 D(4)
|
||||
|
||||
#define DEF_TIM_AF__PC10__TCH_TIM8_CH1N D(4)
|
||||
#define DEF_TIM_AF__PC11__TCH_TIM8_CH2N D(4)
|
||||
#define DEF_TIM_AF__PC12__TCH_TIM8_CH3N D(4)
|
||||
#define DEF_TIM_AF__PC13__TCH_TIM8_CH1N D(4)
|
||||
|
||||
#define DEF_TIM_AF__PD3__TCH_TIM2_CH1 D(2)
|
||||
#define DEF_TIM_AF__PD4__TCH_TIM2_CH2 D(2)
|
||||
#define DEF_TIM_AF__PD6__TCH_TIM2_CH4 D(2)
|
||||
#define DEF_TIM_AF__PD7__TCH_TIM2_CH3 D(2)
|
||||
|
||||
#define DEF_TIM_AF__PD12__TCH_TIM4_CH1 D(2)
|
||||
#define DEF_TIM_AF__PD13__TCH_TIM4_CH2 D(2)
|
||||
#define DEF_TIM_AF__PD14__TCH_TIM4_CH3 D(2)
|
||||
#define DEF_TIM_AF__PD15__TCH_TIM4_CH4 D(2)
|
||||
|
||||
#define DEF_TIM_AF__PD1__TCH_TIM8_CH4 D(4)
|
||||
|
||||
#define DEF_TIM_AF__PF9__TCH_TIM15_CH1 D(3)
|
||||
#define DEF_TIM_AF__PF10__TCH_TIM15_CH2 D(3)
|
||||
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
|
||||
#define DEF_TIM(tim, chan, pin, flags, out, dmaopt) { \
|
||||
tim, \
|
||||
|
|
|
@ -951,9 +951,6 @@ _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
|
|||
#if defined(STM32H7) && (USED_TIMERS & TIM_N(16))
|
||||
_TIM_IRQ_HANDLER(TIM16_IRQHandler, 16);
|
||||
#endif
|
||||
#if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
|
||||
_TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 16); // only timer16 is used, not timer1
|
||||
#endif
|
||||
#if USED_TIMERS & TIM_N(17)
|
||||
# if defined(STM32H7)
|
||||
_TIM_IRQ_HANDLER(TIM17_IRQHandler, 17);
|
||||
|
@ -1031,7 +1028,7 @@ void timerInit(void)
|
|||
RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE);
|
||||
}
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
for (unsigned timerIndex = 0; timerIndex < TIMER_CHANNEL_COUNT; timerIndex++) {
|
||||
const timerHardware_t *timerHardwarePtr = &TIMER_HARDWARE[timerIndex];
|
||||
if (timerHardwarePtr->usageFlags == TIM_USE_NONE) {
|
||||
|
|
|
@ -1,57 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_TIMER
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), .inputIrq = TIM3_IRQn },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), .inputIrq = TIM4_IRQn },
|
||||
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
|
||||
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), .inputIrq = TIM5_IRQn },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0 },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0 },
|
||||
#endif
|
||||
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB1(TIM8), .inputIrq = TIM8_CC_IRQn },
|
||||
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), .inputIrq = TIM1_BRK_TIM9_IRQn },
|
||||
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), .inputIrq = TIM1_UP_TIM10_IRQn },
|
||||
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), .inputIrq = TIM1_TRG_COM_TIM11_IRQn },
|
||||
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), .inputIrq = TIM12_IRQn },
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), .inputIrq = TIM13_IRQn },
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), .inputIrq = TIM14_IRQn },
|
||||
#endif
|
||||
};
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return SystemCoreClock;
|
||||
}
|
||||
#endif
|
|
@ -1,168 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_TIMER
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "stm32f30x.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), .inputIrq = TIM3_IRQn },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), .inputIrq = TIM4_IRQn },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0 },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0 },
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), .inputIrq = TIM8_CC_IRQn },
|
||||
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15), .inputIrq = TIM1_BRK_TIM15_IRQn },
|
||||
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16), .inputIrq = TIM1_UP_TIM16_IRQn },
|
||||
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), .inputIrq = TIM1_TRG_COM_TIM17_IRQn },
|
||||
};
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return SystemCoreClock;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_TIMER_MGMT)
|
||||
const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = {
|
||||
|
||||
// Auto-generated from 'timer_def.h'
|
||||
// Search: \#define DEF_TIM_AF__(.*)__TCH_(.*)_([^ ]*).*
|
||||
// Replace: DEF_TIM($2, $3, $1, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1, PA6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1, PA12, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1N, PA13, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH2, PA7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH1, PA15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH1N, PA7, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH2, PA14, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH1N, PA7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH1N, PA11, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH2N, PA12, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM15, CH1N, PA1, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH1, PA2, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH2, PA3, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM2, CH3, PA9, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH4, PA10, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH1, PA11, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH2, PA12, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH3, PA13, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH4, PA11, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1, PB4, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1N, PB6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM17, CH1N, PB7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM17, CH1, PB9, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH1, PB14, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH2, PB15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH1N, PB15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH3N, PB5, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH1N, PB3, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH2N, PB4, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH1, PB6, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH1N, PB13, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM1, CH2N, PB14, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM17, CH1, PB5, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH4, PB7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH1N, PC10, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH2N, PC11, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH3N, PC12, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM8, CH1N, PC13, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM2, CH1, PD3, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH2, PD4, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH4, PD6, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM2, CH3, PD7, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH2, PD13, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH3, PD14, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM4, CH4, PD15, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH4, PD1, TIM_USE_ANY, 0),
|
||||
|
||||
DEF_TIM(TIM15, CH1, PF9, TIM_USE_ANY, 0),
|
||||
DEF_TIM(TIM15, CH2, PF10, TIM_USE_ANY, 0),
|
||||
|
||||
};
|
||||
#endif
|
|
@ -69,10 +69,8 @@
|
|||
* Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast
|
||||
* ISR to generate the output signal dynamically based on state would be more memory efficient and would likely be more appropriate for
|
||||
* other targets. However this approach requires very little CPU time and is just fire-and-forget.
|
||||
*
|
||||
* On an STM32F303CC 720 bytes is currently fine and that is the target for which this code was designed for.
|
||||
*/
|
||||
#if defined(STM32F3) || defined(UNIT_TEST)
|
||||
#if defined(UNIT_TEST)
|
||||
|
||||
typedef union transponderIrDMABuffer_s {
|
||||
uint8_t arcitimer[TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER]; // 620
|
||||
|
@ -96,7 +94,7 @@ typedef struct transponder_s {
|
|||
uint16_t bitToggleOne;
|
||||
uint32_t dma_buffer_size;
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4)|| defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
#if defined(STM32F4)|| defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
transponderIrDMABuffer_t transponderIrDMABuffer;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/transponder_ir_arcitimer.h"
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
|
||||
extern const struct transponderVTable arcitimerTansponderVTable;
|
||||
static uint16_t dmaBufferOffset;
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/transponder_ir_erlt.h"
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
|
||||
static uint16_t dmaBufferOffset;
|
||||
extern const struct transponderVTable erltTansponderVTable;
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/transponder_ir_ilap.h"
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST)
|
||||
|
||||
static uint16_t dmaBufferOffset;
|
||||
extern const struct transponderVTable ilapTansponderVTable;
|
||||
|
|
|
@ -138,11 +138,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
|
|||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||
#if defined(STM32F3)
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&(transponder->transponderIrDMABuffer);
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
#elif defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
DMA_InitStructure.DMA_Channel = dmaChannel;
|
||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&(transponder->transponderIrDMABuffer);
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
|
@ -150,11 +146,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
|
|||
DMA_InitStructure.DMA_BufferSize = transponder->dma_buffer_size;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
#if defined(STM32F3)
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
#elif defined(STM32F4)
|
||||
|
||||
#if defined(STM32F4)
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
#endif
|
||||
|
|
|
@ -89,11 +89,7 @@ pt1Filter_t throttleLpf;
|
|||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 3);
|
||||
|
||||
#if defined(STM32F1)
|
||||
#define PID_PROCESS_DENOM_DEFAULT 8
|
||||
#elif defined(STM32F3)
|
||||
#define PID_PROCESS_DENOM_DEFAULT 4
|
||||
#elif defined(STM32F411xE) || defined(STM32G4) //G4 sometimes cpu overflow when PID rate set to higher than 4k
|
||||
#if defined(STM32F411xE)
|
||||
#define PID_PROCESS_DENOM_DEFAULT 2
|
||||
#else
|
||||
#define PID_PROCESS_DENOM_DEFAULT 1
|
||||
|
|
|
@ -71,11 +71,7 @@ typedef enum {
|
|||
#define MSP_PORT_OUTBUF_SIZE_MIN 320
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
#ifdef STM32F1
|
||||
#define MSP_PORT_DATAFLASH_BUFFER_SIZE 1024
|
||||
#else
|
||||
#define MSP_PORT_DATAFLASH_BUFFER_SIZE 4096
|
||||
#endif
|
||||
#define MSP_PORT_DATAFLASH_INFO_SIZE 16
|
||||
#define MSP_PORT_OUTBUF_SIZE (MSP_PORT_DATAFLASH_BUFFER_SIZE + MSP_PORT_DATAFLASH_INFO_SIZE)
|
||||
#else
|
||||
|
|
|
@ -108,41 +108,11 @@
|
|||
#define STM32F4
|
||||
#endif
|
||||
|
||||
#elif defined(STM32F303xC)
|
||||
#include "stm32f30x_conf.h"
|
||||
#include "stm32f30x_rcc.h"
|
||||
#include "stm32f30x_gpio.h"
|
||||
#include "core_cm4.h"
|
||||
|
||||
// Chip Unique ID on F303
|
||||
#define U_ID_0 (*(uint32_t*)0x1FFFF7AC)
|
||||
#define U_ID_1 (*(uint32_t*)0x1FFFF7B0)
|
||||
#define U_ID_2 (*(uint32_t*)0x1FFFF7B4)
|
||||
|
||||
#ifndef STM32F3
|
||||
#define STM32F3
|
||||
#endif
|
||||
|
||||
#elif defined(STM32F10X)
|
||||
|
||||
#include "stm32f10x_conf.h"
|
||||
#include "stm32f10x_gpio.h"
|
||||
#include "core_cm3.h"
|
||||
|
||||
// Chip Unique ID on F103
|
||||
#define U_ID_0 (*(uint32_t*)0x1FFFF7E8)
|
||||
#define U_ID_1 (*(uint32_t*)0x1FFFF7EC)
|
||||
#define U_ID_2 (*(uint32_t*)0x1FFFF7F0)
|
||||
|
||||
#ifndef STM32F1
|
||||
#define STM32F1
|
||||
#endif
|
||||
|
||||
#elif defined(SIMULATOR_BUILD)
|
||||
|
||||
// Nop
|
||||
|
||||
#else // STM32F10X
|
||||
#else
|
||||
#error "Invalid chipset specified. Update platform.h"
|
||||
#endif
|
||||
|
||||
|
|
|
@ -368,7 +368,7 @@ bool accInit(uint16_t accSampleRateHz)
|
|||
acc.dev.acc_high_fsr = accelerometerConfig()->acc_high_fsr;
|
||||
|
||||
// Copy alignment from active gyro, as all production boards use acc-gyro-combi chip.
|
||||
// Exceptions are STM32F3DISCOVERY and STM32F411DISCOVERY, and (may be) handled in future enhancement.
|
||||
// Exception is STM32F411DISCOVERY, and (may be) handled in future enhancement.
|
||||
|
||||
sensor_align_e alignment = gyroDeviceConfig(0)->alignment;
|
||||
const sensorAlignment_t* customAlignment = &gyroDeviceConfig(0)->customAlignment;
|
||||
|
|
|
@ -1,362 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f1xx_hal_conf.h
|
||||
* @brief HAL configuration template file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F1xx_HAL_CONF_H
|
||||
#define __STM32F1xx_HAL_CONF_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* ########################## Module Selection ############################## */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
//#define HAL_CAN_MODULE_ENABLED
|
||||
//#define HAL_CEC_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
//#define HAL_CRC_MODULE_ENABLED
|
||||
//#define HAL_DAC_MODULE_ENABLED
|
||||
#define HAL_DMA_MODULE_ENABLED
|
||||
//#define HAL_ETH_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
//#define HAL_HCD_MODULE_ENABLED
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
//#define HAL_I2S_MODULE_ENABLED
|
||||
//#define HAL_IRDA_MODULE_ENABLED
|
||||
//#define HAL_IWDG_MODULE_ENABLED
|
||||
//#define HAL_NAND_MODULE_ENABLED
|
||||
//#define HAL_NOR_MODULE_ENABLED
|
||||
//#define HAL_PCCARD_MODULE_ENABLED
|
||||
#define HAL_PCD_MODULE_ENABLED
|
||||
#define HAL_PWR_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
//#define HAL_RTC_MODULE_ENABLED
|
||||
//#define HAL_SD_MODULE_ENABLED
|
||||
//#define HAL_SMARTCARD_MODULE_ENABLED
|
||||
#define HAL_SPI_MODULE_ENABLED
|
||||
//#define HAL_SRAM_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
#define HAL_USART_MODULE_ENABLED
|
||||
//#define HAL_WWDG_MODULE_ENABLED
|
||||
|
||||
/* ########################## Oscillator Values adaptation ####################*/
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#if defined(USE_STM3210C_EVAL)
|
||||
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
|
||||
#else
|
||||
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
|
||||
#endif
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief External Low Speed oscillator (LSE) value.
|
||||
* This value is used by the UART, RTC HAL module to compute the system frequency
|
||||
*/
|
||||
#if !defined (LSE_VALUE)
|
||||
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
|
||||
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||
|
||||
/* ########################### System Configuration ######################### */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */
|
||||
#define USE_RTOS 0
|
||||
#define PREFETCH_ENABLE 1
|
||||
|
||||
/* ########################## Assert Selection ############################## */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/*#define USE_FULL_ASSERT 1*/
|
||||
|
||||
|
||||
/* ################## Ethernet peripheral configuration ##################### */
|
||||
|
||||
/* Section 1 : Ethernet peripheral configuration */
|
||||
|
||||
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
|
||||
#define MAC_ADDR0 2
|
||||
#define MAC_ADDR1 0
|
||||
#define MAC_ADDR2 0
|
||||
#define MAC_ADDR3 0
|
||||
#define MAC_ADDR4 0
|
||||
#define MAC_ADDR5 0
|
||||
|
||||
/* Definition of the Ethernet driver buffers size and count */
|
||||
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
|
||||
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
|
||||
#define ETH_RXBUFNB ((uint32_t)8) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
|
||||
#define ETH_TXBUFNB ((uint32_t)4) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
|
||||
|
||||
/* Section 2: PHY configuration section */
|
||||
|
||||
/* DP83848 PHY Address*/
|
||||
#define DP83848_PHY_ADDRESS 0x01
|
||||
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
|
||||
#define PHY_RESET_DELAY ((uint32_t)0x000000FF)
|
||||
/* PHY Configuration delay */
|
||||
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF)
|
||||
|
||||
#define PHY_READ_TO ((uint32_t)0x0000FFFF)
|
||||
#define PHY_WRITE_TO ((uint32_t)0x0000FFFF)
|
||||
|
||||
/* Section 3: Common PHY Registers */
|
||||
|
||||
#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */
|
||||
#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */
|
||||
|
||||
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
|
||||
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
|
||||
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
|
||||
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
|
||||
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
|
||||
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
|
||||
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
|
||||
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
|
||||
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
|
||||
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
|
||||
|
||||
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
|
||||
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
|
||||
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
|
||||
|
||||
/* Section 4: Extended PHY Registers */
|
||||
|
||||
#define PHY_SR ((uint16_t)0x10) /*!< PHY status register Offset */
|
||||
#define PHY_MICR ((uint16_t)0x11) /*!< MII Interrupt Control Register */
|
||||
#define PHY_MISR ((uint16_t)0x12) /*!< MII Interrupt Status and Misc. Control Register */
|
||||
|
||||
#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */
|
||||
#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */
|
||||
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */
|
||||
|
||||
#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */
|
||||
#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */
|
||||
|
||||
#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */
|
||||
#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */
|
||||
|
||||
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_rcc.h"
|
||||
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_gpio.h"
|
||||
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_dma.h"
|
||||
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ETH_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_eth.h"
|
||||
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_can.h"
|
||||
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CEC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_cec.h"
|
||||
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_cortex.h"
|
||||
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_adc.h"
|
||||
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_crc.h"
|
||||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_dac.h"
|
||||
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_flash.h"
|
||||
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_sram.h"
|
||||
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NOR_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_nor.h"
|
||||
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2S_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_i2s.h"
|
||||
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_iwdg.h"
|
||||
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PWR_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_pwr.h"
|
||||
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_rtc.h"
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCCARD_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_pccard.h"
|
||||
#endif /* HAL_PCCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SD_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_sd.h"
|
||||
#endif /* HAL_SD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_tim.h"
|
||||
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_uart.h"
|
||||
#endif /* HAL_UART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_USART_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_usart.h"
|
||||
#endif /* HAL_USART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_irda.h"
|
||||
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_smartcard.h"
|
||||
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_HCD_MODULE_ENABLED
|
||||
#include "stm32f1xx_hal_hcd.h"
|
||||
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert_failed(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __STM32F1xx_HAL_CONF_H */
|
||||
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -1,335 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f3xx_hal_conf.h
|
||||
* @brief HAL configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted provided that the following conditions are met:
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F3xx_HAL_CONF_H
|
||||
#define __STM32F3xx_HAL_CONF_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* ########################## Module Selection ############################## */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
//#define HAL_CAN_MODULE_ENABLED
|
||||
//#define HAL_CEC_MODULE_ENABLED
|
||||
//#define HAL_COMP_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
//#define HAL_CRC_MODULE_ENABLED
|
||||
#define HAL_DAC_MODULE_ENABLED
|
||||
#define HAL_DMA_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
//#define HAL_SRAM_MODULE_ENABLED
|
||||
//#define HAL_NOR_MODULE_ENABLED
|
||||
//#define HAL_NAND_MODULE_ENABLED
|
||||
//#define HAL_PCCARD_MODULE_ENABLED
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
//#define HAL_HRTIM_MODULE_ENABLED
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
//#define HAL_I2S_MODULE_ENABLED
|
||||
//#define HAL_IRDA_MODULE_ENABLED
|
||||
//#define HAL_IWDG_MODULE_ENABLED
|
||||
//#define HAL_OPAMP_MODULE_ENABLED
|
||||
#define HAL_PCD_MODULE_ENABLED
|
||||
#define HAL_PWR_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
//#define HAL_RTC_MODULE_ENABLED
|
||||
//#define HAL_SDADC_MODULE_ENABLED
|
||||
//#define HAL_SMARTCARD_MODULE_ENABLED
|
||||
//#define HAL_SMBUS_MODULE_ENABLED
|
||||
#define HAL_SPI_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
//#define HAL_TSC_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
#define HAL_USART_MODULE_ENABLED
|
||||
//#define HAL_WWDG_MODULE_ENABLED
|
||||
|
||||
/* ########################## HSE/HSI Values adaptation ##################### */
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
/**
|
||||
* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
|
||||
* Timeout value
|
||||
*/
|
||||
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
|
||||
* Timeout value
|
||||
*/
|
||||
#if !defined (HSI_STARTUP_TIMEOUT)
|
||||
#define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
|
||||
#endif /* HSI_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal Low Speed oscillator (LSI) value.
|
||||
*/
|
||||
#if !defined (LSI_VALUE)
|
||||
#define LSI_VALUE ((uint32_t)40000)
|
||||
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||
The real value may vary depending on the variations
|
||||
in voltage and temperature. */
|
||||
/**
|
||||
* @brief External Low Speed oscillator (LSE) value.
|
||||
*/
|
||||
#if !defined (LSE_VALUE)
|
||||
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Time out for LSE start up value in ms.
|
||||
*/
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
|
||||
#endif /* LSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief External clock source for I2S peripheral
|
||||
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
* - External clock generated through external PLL component on EVAL 303 (based on MCO or crystal)
|
||||
* - External clock not generated on EVAL 373
|
||||
*/
|
||||
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||
#define EXTERNAL_CLOCK_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz*/
|
||||
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||
|
||||
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||
|
||||
/* ########################### System Configuration ######################### */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY ((uint32_t)(1<<__NVIC_PRIO_BITS) - 1) /*!< tick interrupt priority (lowest by default) */
|
||||
#define USE_RTOS 0
|
||||
#define PREFETCH_ENABLE 1
|
||||
#define INSTRUCTION_CACHE_ENABLE 0
|
||||
#define DATA_CACHE_ENABLE 0
|
||||
|
||||
/* ########################## Assert Selection ############################## */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/*#define USE_FULL_ASSERT 1*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_rcc.h"
|
||||
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_gpio.h"
|
||||
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_dma.h"
|
||||
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_cortex.h"
|
||||
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_adc.h"
|
||||
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CAN_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_can.h"
|
||||
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CEC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_cec.h"
|
||||
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_COMP_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_comp.h"
|
||||
#endif /* HAL_COMP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_crc.h"
|
||||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_dac.h"
|
||||
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_flash.h"
|
||||
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_sram.h"
|
||||
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NOR_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_nor.h"
|
||||
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCCARD_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_pccard.h"
|
||||
#endif /* HAL_PCCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HRTIM_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_hrtim.h"
|
||||
#endif /* HAL_HRTIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2S_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_i2s.h"
|
||||
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_irda.h"
|
||||
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_iwdg.h"
|
||||
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_OPAMP_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_opamp.h"
|
||||
#endif /* HAL_OPAMP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PWR_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_pwr.h"
|
||||
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_rtc.h"
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SDADC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_sdadc.h"
|
||||
#endif /* HAL_SDADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_smartcard.h"
|
||||
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_smbus.h"
|
||||
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_tim.h"
|
||||
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TSC_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_tsc.h"
|
||||
#endif /* HAL_TSC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_uart.h"
|
||||
#endif /* HAL_UART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_USART_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_usart.h"
|
||||
#endif /* HAL_USART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32f3xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert_failed(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __STM32F3xx_HAL_CONF_H */
|
||||
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -1,386 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F30x devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f30x.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
* Supported STM32F30x device
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 72000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*----------------------------------------------------------------------------
|
||||
* PLLMUL | 9
|
||||
*-----------------------------------------------------------------------------
|
||||
* PREDIV | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* USB Clock | ENABLE
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "stm32f30x.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
uint32_t hse_value = HSE_VALUE;
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 72000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F30x_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
initialiseMemorySections();
|
||||
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR &= 0xF87FC00C;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||
|
||||
/* Reset PREDIV1[3:0] bits */
|
||||
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||
|
||||
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
//SetSysClock(); // called from main()
|
||||
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||
#endif
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
HAL_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock */
|
||||
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||
}
|
||||
break;
|
||||
default: /* HSI used as system clock */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK clock frequency ----------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK clock frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in SystemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
|
||||
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer and set Flash Latency */
|
||||
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 1 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 2 */
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||
|
||||
if (HSE_VALUE == 12000000) {
|
||||
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL6);
|
||||
}
|
||||
else {
|
||||
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||
}
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -1,76 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f30x.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 28-March-2014
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f30x_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
#ifndef __SYSTEM_STM32F30X_H
|
||||
#define __SYSTEM_STM32F30X_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__SYSTEM_STM32F30X_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -1,41 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, 0), // PWM1 - PA4 - *TIM3_CH2
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 0), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 0), // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
};
|
|
@ -1,111 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AR32" // AiR32
|
||||
|
||||
|
||||
#define LED0_PIN PB5 // Blue LED - PB5
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PA0
|
||||
|
||||
// MPU6050 interrupts
|
||||
#define USE_EXTI
|
||||
#define USE_GYRO_EXTI
|
||||
#define GYRO_1_EXTI_PIN PA15
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
//#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_ACC
|
||||
|
||||
// MPU6050 support has been dropped according to board wiki
|
||||
// https://github.com/betaflight/betaflight/wiki/Board---AIR32
|
||||
//#define USE_GYRO_MPU6050
|
||||
//#define USE_ACC_MPU6050
|
||||
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
|
||||
#define GYRO_1_CS_PIN PB12
|
||||
#define GYRO_1_SPI_INSTANCE SPI2
|
||||
|
||||
#define GYRO_1_ALIGN CW180_DEG
|
||||
|
||||
//#define USE_BARO
|
||||
//#define USE_BARO_MS5611
|
||||
|
||||
//#define USE_MAG
|
||||
//#define USE_MAG_HMC5883
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_PIN PA4 // (HARDARE=0)
|
||||
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
#define UART2_TX_PIN PB3
|
||||
#define UART2_RX_PIN PB4
|
||||
|
||||
#define UART3_TX_PIN PB10 //(AF7)
|
||||
#define UART3_RX_PIN PB11 //(AF7)
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
#define I2C2_SCL PA9
|
||||
#define I2C2_SDA PA10
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define FLASH_CS_PIN PB12
|
||||
#define FLASH_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_ADC
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA5
|
||||
//#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
// #define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
// !!TODO - check the following line is correct
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) | TIM_N(17))
|
|
@ -1,13 +0,0 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
|
||||
FEATURES = VCP ONBOARDFLASH
|
||||
|
||||
FEATURE_CUT_LEVEL = 1
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6050.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||
drivers/barometer/barometer_ms5611.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/inverter.c
|
|
@ -1,61 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
/*
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM | TIM_USE_LED, 0, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0}, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_11, NULL, 0}, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0} // PWM14 - OUT6
|
||||
*/
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM | TIM_USE_LED, 0),
|
||||
DEF_TIM(TIM3, CH2, PA7, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // DMA1_CH2
|
||||
DEF_TIM(TIM4, CH1, PA11, TIM_USE_MOTOR, 0), // DMA1_CH1
|
||||
DEF_TIM(TIM8, CH1, PB6, TIM_USE_MOTOR, 0), // DMA2_CH3
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0), // DMA1_CH4
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, 0), // DMA2_CH5
|
||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, 0), // DMA2_CH1
|
||||
};
|
|
@ -1,99 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AIR3"
|
||||
|
||||
#define LED0_PIN PB3
|
||||
#define LED1_PIN PB4
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PA12
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_GYRO_EXTI
|
||||
#define GYRO_1_EXTI_PIN PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define GYRO_1_CS_PIN PB12
|
||||
#define GYRO_1_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_1_ALIGN CW0_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define USE_BARO
|
||||
#define USE_BARO_SPI_BMP280
|
||||
|
||||
#define BARO_SPI_INSTANCE SPI2
|
||||
#define BARO_CS_PIN PB5
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_PIN PA0 // (HARDARE=0,PPM)
|
||||
|
||||
#define SOFTSERIAL1_RX_PIN PA6 // PWM 5
|
||||
#define SOFTSERIAL1_TX_PIN PA7 // PWM 6
|
||||
|
||||
#define SOFTSERIAL2_RX_PIN PB6 // PWM 7
|
||||
#define SOFTSERIAL2_TX_PIN PB1 // PWM 8
|
||||
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
|
|
@ -1,11 +0,0 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
|
||||
FEATURE_CUT_LEVEL = 0
|
||||
|
||||
HSE_VALUE = 12000000
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c
|
|
@ -1,74 +0,0 @@
|
|||
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
|
||||
|
||||
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
|
||||
|
||||
http://www.alienflight.com
|
||||
|
||||
AlienFlight F3 Eagle files are available at:
|
||||
|
||||
https://github.com/MJ666/Flight-Controllers
|
||||
|
||||
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
|
||||
|
||||
http://www.alienflightng.com
|
||||
|
||||
This targets supports various variants of brushed and brushless flight controllers. All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users and in some cases RC vendors to build them.
|
||||
|
||||
Some variants of the AlienFlight controllers will be available for purchase from:
|
||||
|
||||
http://www.microfpv.eu
|
||||
https://micro-motor-warehouse.com
|
||||
|
||||
Here are the general hardware specifications for this boards:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
|
||||
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
|
||||
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
|
||||
- STM32F722RET6 MCU (ALIENFLIGHTNGF7)
|
||||
- MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
|
||||
- The MPU sensor interrupt is connected to the MCU for all published designs and enabled in the firmware
|
||||
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
|
||||
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
|
||||
- some new F4 boards using a 4-layer PCB for better power distribution
|
||||
- USB port, integrated
|
||||
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
|
||||
- CPPM input
|
||||
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
|
||||
- hardware bind plug for easy binding
|
||||
- motor connections are at the corners for a clean look with reduced wiring
|
||||
- small footprint
|
||||
- direct operation from a single cell LIPO battery for brushed versions
|
||||
- 3.3V LDO power regulator (older prototypes)
|
||||
- 3.3V buck-boost power converter (all new versions)
|
||||
- 5V buck-boost power converter for FPV (some versions)
|
||||
- brushless versions are designed for 4S operation and also have an 5V power output
|
||||
- battery monitoring with an LED or buzzer output (for some variants only)
|
||||
- current monitoring (F4/F7 V1.1 versions)
|
||||
- SDCard Reader for black box monitoring (F4/F7 V1.1 versions)
|
||||
- (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions)
|
||||
- hardware detection of brushed and brushless versions with individual defaults
|
||||
|
||||
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
|
||||
|
||||
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
|
||||
set spektrum_sat_bind = 5
|
||||
|
||||
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
|
||||
|
||||
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
|
||||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
|
||||
|
||||
## Flashing the firmware
|
||||
|
||||
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.
|
||||
|
||||
The firmware for the OpenSky receiver can be updated via serial pass-through and the embedded boot loader. The initial flashing need to be done with the ISP programming pins. The target for the embedded AlienFlight OpenSky receiver is "AFF4RX". Please refer to the OpenSky project for more details.
|
||||
|
||||
https://github.com/fishpepper/OpenSky/blob/master/README.md
|
|
@ -1,77 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_TARGET_CONFIG
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "pg/rx.h"
|
||||
#include "pg/motor.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
|
||||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 90;
|
||||
pidProfile->pid[PID_ROLL].I = 44;
|
||||
pidProfile->pid[PID_ROLL].D = 60;
|
||||
pidProfile->pid[PID_PITCH].P = 90;
|
||||
pidProfile->pid[PID_PITCH].I = 44;
|
||||
pidProfile->pid[PID_PITCH].D = 60;
|
||||
}
|
||||
|
||||
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
*customMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
|
||||
*customMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
|
||||
*customMotorMixerMutable(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
|
||||
*customMotorMixerMutable(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
|
||||
*customMotorMixerMutable(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
|
||||
*customMotorMixerMutable(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L
|
||||
}
|
||||
#endif
|
|
@ -1,45 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0), // PWM1 - RC1
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0), // PWM2 - RC2
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0), // PWM3 - RC3
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM, 0), // PWM4 - RC4
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM | TIM_USE_LED, 0), // PWM5 - RC5
|
||||
DEF_TIM(TIM3, CH2, PA7, TIM_USE_PWM, 0), // PWM6 - RC6
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0), // PWM7 - RC7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0), // PWM8 - RC8
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // PWM9 - OUT1
|
||||
DEF_TIM(TIM1, CH4, PA11, TIM_USE_MOTOR, 0), // PWM10 - OUT2
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0), // PWM11 - OUT3
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0), // PWM12 - OUT4
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0), // PWM13 - OUT5
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0), // PWM14 - OUT6
|
||||
};
|
|
@ -1,79 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define LED0_PIN PB3
|
||||
#define LED1_PIN PB4
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PA12
|
||||
|
||||
#define USE_EXTI
|
||||
#define MAG_INT_EXTI PC14
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
|
||||
#define GYRO_1_ALIGN CW0_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_MPU6050
|
||||
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
#define BINDPLUG_PIN PB5
|
||||
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
// IO - assuming all IOs on 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
|
@ -1,5 +0,0 @@
|
|||
F1_TARGETS += $(TARGET)
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6050.c
|
|
@ -1,74 +0,0 @@
|
|||
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
|
||||
|
||||
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
|
||||
|
||||
http://www.alienflight.com
|
||||
|
||||
AlienFlight F3 Eagle files are available at:
|
||||
|
||||
https://github.com/MJ666/Flight-Controllers
|
||||
|
||||
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
|
||||
|
||||
http://www.alienflightng.com
|
||||
|
||||
This targets supports various variants of brushed and brushless flight controllers. All published designs are flight tested by various people. The intention here is to make these flight controllers available and enable skilled users and in some cases RC vendors to build them.
|
||||
|
||||
Some variants of the AlienFlight controllers will be available for purchase from:
|
||||
|
||||
http://www.microfpv.eu
|
||||
https://micro-motor-warehouse.com
|
||||
|
||||
Here are the general hardware specifications for this boards:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
|
||||
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
|
||||
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
|
||||
- STM32F722RET6 MCU (ALIENFLIGHTNGF7)
|
||||
- MPU6050/6500/9250/ICM-20602 accelerometer/gyro(/mag) sensor unit
|
||||
- The MPU sensor interrupt is connected to the MCU for all published designs and enabled in the firmware
|
||||
- 4-8 x 4.2A to 9.5A brushed ESCs, integrated, to run the strongest micro motors (brushed variants)
|
||||
- extra-wide traces on the PCB, for maximum power throughput (brushed variants)
|
||||
- some new F4 boards using a 4-layer PCB for better power distribution
|
||||
- USB port, integrated
|
||||
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31) and SBUS
|
||||
- CPPM input
|
||||
- ground and 3.3V for the receiver, some boards have also the option to power an 5V receiver
|
||||
- hardware bind plug for easy binding
|
||||
- motor connections are at the corners for a clean look with reduced wiring
|
||||
- small footprint
|
||||
- direct operation from a single cell LIPO battery for brushed versions
|
||||
- 3.3V LDO power regulator (older prototypes)
|
||||
- 3.3V buck-boost power converter (all new versions)
|
||||
- 5V buck-boost power converter for FPV (some versions)
|
||||
- brushless versions are designed for 4S operation and also have an 5V power output
|
||||
- battery monitoring with an LED or buzzer output (for some variants only)
|
||||
- current monitoring (F4/F7 V1.1 versions)
|
||||
- SDCard Reader for black box monitoring (F4/F7 V1.1 versions)
|
||||
- (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions)
|
||||
- hardware detection of brushed and brushless versions with individual defaults
|
||||
|
||||
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
|
||||
|
||||
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
|
||||
set spektrum_sat_bind = 5
|
||||
|
||||
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
|
||||
|
||||
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.
|
||||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
|
||||
|
||||
## Flashing the firmware
|
||||
|
||||
The firmware can be updated with the BetaFlight configurator as for any other target. All AlienFlight boards have a boot jumper which need to be closed for initial flashing or for recovery from a broken firmware.
|
||||
|
||||
The firmware for the OpenSky receiver can be updated via serial pass-through and the embedded boot loader. The initial flashing need to be done with the ISP programming pins. The target for the embedded AlienFlight OpenSky receiver is "AFF4RX". Please refer to the OpenSky project for more details.
|
||||
|
||||
https://github.com/fishpepper/OpenSky/blob/master/README.md
|
|
@ -1,137 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_TARGET_CONFIG
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "pg/beeper_dev.h"
|
||||
#include "pg/gyrodev.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/motor.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
#define VBAT_SCALE 20
|
||||
|
||||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
gyroDeviceConfigMutable(0)->extiTag = selectMPUIntExtiConfigByHardwareRevision();
|
||||
|
||||
/* depending on revision ... depends on the LEDs to be utilised. */
|
||||
if (hardwareRevision == AFF3_REV_2) {
|
||||
statusLedConfigMutable()->inversion = 0
|
||||
#ifdef LED0_A_INVERTED
|
||||
| BIT(0)
|
||||
#endif
|
||||
#ifdef LED1_A_INVERTED
|
||||
| BIT(1)
|
||||
#endif
|
||||
#ifdef LED2_A_INVERTED
|
||||
| BIT(2)
|
||||
#endif
|
||||
;
|
||||
|
||||
for (int i = 0; i < STATUS_LED_NUMBER; i++) {
|
||||
statusLedConfigMutable()->ioTags[i] = IO_TAG_NONE;
|
||||
}
|
||||
#ifdef LED0_A
|
||||
statusLedConfigMutable()->ioTags[0] = IO_TAG(LED0_A);
|
||||
#endif
|
||||
#ifdef LED1_A
|
||||
statusLedConfigMutable()->ioTags[1] = IO_TAG(LED1_A);
|
||||
#endif
|
||||
#ifdef LED2_A
|
||||
statusLedConfigMutable()->ioTags[2] = IO_TAG(LED2_A);
|
||||
#endif
|
||||
} else {
|
||||
pidConfigMutable()->pid_process_denom = 4;
|
||||
}
|
||||
|
||||
if (!haveFrSkyRX) {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048;
|
||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
parseRcChannels("TAER1234", rxConfigMutable());
|
||||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
rxConfigMutable()->serialrx_inverted = true;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_RX_SERIAL;
|
||||
telemetryConfigMutable()->telemetry_inverted = false;
|
||||
featureConfigSet(FEATURE_TELEMETRY);
|
||||
beeperDevConfigMutable()->isOpenDrain = false;
|
||||
beeperDevConfigMutable()->isInverted = true;
|
||||
parseRcChannels("AETR1234", rxConfigMutable());
|
||||
}
|
||||
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 90;
|
||||
pidProfile->pid[PID_ROLL].I = 44;
|
||||
pidProfile->pid[PID_ROLL].D = 60;
|
||||
pidProfile->pid[PID_PITCH].P = 90;
|
||||
pidProfile->pid[PID_PITCH].I = 44;
|
||||
pidProfile->pid[PID_PITCH].D = 60;
|
||||
}
|
||||
|
||||
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
*customMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
|
||||
*customMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
|
||||
*customMotorMixerMutable(4) = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
|
||||
*customMotorMixerMutable(5) = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
|
||||
*customMotorMixerMutable(6) = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
|
||||
*customMotorMixerMutable(7) = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L
|
||||
}
|
||||
#endif
|
|
@ -1,78 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
uint8_t hardwareRevision = AFF3_UNKNOWN;
|
||||
bool haveFrSkyRX = true;
|
||||
|
||||
static IO_t HWDetectPin = IO_NONE;
|
||||
static IO_t RXDetectPin = IO_NONE;
|
||||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
|
||||
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||
|
||||
RXDetectPin = IOGetByTag(IO_TAG(BEEPER_PIN));
|
||||
IOInit(RXDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(RXDetectPin, IOCFG_IPU);
|
||||
|
||||
delayMicroseconds(40); // allow configuration to settle
|
||||
|
||||
// Check hardware revision
|
||||
if (IORead(HWDetectPin)) {
|
||||
hardwareRevision = AFF3_REV_1;
|
||||
} else {
|
||||
hardwareRevision = AFF3_REV_2;
|
||||
}
|
||||
|
||||
// Check for integrated OpenSky reciever
|
||||
if (IORead(RXDetectPin)) {
|
||||
haveFrSkyRX = false;
|
||||
}
|
||||
}
|
||||
|
||||
void updateHardwareRevision(void)
|
||||
{
|
||||
}
|
||||
|
||||
ioTag_t selectMPUIntExtiConfigByHardwareRevision(void)
|
||||
{
|
||||
if (hardwareRevision == AFF3_REV_1) {
|
||||
// MPU_INT output on V1 PA15
|
||||
return IO_TAG(PA15);
|
||||
} else {
|
||||
// MPU_INT output on V2 PB13
|
||||
return IO_TAG(PB13);
|
||||
}
|
||||
}
|
|
@ -1,35 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
typedef enum awf3HardwareRevision_t {
|
||||
AFF3_UNKNOWN = 0,
|
||||
AFF3_REV_1, // MPU6050 (I2C)
|
||||
AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
|
||||
} awf3HardwareRevision_e;
|
||||
|
||||
extern uint8_t hardwareRevision;
|
||||
extern bool haveFrSkyRX;
|
||||
|
||||
void updateHardwareRevision(void);
|
||||
void detectHardwareRevision(void);
|
||||
|
||||
ioTag_t selectMPUIntExtiConfigByHardwareRevision(void);
|
|
@ -1,49 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
#include "sensors/initialisation.h"
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
if (hardwareRevision == AFF3_REV_2) {
|
||||
spiPinConfigure(spiPinConfig(0));
|
||||
sensorsPreInit();
|
||||
spiPreinit();
|
||||
spiInit(SPIDEV_3);
|
||||
}
|
||||
i2cHardwareConfigure(i2cConfig(0));
|
||||
i2cInit(I2CDEV_2);
|
||||
}
|
|
@ -1,46 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
// DSHOT is working for motor 1-8
|
||||
// Motor 7 is only working if battery monitoring is disabled
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// up to 10 Motor Outputs
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR, 0), // PWM1 - PB15 - DMA1_CH6 - *TIM1_CH3N, TIM15_CH1N, TIM15_CH2
|
||||
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, 0), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR, 0), // PWM4 - PB0 - DMA2_CH5 - TIM3_CH3, TIM1_CH2N, *TIM8_CH2N
|
||||
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MOTOR, 0), // PWM5 - PA6 - DMA1_CH3 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0), // PWM6 - PA2 - DMA1_CH1 - *TIM2_CH3, !TIM15_CH1
|
||||
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR, 0), // PWM7 - PB1 - DMA2_CH1 - TIM3_CH4, TIM1_CH3N, *TIM8_CH3N
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR | TIM_USE_LED, 0), // PWM8 - PA7 - DMA1_CH7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, 0), // PWM9 - PA4 - DMA_NONE - *TIM3_CH2
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0), // PWM10 - PA1 - DMA1_CH7 - *TIM2_CH2, TIM15_CH1N
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0), // PPM - PA3 - DMA1_CH7 - TIM2_CH4, TIM15_CH2
|
||||
};
|
|
@ -1,127 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
||||
#define USE_TARGET_CONFIG
|
||||
#define TARGET_BUS_INIT
|
||||
#define REMAP_TIM17_DMA
|
||||
|
||||
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
#define HW_PIN PB2
|
||||
|
||||
// LED's V1
|
||||
#define LED0_PIN PB4
|
||||
#define LED1_PIN PB5
|
||||
|
||||
// LED's V2
|
||||
#define LED0_A PB8
|
||||
#define LED1_A PB9
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PA5
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
// Using MPU6050 for the moment.
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
|
||||
#define GYRO_1_ALIGN CW270_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_MPU6050
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
|
||||
// No baro support.
|
||||
//#define USE_BARO
|
||||
//#define USE_BARO_MS5611
|
||||
|
||||
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
|
||||
#define USE_MAG
|
||||
#define USE_MAG_AK8963
|
||||
#define MAG_AK8963_ALIGN CW180_DEG_FLIP
|
||||
|
||||
#define USE_VCP
|
||||
#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 USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
#define AVOID_UART2_FOR_PWM_PPM
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_PIN PB15 // (HARDARE=0)
|
||||
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_PULLUP
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
#define I2C2_SCL PA9
|
||||
#define I2C2_SDA PA10
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define GYRO_1_CS_PIN SPI3_NSS_PIN
|
||||
#define GYRO_1_SPI_INSTANCE SPI3
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define VBAT_SCALE_DEFAULT 20
|
||||
|
||||
#define BINDPLUG_PIN PB12
|
||||
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
|
@ -1,12 +0,0 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
|
||||
FEATURES = VCP
|
||||
|
||||
FEATURE_CUT_LEVEL = 0
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6050.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/compass/compass_ak8963.c
|
|
@ -1 +0,0 @@
|
|||
# BEEBRAIN_V2D is a variant of BEEBRAIN_V2F with DSM receiver
|
|
@ -1 +0,0 @@
|
|||
# BEESTORM is a variant of BEEBRAIN_V2F without built-in vtx.
|
|
@ -1,182 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_TARGET_CONFIG
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "pg/vcd.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/motor.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#if !defined(BEEBRAIN_V2D)
|
||||
#define BBV2_FRSKY_RSSI_CH_IDX 9
|
||||
#endif
|
||||
|
||||
#ifdef BRUSHED_MOTORS_PWM_RATE
|
||||
#undef BRUSHED_MOTORS_PWM_RATE
|
||||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1030;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
||||
for (uint8_t pidProfileIndex = 0; pidProfileIndex < PID_PROFILE_COUNT; pidProfileIndex++) {
|
||||
pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex);
|
||||
|
||||
pidProfile->pid[PID_ROLL].P = 86;
|
||||
pidProfile->pid[PID_ROLL].I = 50;
|
||||
pidProfile->pid[PID_ROLL].D = 60;
|
||||
pidProfile->pid[PID_PITCH].P = 90;
|
||||
pidProfile->pid[PID_PITCH].I = 55;
|
||||
pidProfile->pid[PID_PITCH].D = 60;
|
||||
pidProfile->pid[PID_YAW].P = 123;
|
||||
pidProfile->pid[PID_YAW].I = 75;
|
||||
}
|
||||
|
||||
for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
|
||||
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
|
||||
|
||||
controlRateConfig->rcRates[FD_YAW] = 120;
|
||||
controlRateConfig->rcExpo[FD_ROLL] = 15;
|
||||
controlRateConfig->rcExpo[FD_PITCH] = 15;
|
||||
controlRateConfig->rcExpo[FD_YAW] = 15;
|
||||
controlRateConfig->rates[FD_ROLL] = 85;
|
||||
controlRateConfig->rates[FD_PITCH] = 85;
|
||||
}
|
||||
|
||||
batteryConfigMutable()->batteryCapacity = 250;
|
||||
batteryConfigMutable()->vbatmincellvoltage = 280;
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = 330;
|
||||
|
||||
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
*customMotorMixerMutable(2) = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
|
||||
*customMotorMixerMutable(3) = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
|
||||
|
||||
vcdProfileMutable()->video_system = VIDEO_SYSTEM_NTSC;
|
||||
#if defined(BEESTORM)
|
||||
strcpy(pilotConfigMutable()->name, "BeeStorm");
|
||||
#else
|
||||
strcpy(pilotConfigMutable()->name, "BeeBrain V2");
|
||||
#endif
|
||||
osdConfigMutable()->cap_alarm = 250;
|
||||
osdElementConfigMutable()->item_pos[OSD_CRAFT_NAME] = OSD_POS(9, 11) | OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(23, 10) | OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(2, 10) | OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_FLYMODE] = OSD_POS(17, 10) | OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_VTX_CHANNEL] = OSD_POS(10, 10) | OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_RSSI_VALUE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ITEM_TIMER_1] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_THROTTLE_POS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_CROSSHAIRS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_HORIZON_SIDEBARS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ARTIFICIAL_HORIZON] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_CURRENT_DRAW] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_MAH_DRAWN] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_GPS_SPEED] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_GPS_LON] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_GPS_LAT] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_GPS_SATS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_HOME_DIR] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_HOME_DIST] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_COMPASS_BAR] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ALTITUDE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ROLL_PIDS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_PITCH_PIDS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_YAW_PIDS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_DEBUG] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_POWER] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_PIDRATE_PROFILE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_WARNINGS] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_AVG_CELL_VOLTAGE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_PITCH_ANGLE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ROLL_ANGLE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_MAIN_BATT_USAGE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_DISARMED] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_NUMERICAL_HEADING] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_NUMERICAL_VARIO] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ESC_TMP] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_ESC_RPM] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_G_FORCE] &= ~OSD_PROFILE_1_FLAG;
|
||||
osdElementConfigMutable()->item_pos[OSD_FLIP_ARROW] &= ~OSD_PROFILE_1_FLAG;
|
||||
|
||||
modeActivationConditionsMutable(0)->modeId = BOXANGLE;
|
||||
modeActivationConditionsMutable(0)->auxChannelIndex = AUX2 - NON_AUX_CHANNEL_COUNT;
|
||||
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(900);
|
||||
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
||||
|
||||
analyzeModeActivationConditions();
|
||||
|
||||
#if defined(BEEBRAIN_V2D)
|
||||
// DSM version
|
||||
for (uint8_t rxRangeIndex = 0; rxRangeIndex < NON_AUX_CHANNEL_COUNT; rxRangeIndex++) {
|
||||
rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigsMutable(rxRangeIndex);
|
||||
|
||||
channelRangeConfig->min = 1160;
|
||||
channelRangeConfig->max = 1840;
|
||||
}
|
||||
#else
|
||||
// Frsky version
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_RX_SERIAL;
|
||||
rxConfigMutable()->rssi_channel = BBV2_FRSKY_RSSI_CH_IDX;
|
||||
rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigsMutable(BBV2_FRSKY_RSSI_CH_IDX - 1);
|
||||
channelFailsafeConfig->mode = RX_FAILSAFE_MODE_SET;
|
||||
channelFailsafeConfig->step = CHANNEL_VALUE_TO_RXFAIL_STEP(1000);
|
||||
osdElementConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(2, 11) | OSD_PROFILE_1_FLAG;
|
||||
#endif
|
||||
}
|
||||
#endif
|
|
@ -1,36 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR, 0), // PWM1 - PB15 - DMA1_CH6 - *TIM1_CH3N, TIM15_CH1N, TIM15_CH2
|
||||
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, 0), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR, 0), // PWM4 - PB0 - DMA2_CH5 - TIM3_CH3, TIM1_CH2N, *TIM8_CH2N
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_TRANSPONDER | TIM_USE_LED, 0),
|
||||
};
|
|
@ -1,130 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#if defined(BEESTORM)
|
||||
#define TARGET_BOARD_IDENTIFIER "BEST" // Oversky BeeStorm
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "BBV2" // BeeBrain V2.
|
||||
#endif
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
|
||||
#define LED0_PIN PB1
|
||||
#define LED1_PIN PB2
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_GYRO_EXTI
|
||||
#define GYRO_1_EXTI_PIN PB6
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#if defined(BEESTORM)
|
||||
#define GYRO_1_ALIGN CW180_DEG
|
||||
#else
|
||||
#define GYRO_1_ALIGN CW270_DEG
|
||||
#endif
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
|
||||
#define USE_MSP_UART
|
||||
|
||||
#define AVOID_UART2_FOR_PWM_PPM
|
||||
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define GYRO_1_CS_PIN PA15
|
||||
#define GYRO_1_SPI_INSTANCE SPI3
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI1
|
||||
#define MAX7456_SPI_CS_PIN PA4
|
||||
|
||||
#if !defined(BEESTORM)
|
||||
#define USE_VTX_RTC6705
|
||||
#define USE_VTX_RTC6705_SOFTSPI
|
||||
#define USE_VTX_CONTROL
|
||||
#define RTC6705_SPI_MOSI_PIN PC15
|
||||
#define RTC6705_SPICLK_PIN PC13
|
||||
#define RTC6705_CS_PIN PB12
|
||||
#endif
|
||||
|
||||
#define USE_ADC
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_NONE
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define VBAT_ADC_PIN PB13
|
||||
|
||||
#define USE_TRANSPONDER
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#if !defined(BEESTORM)
|
||||
#define RX_CHANNELS_TAER
|
||||
#endif
|
||||
|
||||
#if defined(BEEBRAIN_V2D)
|
||||
// Receiver - DSM
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_MOTOR_STOP | FEATURE_OSD)
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#else
|
||||
// Receiver - Frsky
|
||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_MOTOR_STOP | FEATURE_OSD | FEATURE_TELEMETRY)
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#endif
|
||||
|
||||
// IO - stm32f303cc in 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 5
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(8) | TIM_N(15) | TIM_N(16) )
|
|
@ -1,15 +0,0 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
|
||||
FEATURES = VCP
|
||||
|
||||
FEATURE_CUT_LEVEL = 1
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/max7456.c
|
||||
|
||||
ifneq ($(TARGET), BEESTORM)
|
||||
TARGET_SRC += drivers/vtx_rtc6705_soft_spi.c
|
||||
endif
|
|
@ -1,13 +0,0 @@
|
|||
==BETAFLIGHTF3==
|
||||
|
||||
Owner: BorisB
|
||||
|
||||
Board information:
|
||||
|
||||
- CPU - STM32F303CCT6
|
||||
- MPU-6000
|
||||
- SD Card Slot
|
||||
- Build in 5V BEC + LC filter - board can be powered from main battery
|
||||
- Built in current meter, PDB
|
||||
|
||||
More info to come
|
|
@ -1,50 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
//Target code By BorisB and Hector "Hectech FPV" Hind
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0), // PPM DMA(1,4)
|
||||
|
||||
// Motors 1-4
|
||||
DEF_TIM(TIM16, CH1, PA6, TIM_USE_MOTOR, 0), // PWM1 UP(1,6)
|
||||
DEF_TIM(TIM8, CH1N, PA7, TIM_USE_MOTOR, 0), // PWM2 UP(2,1)
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, 0), // PWM3 UP(2,1)
|
||||
DEF_TIM(TIM17, CH1, PB9, TIM_USE_MOTOR, 0), // PWM4 UP(1,7)
|
||||
|
||||
// Motors 5-6 or SoftSerial
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0), // PWM5 UP(1,3)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0), // PWM6 UP(1,3)
|
||||
|
||||
// Motors 7-8 or UART2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0), // PWM7/UART2_RX
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0), // PWM8/UART2_TX
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_LED, 0), // LED DMA(1,2)
|
||||
};
|
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