mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 16:25:26 +03:00
Initial cut on timer mapping cleanup; refactor time code to align more with BF; Mixer refactoring (in progress)
This commit is contained in:
parent
29df2b4f0f
commit
e4f31fbe62
68 changed files with 1006 additions and 2451 deletions
1
Makefile
1
Makefile
|
@ -653,7 +653,6 @@ STM32F30x_COMMON_SRC = \
|
|||
drivers/bus_i2c_stm32f30x.c \
|
||||
drivers/dma.c \
|
||||
drivers/gpio_stm32f30x.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_uart_stm32f30x.c \
|
||||
drivers/system_stm32f30x.c \
|
||||
drivers/timer_stm32f30x.c
|
||||
|
|
|
@ -64,9 +64,11 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER)
|
|||
#endif
|
||||
|
||||
|
||||
void dmaInit(void)
|
||||
void dmaInit(dmaHandlerIdentifier_e identifier, resourceOwner_t owner, uint8_t resourceIndex)
|
||||
{
|
||||
// TODO: Do we need this?
|
||||
RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
||||
dmaDescriptors[identifier].owner = owner;
|
||||
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Channel_TypeDef* channel)
|
||||
|
@ -74,7 +76,7 @@ dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Channel_TypeDef* channel)
|
|||
dmaHandlerIdentifier_e i;
|
||||
|
||||
for (i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
|
||||
if (channel == dmaDescriptors[i].channel) {
|
||||
if (channel == dmaDescriptors[i].ref) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -15,10 +15,27 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "resource.h"
|
||||
|
||||
struct dmaChannelDescriptor_s;
|
||||
typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor);
|
||||
|
||||
typedef struct dmaChannelDescriptor_s {
|
||||
DMA_TypeDef* dma;
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
DMA_Stream_TypeDef* ref;
|
||||
#else
|
||||
DMA_Channel_TypeDef* ref;
|
||||
#endif
|
||||
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
||||
uint8_t flagsShift;
|
||||
IRQn_Type irqN;
|
||||
uint32_t rcc;
|
||||
uint32_t userParam;
|
||||
resourceOwner_t owner;
|
||||
uint8_t resourceIndex;
|
||||
} dmaChannelDescriptor_t;
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
|
||||
typedef enum {
|
||||
|
@ -40,17 +57,7 @@ typedef enum {
|
|||
DMA2_ST7_HANDLER,
|
||||
} dmaHandlerIdentifier_e;
|
||||
|
||||
typedef struct dmaChannelDescriptor_s {
|
||||
DMA_TypeDef* dma;
|
||||
DMA_Stream_TypeDef* stream;
|
||||
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
||||
uint8_t flagsShift;
|
||||
IRQn_Type irqN;
|
||||
uint32_t rcc;
|
||||
uint32_t userParam;
|
||||
} dmaChannelDescriptor_t;
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
||||
#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .ref = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
||||
if (dmaDescriptors[i].irqHandlerCallback)\
|
||||
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
||||
|
@ -83,17 +90,7 @@ typedef enum {
|
|||
DMA2_CH5_HANDLER,
|
||||
} dmaHandlerIdentifier_e;
|
||||
|
||||
typedef struct dmaChannelDescriptor_s {
|
||||
DMA_TypeDef* dma;
|
||||
DMA_Channel_TypeDef* channel;
|
||||
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
||||
uint8_t flagsShift;
|
||||
IRQn_Type irqN;
|
||||
uint32_t rcc;
|
||||
uint32_t userParam;
|
||||
} dmaChannelDescriptor_t;
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
||||
#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .ref = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||
if (dmaDescriptors[i].irqHandlerCallback)\
|
||||
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
||||
|
@ -119,7 +116,7 @@ dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Stream_TypeDef* stream);
|
|||
dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Channel_TypeDef* channel);
|
||||
#endif
|
||||
|
||||
void dmaInit(void);
|
||||
void dmaInit(dmaHandlerIdentifier_e identifier, resourceOwner_t owner, uint8_t resourceIndex);
|
||||
void dmaEnableClock(dmaHandlerIdentifier_e identifier);
|
||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam);
|
||||
|
||||
|
|
|
@ -67,9 +67,11 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
|
|||
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
||||
|
||||
void dmaInit(void)
|
||||
void dmaInit(dmaHandlerIdentifier_e identifier, resourceOwner_t owner, uint8_t resourceIndex)
|
||||
{
|
||||
// TODO: Do we need this?
|
||||
RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
||||
dmaDescriptors[identifier].owner = owner;
|
||||
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Stream_TypeDef* stream)
|
||||
|
@ -77,7 +79,7 @@ dmaHandlerIdentifier_e dmaFindHandlerIdentifier(DMA_Stream_TypeDef* stream)
|
|||
dmaHandlerIdentifier_e i;
|
||||
|
||||
for (i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
|
||||
if (stream == dmaDescriptors[i].stream) {
|
||||
if (stream == dmaDescriptors[i].ref) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -68,10 +68,22 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
|
|||
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
||||
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
||||
|
||||
|
||||
void dmaInit(void)
|
||||
static void enableDmaClock(uint32_t rcc)
|
||||
{
|
||||
// TODO: Do we need this?
|
||||
do {
|
||||
__IO uint32_t tmpreg;
|
||||
SET_BIT(RCC->AHB1ENR, rcc);
|
||||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmpreg = READ_BIT(RCC->AHB1ENR, rcc);
|
||||
UNUSED(tmpreg);
|
||||
} while(0);
|
||||
}
|
||||
|
||||
void dmaInit(dmaHandlerIdentifier_e identifier, resourceOwner_t owner, uint8_t resourceIndex)
|
||||
{
|
||||
enableDmaClock(dmaDescriptors[identifier].rcc);
|
||||
dmaDescriptors[identifier].owner = owner;
|
||||
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
#include "common/color.h"
|
||||
#include "common/colorconversion.h"
|
||||
#include "dma.h"
|
||||
#include "drivers/io.h"
|
||||
#include "light_ws2811strip.h"
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
|
@ -46,6 +47,9 @@ uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
|||
#endif
|
||||
volatile uint8_t ws2811LedDataTransferInProgress = 0;
|
||||
|
||||
uint16_t BIT_COMPARE_1 = 0;
|
||||
uint16_t BIT_COMPARE_0 = 0;
|
||||
|
||||
static hsvColor_t ledColorBuffer[WS2811_LED_STRIP_LENGTH];
|
||||
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color)
|
||||
|
|
|
@ -25,19 +25,10 @@
|
|||
|
||||
#define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH) // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes)
|
||||
|
||||
#if defined(STM32F40_41xxx)
|
||||
#define BIT_COMPARE_1 67 // timer compare value for logical 1
|
||||
#define BIT_COMPARE_0 33 // timer compare value for logical 0
|
||||
#elif defined(STM32F7)
|
||||
#define BIT_COMPARE_1 76 // timer compare value for logical 1
|
||||
#define BIT_COMPARE_0 38 // timer compare value for logical 0
|
||||
#else
|
||||
#define BIT_COMPARE_1 17 // timer compare value for logical 1
|
||||
#define BIT_COMPARE_0 9 // timer compare value for logical 0
|
||||
#endif
|
||||
#define WS2811_TIMER_MHZ 24
|
||||
#define WS2811_CARRIER_HZ 800000
|
||||
|
||||
void ws2811LedStripInit(void);
|
||||
|
||||
void ws2811LedStripHardwareInit(void);
|
||||
void ws2811LedStripDMAEnable(void);
|
||||
|
||||
|
@ -60,3 +51,6 @@ extern uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
|||
extern uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#endif
|
||||
extern volatile uint8_t ws2811LedDataTransferInProgress;
|
||||
|
||||
extern uint16_t BIT_COMPARE_1;
|
||||
extern uint16_t BIT_COMPARE_0;
|
185
src/main/drivers/light_ws2811strip_stdperiph.c
Executable file
185
src/main/drivers/light_ws2811strip_stdperiph.c
Executable file
|
@ -0,0 +1,185 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "dma.h"
|
||||
#include "drivers/system.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
#if !defined(WS2811_PIN)
|
||||
#if defined(STM32F4)
|
||||
#define WS2811_PIN PA0
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA1_Stream2
|
||||
#define WS2811_DMA_CHANNEL DMA_Channel_6
|
||||
#elif defined(STM32F3) || defined(STM32F1)
|
||||
#define WS2811_PIN PB8 // TIM16_CH1
|
||||
#define WS2811_DMA_STREAM DMA1_Channel3
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
bool ws2811Initialised = false;
|
||||
#if defined(STM32F4)
|
||||
static DMA_Stream_TypeDef *dmaRef = NULL;
|
||||
#elif defined(STM32F3) || defined(STM32F1)
|
||||
static DMA_Channel_TypeDef *dmaRef = NULL;
|
||||
#else
|
||||
#error "No MCU definition in light_ws2811strip_stdperiph.c"
|
||||
#endif
|
||||
static TIM_TypeDef *timer = NULL;
|
||||
|
||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(descriptor->ref, DISABLE);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}
|
||||
|
||||
void ws2811LedStripHardwareInit(void)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
const timerHardware_t *timerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
return;
|
||||
}
|
||||
|
||||
timer = timerHardware->tim;
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 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);
|
||||
|
||||
// Stop timer
|
||||
TIM_Cmd(timer, DISABLE);
|
||||
|
||||
/* Compute the prescaler value */
|
||||
uint16_t prescaler = timerGetPrescalerByDesiredMhz(timer, WS2811_TIMER_MHZ);
|
||||
uint16_t period = timerGetPeriodByPrescaler(timer, prescaler, WS2811_CARRIER_HZ);
|
||||
|
||||
BIT_COMPARE_1 = period / 3 * 2;
|
||||
BIT_COMPARE_0 = period / 3;
|
||||
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = period; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescaler;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration */
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||
} else {
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||
}
|
||||
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
|
||||
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
|
||||
timerOCPreloadConfig(timer, timerHardware->channel, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||
TIM_ARRPreloadConfig(timer, ENABLE);
|
||||
|
||||
TIM_CCxCmd(timer, timerHardware->channel, TIM_CCx_Enable);
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
|
||||
// dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
|
||||
// dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
//dmaRef = timerHardware->dmaRef;
|
||||
dmaRef = WS2811_DMA_STREAM;
|
||||
dmaInit(WS2811_DMA_HANDLER_IDENTIFER, OWNER_LED_STRIP, 0);
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
DMA_DeInit(dmaRef);
|
||||
|
||||
/* configure DMA */
|
||||
DMA_Cmd(dmaRef, DISABLE);
|
||||
DMA_DeInit(dmaRef);
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
|
||||
#if defined(STM32F4)
|
||||
DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL; //timerHardware->dmaChannel;
|
||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
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
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
|
||||
DMA_Init(dmaRef, &DMA_InitStructure);
|
||||
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
||||
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
|
||||
ws2811Initialised = true;
|
||||
}
|
||||
|
||||
void ws2811LedStripDMAEnable(void)
|
||||
{
|
||||
if (!ws2811Initialised)
|
||||
return;
|
||||
|
||||
DMA_SetCurrDataCounter(dmaRef, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(timer, 0);
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
DMA_Cmd(dmaRef, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,126 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "common/color.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/io.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
bool ws2811Initialised = false;
|
||||
|
||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(descriptor->channel, DISABLE);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}
|
||||
|
||||
void ws2811LedStripHardwareInit(void)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
|
||||
|
||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
||||
|
||||
/* Compute the prescaler value */
|
||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration: Channel1 */
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
||||
TIM_OC1Init(TIM3, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_CtrlPWMOutputs(TIM3, ENABLE);
|
||||
|
||||
/* configure DMA */
|
||||
/* DMA clock enable */
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
|
||||
/* DMA1 Channel6 Config */
|
||||
DMA_DeInit(DMA1_Channel6);
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
|
||||
DMA_Init(DMA1_Channel6, &DMA_InitStructure);
|
||||
|
||||
/* TIM3 CC1 DMA Request enable */
|
||||
TIM_DMACmd(TIM3, TIM_DMA_CC1, ENABLE);
|
||||
|
||||
DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE);
|
||||
|
||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
||||
ws2811Initialised = true;
|
||||
setStripColor(&hsv_white);
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
void ws2811LedStripDMAEnable(void)
|
||||
{
|
||||
if (!ws2811Initialised)
|
||||
return;
|
||||
|
||||
DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(TIM3, 0);
|
||||
TIM_Cmd(TIM3, ENABLE);
|
||||
DMA_Cmd(DMA1_Channel6, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,131 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
#ifndef WS2811_PIN
|
||||
#define WS2811_PIN PB8 // TIM16_CH1
|
||||
#define WS2811_TIMER TIM16
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
||||
#endif
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
bool ws2811Initialised = false;
|
||||
|
||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(descriptor->channel, DISABLE);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}
|
||||
|
||||
void ws2811LedStripHardwareInit(void)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
||||
|
||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
||||
|
||||
/* Compute the prescaler value */
|
||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration */
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
||||
TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
|
||||
|
||||
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
|
||||
|
||||
/* configure DMA */
|
||||
/* DMA1 Channel Config */
|
||||
DMA_DeInit(WS2811_DMA_CHANNEL);
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
|
||||
DMA_Init(WS2811_DMA_CHANNEL, &DMA_InitStructure);
|
||||
|
||||
TIM_DMACmd(WS2811_TIMER, TIM_DMA_CC1, ENABLE);
|
||||
|
||||
DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE);
|
||||
|
||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
||||
ws2811Initialised = true;
|
||||
setStripColor(&hsv_white);
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
void ws2811LedStripDMAEnable(void)
|
||||
{
|
||||
if (!ws2811Initialised)
|
||||
return;
|
||||
|
||||
DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(WS2811_TIMER, 0);
|
||||
TIM_Cmd(WS2811_TIMER, ENABLE);
|
||||
DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,174 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef LED_STRIP
|
||||
|
||||
#include "common/color.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "dma.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
#if !defined(WS2811_PIN)
|
||||
#define WS2811_PIN PA0
|
||||
#define WS2811_TIMER TIM5
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA1_Stream2
|
||||
#define WS2811_DMA_IT DMA_IT_TCIF2
|
||||
#define WS2811_DMA_CHANNEL DMA_Channel_6
|
||||
#define WS2811_TIMER_CHANNEL TIM_Channel_1
|
||||
#endif
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
static uint16_t timDMASource = 0;
|
||||
bool ws2811Initialised = false;
|
||||
|
||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(descriptor->stream, DISABLE);
|
||||
TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}
|
||||
|
||||
void ws2811LedStripHardwareInit(void)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER));
|
||||
|
||||
// Stop timer
|
||||
TIM_Cmd(WS2811_TIMER, DISABLE);
|
||||
|
||||
/* Compute the prescaler value */
|
||||
prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1;
|
||||
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration: Channel1 */
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
|
||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
|
||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High;
|
||||
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
|
||||
uint32_t channelAddress = 0;
|
||||
switch (WS2811_TIMER_CHANNEL) {
|
||||
case TIM_Channel_1:
|
||||
TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
timDMASource = TIM_DMA_CC1;
|
||||
channelAddress = (uint32_t)(&WS2811_TIMER->CCR1);
|
||||
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
timDMASource = TIM_DMA_CC2;
|
||||
channelAddress = (uint32_t)(&WS2811_TIMER->CCR2);
|
||||
TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
timDMASource = TIM_DMA_CC3;
|
||||
channelAddress = (uint32_t)(&WS2811_TIMER->CCR3);
|
||||
TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
timDMASource = TIM_DMA_CC4;
|
||||
channelAddress = (uint32_t)(&WS2811_TIMER->CCR4);
|
||||
TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
break;
|
||||
}
|
||||
|
||||
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
|
||||
TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE);
|
||||
|
||||
TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable);
|
||||
TIM_Cmd(WS2811_TIMER, ENABLE);
|
||||
|
||||
/* configure DMA */
|
||||
DMA_Cmd(WS2811_DMA_STREAM, DISABLE);
|
||||
DMA_DeInit(WS2811_DMA_STREAM);
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL;
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = channelAddress;
|
||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
|
||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
|
||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||
|
||||
DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure);
|
||||
|
||||
DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE);
|
||||
DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT);
|
||||
|
||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||
|
||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
||||
ws2811Initialised = true;
|
||||
setStripColor(&hsv_white);
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
void ws2811LedStripDMAEnable(void)
|
||||
{
|
||||
if (!ws2811Initialised)
|
||||
return;
|
||||
|
||||
DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(WS2811_TIMER, 0);
|
||||
DMA_Cmd(WS2811_DMA_STREAM, ENABLE);
|
||||
TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -32,46 +32,12 @@
|
|||
#include "pwm_rx.h"
|
||||
#include "pwm_mapping.h"
|
||||
|
||||
|
||||
/*
|
||||
Configuration maps
|
||||
|
||||
Note: this documentation is only valid for STM32F10x, for STM32F30x please read the code itself.
|
||||
|
||||
1) multirotor PPM input
|
||||
PWM1 used for PPM
|
||||
PWM5..8 used for motors
|
||||
PWM9..10 used for servo or else motors
|
||||
PWM11..14 used for motors
|
||||
|
||||
2) multirotor PPM input with more servos
|
||||
PWM1 used for PPM
|
||||
PWM5..8 used for motors
|
||||
PWM9..10 used for servo or else motors
|
||||
PWM11..14 used for servos
|
||||
|
||||
2) multirotor PWM input
|
||||
PWM1..8 used for input
|
||||
PWM9..10 used for servo or else motors
|
||||
PWM11..14 used for motors
|
||||
|
||||
3) airplane / flying wing w/PWM
|
||||
PWM1..8 used for input
|
||||
PWM9 used for motor throttle +PWM10 for 2nd motor
|
||||
PWM11.14 used for servos
|
||||
|
||||
4) airplane / flying wing with PPM
|
||||
PWM1 used for PPM
|
||||
PWM5..8 used for servos
|
||||
PWM9 used for motor throttle +PWM10 for 2nd motor
|
||||
PWM11.14 used for servos
|
||||
*/
|
||||
|
||||
const uint16_t * const hardwareMaps[] = {
|
||||
multiPWM,
|
||||
multiPPM,
|
||||
airPWM,
|
||||
airPPM,
|
||||
enum {
|
||||
MAP_TO_NONE,
|
||||
MAP_TO_PPM_INPUT,
|
||||
MAP_TO_PWM_INPUT,
|
||||
MAP_TO_MOTOR_OUTPUT,
|
||||
MAP_TO_SERVO_OUTPUT,
|
||||
};
|
||||
|
||||
static pwmIOConfiguration_t pwmIOConfiguration;
|
||||
|
@ -93,31 +59,20 @@ bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
|
|||
|
||||
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||
{
|
||||
memset(&pwmIOConfiguration, 0, sizeof(pwmIOConfiguration));
|
||||
|
||||
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||
int channelIndex = 0;
|
||||
#endif
|
||||
|
||||
memset(&pwmIOConfiguration, 0, sizeof(pwmIOConfiguration));
|
||||
|
||||
// this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ]
|
||||
int i = 0;
|
||||
if (init->airplane)
|
||||
i = 2; // switch to air hardware config
|
||||
if (init->usePPM || init->useSerialRx)
|
||||
i++; // next index is for PPM
|
||||
|
||||
const uint16_t *setup = hardwareMaps[i];
|
||||
|
||||
for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT && setup[i] != 0xFFFF; i++) {
|
||||
uint8_t timerIndex = setup[i] & 0x00FF;
|
||||
uint8_t type = (setup[i] & 0xFF00) >> 8;
|
||||
|
||||
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
|
||||
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
|
||||
int type = MAP_TO_NONE;
|
||||
|
||||
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
|
||||
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
|
||||
if (timerIndex == PWM2) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
@ -125,7 +80,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
#ifdef STM32F10X
|
||||
// skip UART2 ports
|
||||
if (init->useUART2 && (timerHardwarePtr->tag == IO_TAG(PA2) || timerHardwarePtr->tag == IO_TAG(PA3))) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
@ -133,27 +88,27 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
#if defined(STM32F303xC) && defined(USE_UART3)
|
||||
// skip UART3 ports (PB10/PB11)
|
||||
if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN))) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(UART6_TX_PIN) || defined(UART6_RX_PIN)
|
||||
if (init->useUART6 && (timerHardwarePtr->tag == IO_TAG(UART6_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART6_RX_PIN))) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SOFTSERIAL_1_TIMER
|
||||
if (init->useSoftSerial && timerHardwarePtr->tim == SOFTSERIAL_1_TIMER) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#ifdef SOFTSERIAL_2_TIMER
|
||||
if (init->useSoftSerial && timerHardwarePtr->tim == SOFTSERIAL_2_TIMER) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
@ -162,12 +117,12 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
// skip LED Strip output
|
||||
if (init->useLEDStrip) {
|
||||
if (timerHardwarePtr->tim == WS2811_TIMER) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#if defined(STM32F303xC) && defined(WS2811_PIN)
|
||||
if (timerHardwarePtr->tag == IO_TAG(WS2811_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
@ -177,21 +132,21 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
#ifdef VBAT_ADC_PIN
|
||||
if (init->useVbat && timerHardwarePtr->tag == IO_TAG(VBAT_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef RSSI_ADC_PIN
|
||||
if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CURRENT_METER_ADC_PIN
|
||||
if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
@ -202,26 +157,51 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
timerHardwarePtr->tag == init->sonarIOConfig.triggerTag ||
|
||||
timerHardwarePtr->tag == init->sonarIOConfig.echoTag
|
||||
)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
// hacks to allow current functionality
|
||||
if (type == MAP_TO_PWM_INPUT && !init->useParallelPWM)
|
||||
continue;
|
||||
// Handle timer mapping to PWM/PPM inputs
|
||||
if (init->useSerialRx) {
|
||||
type = MAP_TO_NONE;
|
||||
}
|
||||
else if (init->useParallelPWM && (timerHardwarePtr->usageFlags & TIM_USE_PWM)) {
|
||||
type = MAP_TO_PWM_INPUT;
|
||||
}
|
||||
else if (init->usePPM && (timerHardwarePtr->usageFlags & TIM_USE_PPM)) {
|
||||
type = MAP_TO_PPM_INPUT;
|
||||
}
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT && !init->usePPM)
|
||||
continue;
|
||||
// Handle outputs - may override the PWM/PPM inputs
|
||||
if (init->flyingPlatformType == PLATFORM_MULTIROTOR) {
|
||||
// Multicopter
|
||||
if (init->useServoOutputs && (timerHardwarePtr->usageFlags & TIM_USE_MC_SERVO)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else if (init->useChannelForwarding && (timerHardwarePtr->usageFlags & TIM_USE_MC_CHNFW)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
else if (init->flyingPlatformType == PLATFORM_AIRPLANE || init->flyingPlatformType == PLATFORM_HELICOPTER) {
|
||||
// Fixed wing or HELI (one/two motors and a lot of servos
|
||||
if (timerHardwarePtr->usageFlags & TIM_USE_FW_SERVO) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else if (timerHardwarePtr->usageFlags & TIM_USE_FW_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
|
||||
// If timer not mapped - skip
|
||||
if (type == MAP_TO_NONE)
|
||||
continue;
|
||||
/*
|
||||
#ifdef USE_SERVOS
|
||||
if (init->useServos && !init->airplane) {
|
||||
#if defined(NAZE)
|
||||
// remap PWM9+10 as servos
|
||||
if ((timerIndex == PWM9 || timerIndex == PWM10) && timerHardwarePtr->tim == TIM1)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(DOGE)
|
||||
// remap outputs 1+2 (PWM2+3) as servos
|
||||
if ((timerIndex == PWM2 || timerIndex == PWM3) && timerHardwarePtr->tim == TIM4)
|
||||
|
@ -234,24 +214,12 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(CC3D)
|
||||
// remap PWM9+10 as servos
|
||||
if ((timerIndex == PWM9 || timerIndex == PWM10) && timerHardwarePtr->tim == TIM1)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SPARKY)
|
||||
// remap PWM1+2 as servos
|
||||
if ((timerIndex == PWM1 || timerIndex == PWM2) && timerHardwarePtr->tim == TIM15)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3)
|
||||
// remap PWM15+16 as servos
|
||||
if ((timerIndex == PWM15 || timerIndex == PWM16) && timerHardwarePtr->tim == TIM15)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3MINI)
|
||||
// remap PWM6+7 as servos
|
||||
if ((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15)
|
||||
|
@ -283,17 +251,6 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3))
|
||||
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
|
||||
if (init->useSoftSerial) {
|
||||
if (timerIndex == PWM5 || timerIndex == PWM6)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
} else {
|
||||
if (timerIndex == PWM9 || timerIndex == PWM10)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(MOTOLAB)
|
||||
// remap PWM 7+8 as servos
|
||||
if (timerIndex == PWM7 || timerIndex == PWM8)
|
||||
|
@ -305,30 +262,8 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
if (timerIndex == PWM6 || timerIndex == PWM7)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(AIRBOTF4)
|
||||
// remap PWM11+PWM12 as servos on multirotor mixers that use servos (i.e. Tri)
|
||||
if (timerIndex == PWM11 || timerIndex == PWM12)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (init->useChannelForwarding && !init->airplane) {
|
||||
#if defined(NAZE) && defined(WS2811_TIMER)
|
||||
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
|
||||
if (init->useLEDStrip) {
|
||||
if (timerIndex >= PWM13 && timerIndex <= PWM14) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
} else
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3) || defined(NAZE)
|
||||
// remap PWM5..8 as servos when used in extended servo mode
|
||||
if (timerIndex >= PWM5 && timerIndex <= PWM8)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3EVO)
|
||||
if ((timerIndex == PWM6 || timerIndex == PWM7 || timerIndex == PWM8 || timerIndex == PWM9) && timerHardwarePtr->tim == TIM3) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
|
@ -344,41 +279,15 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
}
|
||||
|
||||
#endif // USE_SERVOS
|
||||
|
||||
#ifdef CC3D
|
||||
// This part of code is unnecessary and can be removed - timer clash is resolved by forcing configuration with the same
|
||||
// timer tick rate - PWM_TIMER_MHZ
|
||||
/*
|
||||
if (init->useParallelPWM) {
|
||||
// Skip PWM inputs that conflict with timers used outputs.
|
||||
if ((type == MAP_TO_SERVO_OUTPUT || type == MAP_TO_MOTOR_OUTPUT) && (timerHardwarePtr->tim == TIM2 || timerHardwarePtr->tim == TIM3)) {
|
||||
continue;
|
||||
}
|
||||
if (type == MAP_TO_PWM_INPUT && timerHardwarePtr->tim == TIM4) {
|
||||
continue;
|
||||
}
|
||||
|
||||
}
|
||||
*/
|
||||
#endif
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#if defined(USE_RX_PPM)
|
||||
#ifdef CC3D_PPM1
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM4);
|
||||
}
|
||||
#endif
|
||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||
}
|
||||
#endif
|
||||
ppmInConfig(timerHardwarePtr);
|
||||
ppmInConfig(timerHardwarePtr, init->pwmProtocolType);
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_PPM;
|
||||
pwmIOConfiguration.ppmInputCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 0);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 0);
|
||||
#endif
|
||||
} else if (type == MAP_TO_PWM_INPUT) {
|
||||
#if defined(USE_RX_PWM)
|
||||
|
@ -387,26 +296,17 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
pwmIOConfiguration.pwmInputCount++;
|
||||
channelIndex++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 1);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 1);
|
||||
#endif
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
/* Check if we already configured maximum supported number of motors and skip the rest */
|
||||
if (pwmIOConfiguration.motorCount >= MAX_MOTORS) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 1);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 1);
|
||||
continue;
|
||||
}
|
||||
|
||||
#if defined(CC3D) && !defined(CC3D_PPM1)
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
|
||||
if (timerHardwarePtr->tim == TIM2) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
pwmMotorConfig(timerHardwarePtr, pwmIOConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType, init->enablePWMOutput);
|
||||
|
||||
if (init->useFastPwm) {
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_FASTPWM | PWM_PF_OUTPUT_PROTOCOL_PWM;
|
||||
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
|
@ -420,10 +320,10 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
pwmIOConfiguration.motorCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
} else if (type == MAP_TO_SERVO_OUTPUT) {
|
||||
if (pwmIOConfiguration.servoCount >= MAX_SERVOS) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -436,7 +336,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
pwmIOConfiguration.servoCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, i, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
#endif
|
||||
} else {
|
||||
continue;
|
||||
|
|
|
@ -49,7 +49,15 @@ typedef struct sonarIOConfig_s {
|
|||
ioTag_t echoTag;
|
||||
} sonarIOConfig_t;
|
||||
|
||||
typedef enum {
|
||||
PLATFORM_MULTIROTOR = 0,
|
||||
PLATFORM_AIRPLANE = 1,
|
||||
PLATFORM_HELICOPTER = 2
|
||||
} flyingPlatformType_e;
|
||||
|
||||
typedef struct drv_pwm_config_s {
|
||||
int flyingPlatformType;
|
||||
|
||||
bool enablePWMOutput;
|
||||
bool useParallelPWM;
|
||||
bool usePPM;
|
||||
|
@ -67,12 +75,11 @@ typedef struct drv_pwm_config_s {
|
|||
bool useSonar;
|
||||
#endif
|
||||
#ifdef USE_SERVOS
|
||||
bool useServos;
|
||||
bool useServoOutputs;
|
||||
bool useChannelForwarding; // configure additional channels as servos
|
||||
uint16_t servoPwmRate;
|
||||
uint16_t servoCenterPulse;
|
||||
#endif
|
||||
bool airplane; // fixed wing hardware config, lots of servos etc
|
||||
uint8_t pwmProtocolType;
|
||||
uint16_t motorPwmRate;
|
||||
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
|
||||
|
@ -80,14 +87,6 @@ typedef struct drv_pwm_config_s {
|
|||
sonarIOConfig_t sonarIOConfig;
|
||||
} drv_pwm_config_t;
|
||||
|
||||
|
||||
enum {
|
||||
MAP_TO_PPM_INPUT = 1,
|
||||
MAP_TO_PWM_INPUT,
|
||||
MAP_TO_MOTOR_OUTPUT,
|
||||
MAP_TO_SERVO_OUTPUT,
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
PWM_PF_NONE = 0,
|
||||
PWM_PF_MOTOR = (1 << 0),
|
||||
|
|
|
@ -34,18 +34,6 @@
|
|||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#if defined(STM32F40_41xxx) // must be multiples of timer clock
|
||||
#define ONESHOT125_TIMER_MHZ 12
|
||||
#define ONESHOT42_TIMER_MHZ 21
|
||||
#define MULTISHOT_TIMER_MHZ 84
|
||||
#define PWM_BRUSHED_TIMER_MHZ 21
|
||||
#else
|
||||
#define ONESHOT125_TIMER_MHZ 8
|
||||
#define ONESHOT42_TIMER_MHZ 24
|
||||
#define MULTISHOT_TIMER_MHZ 72
|
||||
#define PWM_BRUSHED_TIMER_MHZ 24
|
||||
#endif
|
||||
|
||||
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
|
||||
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
||||
|
||||
|
@ -88,24 +76,8 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
|
|||
TIM_OCInitStructure.TIM_OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
|
||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||
|
||||
switch (channel) {
|
||||
case TIM_Channel_1:
|
||||
TIM_OC1Init(tim, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_OC2Init(tim, &TIM_OCInitStructure);
|
||||
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_OC3Init(tim, &TIM_OCInitStructure);
|
||||
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_OC4Init(tim, &TIM_OCInitStructure);
|
||||
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
|
||||
break;
|
||||
}
|
||||
timerOCInit(tim, channel, &TIM_OCInitStructure);
|
||||
timerOCPreloadConfig(tim, channel, TIM_OCPreload_Enable);
|
||||
}
|
||||
|
||||
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value, bool enableOutput)
|
||||
|
@ -134,20 +106,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
|||
}
|
||||
TIM_Cmd(timerHardware->tim, ENABLE);
|
||||
|
||||
switch (timerHardware->channel) {
|
||||
case TIM_Channel_1:
|
||||
p->ccr = &timerHardware->tim->CCR1;
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
p->ccr = &timerHardware->tim->CCR2;
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
p->ccr = &timerHardware->tim->CCR3;
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
p->ccr = &timerHardware->tim->CCR4;
|
||||
break;
|
||||
}
|
||||
p->ccr = timerCCR(timerHardware->tim, timerHardware->channel);
|
||||
p->period = period;
|
||||
p->tim = timerHardware->tim;
|
||||
|
||||
|
|
|
@ -17,6 +17,18 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(STM32F40_41xxx) // must be multiples of timer clock
|
||||
#define ONESHOT125_TIMER_MHZ 12
|
||||
#define ONESHOT42_TIMER_MHZ 21
|
||||
#define MULTISHOT_TIMER_MHZ 84
|
||||
#define PWM_BRUSHED_TIMER_MHZ 21
|
||||
#else
|
||||
#define ONESHOT125_TIMER_MHZ 8
|
||||
#define ONESHOT42_TIMER_MHZ 24
|
||||
#define MULTISHOT_TIMER_MHZ 72
|
||||
#define PWM_BRUSHED_TIMER_MHZ 24
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
PWM_TYPE_STANDARD = 0,
|
||||
PWM_TYPE_ONESHOT125,
|
||||
|
|
|
@ -86,7 +86,7 @@ static uint16_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
|
|||
|
||||
static uint8_t ppmFrameCount = 0;
|
||||
static uint8_t lastPPMFrameCount = 0;
|
||||
static uint8_t ppmCountShift = 0;
|
||||
static uint8_t ppmCountDivisor = 1;
|
||||
|
||||
typedef struct ppmDevice_s {
|
||||
uint8_t pulseIndex;
|
||||
|
@ -205,13 +205,13 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture
|
|||
}
|
||||
|
||||
// Divide by 8 if Oneshot125 is active and this is a CC3D board
|
||||
currentTime = currentTime >> ppmCountShift;
|
||||
currentTime = currentTime / ppmCountDivisor;
|
||||
|
||||
/* Capture computation */
|
||||
if (currentTime > previousTime) {
|
||||
ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD >> ppmCountShift) : 0));
|
||||
ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD / ppmCountDivisor) : 0));
|
||||
} else {
|
||||
ppmDev.deltaTime = (PPM_TIMER_PERIOD >> ppmCountShift) + currentTime - previousTime;
|
||||
ppmDev.deltaTime = (PPM_TIMER_PERIOD / ppmCountDivisor) + currentTime - previousTime;
|
||||
}
|
||||
|
||||
ppmDev.overflowed = false;
|
||||
|
@ -429,17 +429,40 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
|
|||
#define UNUSED_PPM_TIMER_REFERENCE 0
|
||||
#define FIRST_PWM_PORT 0
|
||||
|
||||
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer)
|
||||
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, uint8_t motorPwmProtocol)
|
||||
{
|
||||
if (timerHardwarePtr->tim == sharedPwmTimer) {
|
||||
ppmCountShift = 3; // Divide by 8 if the timer is running at 8 MHz
|
||||
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
|
||||
// If PPM input timer is also mapped to motor - set PPM divisor accordingly
|
||||
if (((timerHardware[timerIndex].usageFlags & (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR)) == 0) && timerHardware[timerIndex].tim != timerHardwarePtr->tim)
|
||||
continue;
|
||||
|
||||
switch (motorPwmProtocol) {
|
||||
case PWM_TYPE_ONESHOT125:
|
||||
ppmCountDivisor = ONESHOT125_TIMER_MHZ;
|
||||
break;
|
||||
case PWM_TYPE_ONESHOT42:
|
||||
ppmCountDivisor = ONESHOT42_TIMER_MHZ;
|
||||
break;
|
||||
case PWM_TYPE_MULTISHOT:
|
||||
ppmCountDivisor = MULTISHOT_TIMER_MHZ;
|
||||
break;
|
||||
case PWM_TYPE_BRUSHED:
|
||||
ppmCountDivisor = PWM_BRUSHED_TIMER_MHZ;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
||||
void ppmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t motorPwmProtocol)
|
||||
{
|
||||
ppmInit();
|
||||
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, motorPwmProtocol);
|
||||
|
||||
pwmInputPort_t *self = &pwmInputPorts[FIRST_PWM_PORT];
|
||||
|
||||
self->mode = INPUT_MODE_PPM;
|
||||
|
|
|
@ -25,8 +25,7 @@ typedef enum {
|
|||
#define PPM_RCVR_TIMEOUT 0
|
||||
|
||||
struct timerHardware_s;
|
||||
void ppmInConfig(const struct timerHardware_s *timerHardwarePtr);
|
||||
void ppmAvoidPWMTimerClash(const struct timerHardware_s *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer);
|
||||
void ppmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t motorPwmProtocol);
|
||||
|
||||
void pwmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t channel);
|
||||
uint16_t pwmRead(uint8_t channel);
|
||||
|
|
|
@ -103,7 +103,7 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
|
|||
{
|
||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
DMA_Cmd(descriptor->channel, DISABLE);
|
||||
DMA_Cmd(descriptor->ref, DISABLE);
|
||||
|
||||
if (s->port.txBufferHead != s->port.txBufferTail)
|
||||
uartStartTxDMA(s);
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -207,25 +208,23 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
|
|||
return 0;
|
||||
}
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
uint8_t timerGPIOAF(TIM_TypeDef *tim)
|
||||
uint8_t timerInputIrq(TIM_TypeDef *tim)
|
||||
{
|
||||
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
|
||||
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
|
||||
if (timerDefinitions[i].TIMx == tim) {
|
||||
return timerDefinitions[i].alternateFunction;
|
||||
return timerDefinitions[i].inputIrq;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
void timerNVICConfigure(uint8_t irq)
|
||||
void timerNVICConfigure(uint8_t irq, int irqPriority)
|
||||
{
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER);
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
@ -239,24 +238,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
|
||||
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
|
||||
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
|
||||
#if defined (STM32F40_41xxx) || defined (STM32F427_437xx)
|
||||
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
||||
}
|
||||
else {
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
|
||||
}
|
||||
#elif defined (STM32F411xE)
|
||||
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
||||
}
|
||||
else {
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
|
||||
}
|
||||
#else
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
||||
#endif
|
||||
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(tim) / ((uint32_t)mhz * 1000000)) - 1;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
|
||||
|
@ -267,39 +249,42 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
{
|
||||
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
||||
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
|
||||
timerNVICConfigure(timerHardwarePtr->irq);
|
||||
|
||||
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
||||
timerNVICConfigure(irq, NVIC_PRIO_TIMER);
|
||||
|
||||
// HACK - enable second IRQ on timers that need it
|
||||
switch(timerHardwarePtr->irq) {
|
||||
switch(irq) {
|
||||
#if defined(STM32F10X)
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_IRQn);
|
||||
timerNVICConfigure(TIM1_UP_IRQn, NVIC_PRIO_TIMER);
|
||||
break;
|
||||
#endif
|
||||
#if defined (STM32F40_41xxx) || defined(STM32F411xE) || defined (STM32F427_437xx)
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
|
||||
timerNVICConfigure(TIM1_UP_TIM10_IRQn, NVIC_PRIO_TIMER);
|
||||
break;
|
||||
#endif
|
||||
#if defined (STM32F40_41xxx) || defined (STM32F427_437xx)
|
||||
case TIM8_CC_IRQn:
|
||||
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
|
||||
timerNVICConfigure(TIM8_UP_TIM13_IRQn, NVIC_PRIO_TIMER);
|
||||
break;
|
||||
#endif
|
||||
#ifdef STM32F303xC
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_TIM16_IRQn);
|
||||
timerNVICConfigure(TIM1_UP_TIM16_IRQn, NVIC_PRIO_TIMER);
|
||||
break;
|
||||
#endif
|
||||
#if defined(STM32F10X_XL)
|
||||
case TIM8_CC_IRQn:
|
||||
timerNVICConfigure(TIM8_UP_IRQn);
|
||||
timerNVICConfigure(TIM8_UP_IRQn, NVIC_PRIO_TIMER);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// allocate and configure timer channel. Timer priority is set to highest priority of its channels
|
||||
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority)
|
||||
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
|
||||
{
|
||||
unsigned channel = timHw - timerHardware;
|
||||
if(channel >= USABLE_TIMER_CHANNEL_COUNT)
|
||||
|
@ -314,13 +299,7 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori
|
|||
configTimeBase(usedTimers[timer], 0, 1);
|
||||
TIM_Cmd(usedTimers[timer], ENABLE);
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = timHw->irq;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
timerNVICConfigure(irq, irqPriority);
|
||||
|
||||
timerInfo[timer].priority = irqPriority;
|
||||
}
|
||||
|
@ -719,12 +698,12 @@ void timerInit(void)
|
|||
#endif
|
||||
|
||||
/* enable the timer peripherals */
|
||||
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
|
||||
}
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
|
||||
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
|
||||
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
|
||||
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
|
||||
}
|
||||
|
@ -787,3 +766,91 @@ void timerForceOverflow(TIM_TypeDef *tim)
|
|||
tim->EGR |= TIM_EGR_UG;
|
||||
}
|
||||
}
|
||||
|
||||
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
|
||||
{
|
||||
if (!tag) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
if (timerHardware[i].tag == tag) {
|
||||
if (timerHardware[i].usageFlags & flag || flag == 0) {
|
||||
return &timerHardware[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
#if !defined(USE_HAL_DRIVER)
|
||||
void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init)
|
||||
{
|
||||
switch (channel) {
|
||||
case TIM_Channel_1:
|
||||
TIM_OC1Init(tim, init);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_OC2Init(tim, init);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_OC3Init(tim, init);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_OC4Init(tim, init);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload)
|
||||
{
|
||||
switch (channel) {
|
||||
case TIM_Channel_1:
|
||||
TIM_OC1PreloadConfig(tim, preload);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_OC2PreloadConfig(tim, preload);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_OC3PreloadConfig(tim, preload);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_OC4PreloadConfig(tim, preload);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t timerDmaSource(uint8_t channel)
|
||||
{
|
||||
switch (channel) {
|
||||
case TIM_Channel_1:
|
||||
return TIM_DMA_CC1;
|
||||
case TIM_Channel_2:
|
||||
return TIM_DMA_CC2;
|
||||
case TIM_Channel_3:
|
||||
return TIM_DMA_CC3;
|
||||
case TIM_Channel_4:
|
||||
return TIM_DMA_CC4;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
volatile timCCR_t* timerCCR(TIM_TypeDef *tim, uint8_t channel)
|
||||
{
|
||||
return (volatile timCCR_t*)((volatile char*)&tim->CCR1 + channel);
|
||||
}
|
||||
|
||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
||||
{
|
||||
// protection here for desired MHZ > SystemCoreClock???
|
||||
if ((uint32_t)(mhz * 1000000) > (SystemCoreClock / timerClockDivisor(tim))) {
|
||||
return 0;
|
||||
}
|
||||
return (uint16_t)(round((SystemCoreClock / timerClockDivisor(tim) / (mhz * 1000000)) - 1));
|
||||
}
|
||||
|
||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
||||
{
|
||||
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
|
||||
}
|
|
@ -73,21 +73,31 @@ typedef struct timerOvrHandlerRec_s {
|
|||
typedef struct timerDef_s {
|
||||
TIM_TypeDef *TIMx;
|
||||
rccPeriphTag_t rcc;
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
||||
uint8_t alternateFunction;
|
||||
#endif
|
||||
uint8_t inputIrq;
|
||||
} timerDef_t;
|
||||
|
||||
typedef enum {
|
||||
TIM_USE_ANY = 0,
|
||||
TIM_USE_PPM = (1 << 0),
|
||||
TIM_USE_PWM = (1 << 1),
|
||||
TIM_USE_MC_MOTOR = (1 << 2), // Multicopter motor output
|
||||
TIM_USE_MC_SERVO = (1 << 3), // Multicopter servo output (i.e. TRI)
|
||||
TIM_USE_MC_CHNFW = (1 << 4), // Multicopter servo output if channel forwarding is used
|
||||
TIM_USE_FW_MOTOR = (1 << 5),
|
||||
TIM_USE_FW_SERVO = (1 << 6),
|
||||
TIM_USE_LED = (1 << 24),
|
||||
} timerUsageFlag_e;
|
||||
|
||||
typedef struct timerHardware_s {
|
||||
TIM_TypeDef *tim;
|
||||
ioTag_t tag;
|
||||
uint8_t channel;
|
||||
uint8_t irq;
|
||||
uint8_t output;
|
||||
ioConfig_t ioMode;
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
||||
uint8_t alternateFunction;
|
||||
#endif
|
||||
uint32_t usageFlags;
|
||||
} timerHardware_t;
|
||||
|
||||
enum {
|
||||
|
@ -134,6 +144,8 @@ typedef enum {
|
|||
TYPE_TIMER
|
||||
} channelType_t;
|
||||
|
||||
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);
|
||||
|
||||
void timerConfigure(const timerHardware_t *timHw, uint16_t period, uint8_t mhz); // This interface should be replaced.
|
||||
|
||||
void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterSamples);
|
||||
|
@ -153,22 +165,29 @@ void timerChITConfigDualLo(const timerHardware_t* timHw, FunctionalState newStat
|
|||
void timerChITConfig(const timerHardware_t* timHw, FunctionalState newState);
|
||||
void timerChClearCCFlag(const timerHardware_t* timHw);
|
||||
|
||||
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority);
|
||||
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq);
|
||||
|
||||
void timerInit(void);
|
||||
void timerStart(void);
|
||||
void timerForceOverflow(TIM_TypeDef *tim);
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
||||
|
||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
|
||||
|
||||
uint16_t timerGetPeriod(const timerHardware_t *timHw);
|
||||
|
||||
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
||||
uint8_t timerGPIOAF(TIM_TypeDef *tim);
|
||||
#endif
|
||||
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim);
|
||||
#else
|
||||
void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init);
|
||||
void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload);
|
||||
uint16_t timerDmaSource(uint8_t channel);
|
||||
#endif
|
||||
|
||||
volatile timCCR_t *timerCCR(TIM_TypeDef *tim, uint8_t channel);
|
||||
|
||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz);
|
||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz);
|
||||
|
|
|
@ -17,49 +17,26 @@
|
|||
#include "timer.h"
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
|
||||
{ .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) },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
|
||||
{ .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) },
|
||||
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
|
||||
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
|
||||
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
|
||||
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
|
||||
{ .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
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Selects the TIM Output Compare Mode.
|
||||
* @note This function does NOT disable the selected channel before changing the Output
|
||||
* Compare Mode.
|
||||
* @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral.
|
||||
* @param TIM_Channel: specifies the TIM Channel
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_Channel_1: TIM Channel 1
|
||||
* @arg TIM_Channel_2: TIM Channel 2
|
||||
* @arg TIM_Channel_3: TIM Channel 3
|
||||
* @arg TIM_Channel_4: TIM Channel 4
|
||||
* @param TIM_OCMode: specifies the TIM Output Compare Mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_OCMode_Timing
|
||||
* @arg TIM_OCMode_Active
|
||||
* @arg TIM_OCMode_Toggle
|
||||
* @arg TIM_OCMode_PWM1
|
||||
* @arg TIM_OCMode_PWM2
|
||||
* @arg TIM_ForcedAction_Active
|
||||
* @arg TIM_ForcedAction_InActive
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
#define CCMR_Offset ((uint16_t)0x0018)
|
||||
|
||||
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
|
||||
|
@ -92,3 +69,9 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
*(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -17,48 +17,18 @@
|
|||
#include "timer.h"
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 },
|
||||
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 },
|
||||
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 },
|
||||
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 },
|
||||
{ .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 },
|
||||
};
|
||||
|
||||
|
||||
/**
|
||||
* @brief Selects the TIM Output Compare Mode.
|
||||
* @note This function does NOT disable the selected channel before changing the Output
|
||||
* Compare Mode. If needed, user has to enable this channel using
|
||||
* TIM_CCxCmd() and TIM_CCxNCmd() functions.
|
||||
* @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral.
|
||||
* @param TIM_Channel: specifies the TIM Channel
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_Channel_1: TIM Channel 1
|
||||
* @arg TIM_Channel_2: TIM Channel 2
|
||||
* @arg TIM_Channel_3: TIM Channel 3
|
||||
* @arg TIM_Channel_4: TIM Channel 4
|
||||
* @param TIM_OCMode: specifies the TIM Output Compare Mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_OCMode_Timing
|
||||
* @arg TIM_OCMode_Active
|
||||
* @arg TIM_OCMode_Toggle
|
||||
* @arg TIM_OCMode_PWM1
|
||||
* @arg TIM_OCMode_PWM2
|
||||
* @arg TIM_ForcedAction_Active
|
||||
* @arg TIM_ForcedAction_InActive
|
||||
* @arg TIM_OCMode_Retrigerrable_OPM1
|
||||
* @arg TIM_OCMode_Retrigerrable_OPM2
|
||||
* @arg TIM_OCMode_Combined_PWM1
|
||||
* @arg TIM_OCMode_Combined_PWM2
|
||||
* @arg TIM_OCMode_Asymmetric_PWM1
|
||||
* @arg TIM_OCMode_Asymmetric_PWM2
|
||||
* @retval None
|
||||
*/
|
||||
#define CCMR_OFFSET ((uint16_t)0x0018)
|
||||
#define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F)
|
||||
#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF)
|
||||
|
@ -93,3 +63,9 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
|
|||
*(__IO uint32_t *) tmp |= (uint32_t)(TIM_OCMode << 8);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -16,46 +16,27 @@
|
|||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
/**
|
||||
* @brief Selects the TIM Output Compare Mode.
|
||||
* @note This function does NOT disable the selected channel before changing the Output
|
||||
* Compare Mode.
|
||||
* @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral.
|
||||
* @param TIM_Channel: specifies the TIM Channel
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_Channel_1: TIM Channel 1
|
||||
* @arg TIM_Channel_2: TIM Channel 2
|
||||
* @arg TIM_Channel_3: TIM Channel 3
|
||||
* @arg TIM_Channel_4: TIM Channel 4
|
||||
* @param TIM_OCMode: specifies the TIM Output Compare Mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_OCMode_Timing
|
||||
* @arg TIM_OCMode_Active
|
||||
* @arg TIM_OCMode_Toggle
|
||||
* @arg TIM_OCMode_PWM1
|
||||
* @arg TIM_OCMode_PWM2
|
||||
* @arg TIM_ForcedAction_Active
|
||||
* @arg TIM_ForcedAction_InActive
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
#define CCMR_Offset ((uint16_t)0x0018)
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 },
|
||||
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 },
|
||||
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 },
|
||||
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 },
|
||||
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 },
|
||||
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 },
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF_TIM13 },
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF_TIM14 },
|
||||
{ .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 = TIM5, .rcc = RCC_APB1(TIM5), .inputIrq = TIM5_IRQn},
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0},
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0},
|
||||
#if !defined(STM32F411xE) && !defined(STM32F446xx)
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), .inputIrq = TIM8_CC_IRQn},
|
||||
#endif
|
||||
{ .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},
|
||||
#ifndef STM32F411xE
|
||||
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), .inputIrq = TIM8_BRK_TIM12_IRQn},
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), .inputIrq = TIM8_UP_TIM13_IRQn},
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), .inputIrq = TIM8_TRG_COM_TIM14_IRQn},
|
||||
#endif
|
||||
};
|
||||
|
||||
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
|
||||
|
@ -89,3 +70,14 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
||||
{
|
||||
#if defined (STM32F40_41xxx)
|
||||
if (tim == TIM8) return 1;
|
||||
#endif
|
||||
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||
return 1;
|
||||
} else {
|
||||
return 2;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -16,46 +16,23 @@
|
|||
#include "timer.h"
|
||||
#include "rcc.h"
|
||||
|
||||
/**
|
||||
* @brief Selects the TIM Output Compare Mode.
|
||||
* @note This function does NOT disable the selected channel before changing the Output
|
||||
* Compare Mode.
|
||||
* @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral.
|
||||
* @param TIM_Channel: specifies the TIM Channel
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_Channel_1: TIM Channel 1
|
||||
* @arg TIM_Channel_2: TIM Channel 2
|
||||
* @arg TIM_Channel_3: TIM Channel 3
|
||||
* @arg TIM_Channel_4: TIM Channel 4
|
||||
* @param TIM_OCMode: specifies the TIM Output Compare Mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg TIM_OCMode_Timing
|
||||
* @arg TIM_OCMode_Active
|
||||
* @arg TIM_OCMode_Toggle
|
||||
* @arg TIM_OCMode_PWM1
|
||||
* @arg TIM_OCMode_PWM2
|
||||
* @arg TIM_ForcedAction_Active
|
||||
* @arg TIM_ForcedAction_InActive
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
#define CCMR_Offset ((uint16_t)0x0018)
|
||||
|
||||
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF1_TIM1 },
|
||||
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF1_TIM2 },
|
||||
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF2_TIM3 },
|
||||
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF2_TIM4 },
|
||||
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF2_TIM5 },
|
||||
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
|
||||
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
|
||||
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF3_TIM8 },
|
||||
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF3_TIM9 },
|
||||
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF3_TIM10 },
|
||||
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF3_TIM11 },
|
||||
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF9_TIM12 },
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF9_TIM13 },
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF9_TIM14 },
|
||||
{ .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 = TIM5, .rcc = RCC_APB1(TIM5), .inputIrq = TIM5_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 = 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 = TIM8_BRK_TIM12_IRQn},
|
||||
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), .inputIrq = TIM8_UP_TIM13_IRQn},
|
||||
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), .inputIrq = TIM8_TRG_COM_TIM14_IRQn},
|
||||
};
|
||||
|
||||
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
|
||||
|
@ -89,3 +66,8 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
@ -287,18 +288,22 @@ void validateAndFixConfig(void)
|
|||
#endif
|
||||
|
||||
#if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||
if (featureConfigured(FEATURE_SOFTSERIAL) && (
|
||||
0
|
||||
if (featureConfigured(FEATURE_SOFTSERIAL)) {
|
||||
const timerHardware_t *timerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||
if (timerHardware != NULL) {
|
||||
if (0
|
||||
#if defined(USE_SOFTSERIAL1) && defined(SOFTSERIAL_1_TIMER)
|
||||
|| (WS2811_TIMER == SOFTSERIAL_1_TIMER)
|
||||
|| (timerHardware->tim == SOFTSERIAL_1_TIMER)
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
|| (WS2811_TIMER == SOFTSERIAL_2_TIMER)
|
||||
|| (timerHardware->tim == SOFTSERIAL_2_TIMER)
|
||||
#endif
|
||||
)) {
|
||||
) {
|
||||
// led strip needs the same timer as softserial
|
||||
featureClear(FEATURE_LED_STRIP);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(NAZE) && defined(SONAR)
|
||||
|
|
|
@ -703,11 +703,14 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
#ifdef USE_SERVOS
|
||||
if (isMixerUsingServos()) {
|
||||
servoMixer();
|
||||
processServoAutotrim();
|
||||
}
|
||||
|
||||
// Servo tilt is not part of servo mixer, but uses servos
|
||||
if (feature(FEATURE_SERVO_TILT)) {
|
||||
processServoTilt();
|
||||
}
|
||||
processServoAutotrim();
|
||||
|
||||
//Servos should be filtered or written only when mixer is using servos or special feaures are enabled
|
||||
if (isServoOutputEnabled()) {
|
||||
writeServos();
|
||||
|
|
|
@ -226,10 +226,6 @@ void init(void)
|
|||
|
||||
timerInit(); // timer must be initialized before any channel is allocated
|
||||
|
||||
#if !defined(USE_HAL_DRIVER)
|
||||
dmaInit();
|
||||
#endif
|
||||
|
||||
#if defined(AVOID_UART2_FOR_PWM_PPM)
|
||||
serialInit(feature(FEATURE_SOFTSERIAL),
|
||||
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
|
||||
|
@ -261,7 +257,8 @@ void init(void)
|
|||
#endif
|
||||
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
pwm_params.airplane = STATE(FIXED_WING);
|
||||
pwm_params.flyingPlatformType = getFlyingPlatformType();
|
||||
|
||||
#if defined(USE_UART2) && defined(STM32F10X)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
|
@ -285,7 +282,7 @@ void init(void)
|
|||
pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
pwm_params.useServos = isMixerUsingServos();
|
||||
pwm_params.useServoOutputs = isMixerUsingServos();
|
||||
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||
pwm_params.servoCenterPulse = servoConfig()->servoCenterPulse;
|
||||
pwm_params.servoPwmRate = servoConfig()->servoPwmRate;
|
||||
|
@ -321,7 +318,8 @@ void init(void)
|
|||
servo handling mechanism, since external device will do that
|
||||
*/
|
||||
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
|
||||
pwm_params.useServos = false;
|
||||
pwm_params.useServoOutputs = false;
|
||||
pwm_params.useChannelForwarding = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -79,7 +79,8 @@ typedef enum {
|
|||
NAV_MOTOR_STOP_OR_IDLE = (1 << 7), // navigation requests MOTOR_STOP or motor idle regardless of throttle stick, will only activate if MOTOR_STOP feature is available
|
||||
COMPASS_CALIBRATED = (1 << 8),
|
||||
ACCELEROMETER_CALIBRATED= (1 << 9),
|
||||
PWM_DRIVER_AVAILABLE = (1 << 10)
|
||||
PWM_DRIVER_AVAILABLE = (1 << 10),
|
||||
HELICOPTER = (1 << 11)
|
||||
} stateFlags_t;
|
||||
|
||||
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))
|
||||
|
|
|
@ -110,6 +110,7 @@ static const motorMixer_t mixerQuadX[] = {
|
|||
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
|
||||
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
|
||||
};
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static const motorMixer_t mixerTricopter[] = {
|
||||
{ 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR
|
||||
|
@ -227,97 +228,107 @@ static const motorMixer_t mixerDualProp[] = {
|
|||
{ 1.0f, 0.0f, 0.0f, 0.0f },
|
||||
};
|
||||
|
||||
// Keep synced with mixerMode_e
|
||||
const mixer_t mixers[] = {
|
||||
// motors, use servo, motor mixer
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=true }, // entry 0
|
||||
{ .motorCount=3, .useServo=true, .motor=mixerTricopter, .enabled=true }, // MIXER_TRI
|
||||
{ .motorCount=4, .useServo=false, .motor=mixerQuadP, .enabled=true }, // MIXER_QUADP
|
||||
{ .motorCount=4, .useServo=false, .motor=mixerQuadX, .enabled=true }, // MIXER_QUADX
|
||||
#define DEF_MIXER(_mixerMode, _flyingPlatformType, _motorCount, _useServos, _hasFlaps, _motorMap) \
|
||||
{ .mixerMode=_mixerMode, .flyingPlatformType=_flyingPlatformType, .motorCount=_motorCount, .useServos=_useServos, .hasFlaps=_hasFlaps, .motor=_motorMap }
|
||||
|
||||
static const mixer_t mixerTable[] = {
|
||||
// motors, use servo, motor mixer
|
||||
// mixerMode flyingPlatformType motorCount useServos hasFlaps motorMap
|
||||
DEF_MIXER( MIXER_TRI, PLATFORM_MULTIROTOR, 3, true, false, mixerTricopter ),
|
||||
DEF_MIXER( MIXER_CUSTOM_TRI, PLATFORM_MULTIROTOR, 3, false, false, NULL ),
|
||||
|
||||
DEF_MIXER( MIXER_QUADP, PLATFORM_MULTIROTOR, 4, false, false, mixerQuadP ),
|
||||
DEF_MIXER( MIXER_QUADX, PLATFORM_MULTIROTOR, 4, false, false, mixerQuadX ),
|
||||
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_BICOPTER
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_GIMBAL -> this mixer was never implemented in CF, use feature(FEATURE_SERVO_TILT) instead
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS) && (MAX_SUPPORTED_MOTORS >= 6)
|
||||
{ .motorCount=6, .useServo=false, .motor=mixerY6, .enabled=true }, // MIXER_Y6
|
||||
{ .motorCount=6, .useServo=false, .motor=mixerHex6P, .enabled=true }, // MIXER_HEX6
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_Y6
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_HEX6
|
||||
#endif
|
||||
{ .motorCount=2, .useServo=true, .motor=mixerDualProp, .enabled=true }, // MIXER_FLYING_WING
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
{ .motorCount=4, .useServo=false, .motor=mixerY4, .enabled=true }, // MIXER_Y4
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_Y4
|
||||
#endif
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
{ .motorCount=6, .useServo=false, .motor=mixerHex6X, .enabled=true }, // MIXER_HEX6X
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_HEX6X
|
||||
DEF_MIXER( MIXER_HEX6, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6X ),
|
||||
#endif
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS) && (MAX_SUPPORTED_MOTORS >= 8)
|
||||
{ .motorCount=8, .useServo=false, .motor=mixerOctoX8, .enabled=true }, // MIXER_OCTOX8
|
||||
{ .motorCount=8, .useServo=false, .motor=mixerOctoFlatP, .enabled=true }, // MIXER_OCTOFLATP
|
||||
{ .motorCount=8, .useServo=false, .motor=mixerOctoFlatX, .enabled=true }, // MIXER_OCTOFLATX
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_OCTOX8
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_OCTOFLATP
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_OCTOFLATX
|
||||
#endif
|
||||
{ .motorCount=2, .useServo=true, .motor=mixerDualProp, .enabled=true }, // * MIXER_AIRPLANE
|
||||
{ .motorCount=0, .useServo=true, .motor=NULL, .enabled=false }, // * MIXER_HELI_120_CCPM -> disabled, never fully implemented in CF
|
||||
{ .motorCount=0, .useServo=true, .motor=NULL, .enabled=false }, // * MIXER_HELI_90_DEG -> disabled, never fully implemented in CF
|
||||
|
||||
DEF_MIXER( MIXER_CUSTOM, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_BICOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
//DEF_MIXER( MIXER_GIMBAL, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
DEF_MIXER( MIXER_FLYING_WING, PLATFORM_AIRPLANE, 2, true, false, mixerDualProp ),
|
||||
DEF_MIXER( MIXER_AIRPLANE, PLATFORM_AIRPLANE, 2, true, true, mixerDualProp ),
|
||||
DEF_MIXER( MIXER_CUSTOM_AIRPLANE, PLATFORM_AIRPLANE, 2, true, true, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_HELI_120_CCPM, PLATFORM_HELICOPTER, 1, true, false, NULL ),
|
||||
//DEF_MIXER( MIXER_HELI_90_DEG, PLATFORM_HELICOPTER, 1, true, false, NULL ),
|
||||
|
||||
//DEF_MIXER( MIXER_PPM_TO_SERVO, PLATFORM_MULTIROTOR, 0, true, false, NULL ),
|
||||
//DEF_MIXER( MIXER_DUALCOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
//DEF_MIXER( MIXER_SINGLECOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
{ .motorCount=4, .useServo=false, .motor=mixerVtail4, .enabled=true }, // MIXER_VTAIL4
|
||||
DEF_MIXER( MIXER_Y4, PLATFORM_MULTIROTOR, 4, false, false, mixerY4 ),
|
||||
DEF_MIXER( MIXER_ATAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerAtail4 ),
|
||||
DEF_MIXER( MIXER_VTAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerVtail4 ),
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 6)
|
||||
{ .motorCount=6, .useServo=false, .motor=mixerHex6H, .enabled=true }, // MIXER_HEX6H
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_HEX6H
|
||||
DEF_MIXER( MIXER_Y6, PLATFORM_MULTIROTOR, 6, false, false, mixerY6 ),
|
||||
DEF_MIXER( MIXER_HEX6, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6P ),
|
||||
DEF_MIXER( MIXER_HEX6H, PLATFORM_MULTIROTOR, 6, false, false, mixerHex6H ),
|
||||
#endif
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_VTAIL4
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_HEX6H
|
||||
|
||||
#if (MAX_SUPPORTED_MOTORS >= 8)
|
||||
DEF_MIXER( MIXER_OCTOX8, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoX8 ),
|
||||
DEF_MIXER( MIXER_OCTOFLATP, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoFlatP ),
|
||||
DEF_MIXER( MIXER_OCTOFLATX, PLATFORM_MULTIROTOR, 8, false, false, mixerOctoFlatX ),
|
||||
#endif
|
||||
{ .motorCount=0, .useServo=true, .motor=NULL, .enabled=false }, // * MIXER_PPM_TO_SERVO -> looks like this is not implemented at all
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_DUALCOPTER
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_SINGLECOPTER
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
{ .motorCount=4, .useServo=false, .motor=mixerAtail4, .enabled=true }, // MIXER_ATAIL4
|
||||
#else
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=false }, // MIXER_ATAIL4
|
||||
#endif
|
||||
{ .motorCount=0, .useServo=false, .motor=NULL, .enabled=true }, // MIXER_CUSTOM
|
||||
{ .motorCount=2, .useServo=true, .motor=NULL, .enabled=true }, // MIXER_CUSTOM_AIRPLANE
|
||||
{ .motorCount=3, .useServo=true, .motor=NULL, .enabled=true }, // MIXER_CUSTOM_TRI
|
||||
};
|
||||
#endif // USE_QUAD_MIXER_ONLY
|
||||
|
||||
const mixer_t * findMixer(mixerMode_e mixerMode)
|
||||
{
|
||||
for (unsigned ii = 0; ii < sizeof(mixerTable)/sizeof(mixerTable[0]); ii++) {
|
||||
if (mixerTable[ii].mixerMode == mixerMode)
|
||||
return &mixerTable[ii];
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool isMixerEnabled(mixerMode_e mixerMode)
|
||||
{
|
||||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
UNUSED(mixerMode);
|
||||
return true;
|
||||
#else
|
||||
return mixers[mixerMode].enabled;
|
||||
const mixer_t * mixer = findMixer(mixerMode);
|
||||
return (mixer != NULL) ? true : false;
|
||||
#endif
|
||||
}
|
||||
|
||||
int getFlyingPlatformType(void)
|
||||
{
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
if (mixer)
|
||||
return mixer->flyingPlatformType;
|
||||
else
|
||||
return PLATFORM_MULTIROTOR; // safe default
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
void mixerUpdateStateFlags(void)
|
||||
{
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
// set flag that we're on something with wings
|
||||
if (currentMixerMode == MIXER_FLYING_WING ||
|
||||
currentMixerMode == MIXER_AIRPLANE ||
|
||||
currentMixerMode == MIXER_CUSTOM_AIRPLANE
|
||||
) {
|
||||
if (mixer->flyingPlatformType == PLATFORM_AIRPLANE) {
|
||||
ENABLE_STATE(FIXED_WING);
|
||||
DISABLE_STATE(HELICOPTER);
|
||||
} else if (mixer->flyingPlatformType == PLATFORM_HELICOPTER) {
|
||||
DISABLE_STATE(FIXED_WING);
|
||||
ENABLE_STATE(HELICOPTER);
|
||||
} else {
|
||||
DISABLE_STATE(FIXED_WING);
|
||||
DISABLE_STATE(HELICOPTER);
|
||||
}
|
||||
|
||||
if (currentMixerMode == MIXER_AIRPLANE || currentMixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
if (mixer->hasFlaps) {
|
||||
ENABLE_STATE(FLAPERON_AVAILABLE);
|
||||
} else {
|
||||
DISABLE_STATE(FLAPERON_AVAILABLE);
|
||||
|
@ -331,6 +342,8 @@ void mixerUsePWMIOConfiguration(void)
|
|||
motorCount = 0;
|
||||
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
const mixer_t * mixer = findMixer(mixerConfig()->mixerMode);
|
||||
|
||||
if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
// load custom mixer into currentMixer
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
|
@ -341,11 +354,11 @@ void mixerUsePWMIOConfiguration(void)
|
|||
motorCount++;
|
||||
}
|
||||
} else {
|
||||
motorCount = MIN(mixers[currentMixerMode].motorCount, pwmGetOutputConfiguration()->motorCount);
|
||||
// copy motor-based mixers
|
||||
if (mixers[currentMixerMode].motor) {
|
||||
motorCount = MIN(mixer->motorCount, pwmGetOutputConfiguration()->motorCount);
|
||||
// copy motor-based mixer
|
||||
if (mixer->motor) {
|
||||
for (i = 0; i < motorCount; i++)
|
||||
currentMixer[i] = mixers[currentMixerMode].motor[i];
|
||||
currentMixer[i] = mixer->motor[i];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -387,9 +400,10 @@ void mixerLoadMix(int index, motorMixer_t *customMixers)
|
|||
customMixers[i].throttle = 0.0f;
|
||||
|
||||
// do we have anything here to begin with?
|
||||
if (mixers[index].motor != NULL) {
|
||||
for (i = 0; i < mixers[index].motorCount; i++)
|
||||
customMixers[i] = mixers[index].motor[i];
|
||||
const mixer_t * mixer = findMixer(index);
|
||||
if (mixer->motor != NULL) {
|
||||
for (i = 0; i < mixer->motorCount; i++)
|
||||
customMixers[i] = mixer->motor[i];
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -80,10 +80,12 @@ PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer);
|
|||
|
||||
// Custom mixer configuration
|
||||
typedef struct mixer_s {
|
||||
mixerMode_e mixerMode;
|
||||
const motorMixer_t *motor;
|
||||
uint8_t flyingPlatformType; // MC, FW or HELI
|
||||
uint8_t motorCount;
|
||||
uint8_t useServo;
|
||||
bool enabled;
|
||||
bool useServos;
|
||||
bool hasFlaps;
|
||||
} mixer_t;
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
|
@ -131,4 +133,6 @@ void processServoAutotrim(void);
|
|||
void stopMotors(void);
|
||||
void stopPwmAllMotors(void);
|
||||
|
||||
int getFlyingPlatformType(void);
|
||||
|
||||
bool isMixerEnabled(mixerMode_e mixerMode);
|
||||
|
|
|
@ -60,8 +60,7 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
|
||||
extern const mixer_t mixers[];
|
||||
extern const mixer_t * findMixer(mixerMode_e mixerMode);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0);
|
||||
|
||||
|
@ -196,15 +195,16 @@ int servoDirection(int servoIndex, int inputSource)
|
|||
void servosInit(void)
|
||||
{
|
||||
const mixerMode_e currentMixerMode = mixerConfig()->mixerMode;
|
||||
const mixer_t * motorMixer = findMixer(currentMixerMode);
|
||||
|
||||
minServoIndex = servoMixers[currentMixerMode].minServoIndex;
|
||||
maxServoIndex = servoMixers[currentMixerMode].maxServoIndex;
|
||||
|
||||
// enable servos for mixes that require them. note, this shifts motor counts.
|
||||
mixerUsesServos = mixers[currentMixerMode].useServo || feature(FEATURE_SERVO_TILT);
|
||||
mixerUsesServos = motorMixer->useServos || feature(FEATURE_SERVO_TILT);
|
||||
|
||||
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
||||
servoOutputEnabled = mixerUsesServos || feature(FEATURE_CHANNEL_FORWARDING);
|
||||
servoOutputEnabled = motorMixer->useServos || feature(FEATURE_SERVO_TILT) || feature(FEATURE_CHANNEL_FORWARDING);
|
||||
|
||||
// give all servos a default command
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
|
|
|
@ -22,68 +22,17 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
/*
|
||||
* This target does not allows PWM Input, so this configuration will never be used
|
||||
*/
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
/*
|
||||
* This target does not allows PWM Input, so this configuration will never be used
|
||||
*/
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // PPM / S.BUS input, above MOTOR1
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // Connected: small CH2 pad, not used as PWM, definition inherited from REVO target - GPIO_PartialRemap_TIM3
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // Connected: UART6 TX, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // Connected: UART6 RX, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // Connected: small CH5 pad, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // Connected: small CH6 pad, not used as PWM, definition inherited from REVO target
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // MOTOR_1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // MOTOR_2
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9 }, // MOTOR_3
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2 }, // MOTOR_4
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // MOTOR_5 - GPIO_PartialRemap_TIM3
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1 }, // MOTOR_6
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // PPM / S.BUS input, above MOTOR1
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, 0 }, // Connected: small CH2 pad, not used as PWM, definition inherited from REVO target - GPIO_PartialRemap_TIM3
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, 0 }, // Connected: UART6 TX, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, 0 }, // Connected: UART6 RX, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, 0 }, // Connected: small CH5 pad, not used as PWM, definition inherited from REVO target
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, 0 }, // Connected: small CH6 pad, not used as PWM, definition inherited from REVO target
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // MOTOR_1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // MOTOR_2
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_4
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // MOTOR_5 - GPIO_PartialRemap_TIM3
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // MOTOR_6
|
||||
};
|
||||
|
|
|
@ -13,4 +13,4 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
|
|
@ -23,96 +23,23 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
#endif
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
#endif
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
#endif
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
#endif
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM7 - not broken out
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM8 - not broken out
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM }, // PWM6 - RC6
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_11}, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM12 - OUT4
|
||||
//{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM7 - not broken out
|
||||
//{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM8 - not broken out
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2} // PWM14 - OUT6
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -109,11 +109,11 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
#else
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
#define TARGET_MOTOR_COUNT 6
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
#endif
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
|
|
|
@ -12,6 +12,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/serial_softserial.c
|
||||
|
|
|
@ -22,61 +22,20 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// up to 10 Motor Outputs
|
||||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
|
||||
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
|
||||
{ TIM15, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM9 - PA4 - *TIM3_CH2
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
|
||||
// PPM PORT - Also USART2 RX (AF5)
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_PPM } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||
};
|
||||
|
||||
|
|
|
@ -22,102 +22,22 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // USART2
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // USART2 // Swap to servo if needed
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S1_IN
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S2_IN
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // S3_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // S4_IN
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // S5_IN
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // S6_IN
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PWM }, // S2_IN
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PWM }, // S3_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PWM }, // S4_IN
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PWM }, // S5_IN
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PWM }, // S6_IN
|
||||
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S1_OUT
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S2_OUT
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2 }, // S3_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2 }, // S4_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // S5_OUT
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // S6_OUT
|
||||
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2 }, // S7_OUT
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S8_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S9_OUT
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2 }, // S10_OUT
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S10_OUT 16
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S6_OUT 12
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S5_OUT 11
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S1_OUT 7
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S2_OUT 8
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT 9
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT 10
|
||||
{ TIM2, IO_TAG(PA15), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S7_OUT 13
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S8_OUT 14
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S9_OUT 15
|
||||
};
|
||||
|
|
|
@ -6,6 +6,6 @@ TARGET_SRC = \
|
|||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/pitotmeter_ms4525.c
|
||||
|
||||
|
|
|
@ -22,105 +22,24 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12 }, // S1_IN
|
||||
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12 }, // S2_IN
|
||||
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8 }, // S3_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8 }, // S4_IN
|
||||
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8 }, // S5_IN
|
||||
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8 }, // S6_IN
|
||||
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, 0, IOCFG_IPD, GPIO_AF9_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN 1
|
||||
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, 0, IOCFG_IPD, GPIO_AF9_TIM12, TIM_USE_PWM }, // S2_IN 2
|
||||
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, 0, IOCFG_IPD, GPIO_AF3_TIM8, TIM_USE_PWM }, // S3_IN 3
|
||||
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, 0, IOCFG_IPD, GPIO_AF3_TIM8, TIM_USE_PWM }, // S4_IN 4
|
||||
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, 0, IOCFG_IPD, GPIO_AF3_TIM8, TIM_USE_PWM }, // S6_IN 6
|
||||
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, 0, IOCFG_IPD, GPIO_AF3_TIM8, TIM_USE_PWM }, // S5_IN 5
|
||||
|
||||
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2 }, // S1_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM5 }, // S2_OUT
|
||||
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF3_TIM9 }, // S3_OUT
|
||||
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3 }, // S4_OUT
|
||||
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM4 }, // S5_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2 }, // S6_OUT
|
||||
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM5 }, // S7_OUT
|
||||
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2 }, // S8_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3 }, // S9_OUT
|
||||
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM4 }, // S10_OUT
|
||||
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S10_OUT16
|
||||
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S6_OUT 12
|
||||
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S5_OUT 11
|
||||
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S1_OUT 7
|
||||
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S2_OUT 8
|
||||
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, 1, IOCFG_AF_PP_PD, GPIO_AF3_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT 9
|
||||
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT 10
|
||||
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S7_OUT 13
|
||||
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S8_OUT 14
|
||||
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S9_OUT 15
|
||||
};
|
||||
|
||||
// ALTERNATE LAYOUT
|
||||
|
|
|
@ -21,89 +21,20 @@
|
|||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
//#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
//#include "drivers/timer_def.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
// Never used
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
//Never used
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM IN
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_PPM }, // PPM IN
|
||||
|
||||
// DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_INVERTED, 0), // M1 - DMA2_ST6
|
||||
// DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_INVERTED, 1), // M2 - DMA2_ST4
|
||||
// DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M3 - DMA1_ST6
|
||||
// DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M4 - DMA1_ST2
|
||||
// DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M5 - DMA1_ST4 (conflicts with SDCard, switch off SDCard DMA if used for DShot)
|
||||
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M6 - DMA2_ST3 (doesn't work for DShot)
|
||||
// DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M7 - DMA1_ST5 (doesn't work for DShot)
|
||||
// DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // M8 (no DMA, doesn't work for DShot)
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // M1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // M2
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M3
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M4
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M5
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M6
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M7
|
||||
{ TIM11, IO_TAG(PB9), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // M8
|
||||
|
||||
// DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED | TIM_USE_TRANSPONDER, TIMER_OUTPUT_STANDARD, 0), // LED_STRIP / TRANSPONDER - DMA1_ST7 (can be used for DShot, conflicts with OSD TX)
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // PPM IN
|
||||
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // M1
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // M2
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // M3
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // M4
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // M5
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // M6
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // M7
|
||||
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM11 }, // M8
|
||||
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4 }, // LED_STRIP / TRANSPONDER
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_LED }, // LED_STRIP / TRANSPONDER
|
||||
};
|
||||
|
|
|
@ -9,7 +9,7 @@ TARGET_SRC = \
|
|||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/max7456.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
# drivers/accgyro/accgyro_spi_icm20689.c \
|
||||
# drivers/transponder_ir.c \
|
||||
# io/transponder_ir.c
|
||||
|
|
|
@ -22,57 +22,14 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM IN
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S1_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S2_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S4_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_PPM }, // PPM IN
|
||||
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S2_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S5_OUT
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S6_OUT
|
||||
};
|
||||
|
||||
|
|
|
@ -12,5 +12,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
||||
|
|
|
@ -22,94 +22,26 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
#ifdef CC3D_PPM1
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
#else
|
||||
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
#endif
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
#ifdef CC3D_PPM1
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
#endif
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
#ifdef CC3D_PPM1
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
#else
|
||||
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
#endif
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
#ifdef CC3D_PPM1
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
#endif
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // S1_IN
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // S4_IN - Current
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // S5_IN - Vbattery
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // S6_IN - PPM IN
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP }, // S1_OUT
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP }, // S2_OUT
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP }, // S3_OUT
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP }, // S4_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP } // S6_OUT
|
||||
};
|
||||
#ifdef CC3D_PPM1
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
|
||||
#else
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S1_IN
|
||||
#endif
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S4_IN - Current
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S5_IN - Vbattery
|
||||
#ifdef CC3D_PPM1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, TIM_USE_PWM }, // S6_IN - PPM IN
|
||||
#else
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // S6_IN - PPM IN
|
||||
#endif
|
||||
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S5_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S6_OUT
|
||||
};
|
||||
|
|
|
@ -12,6 +12,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_mag3110.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
io/flashfs.c
|
||||
|
||||
|
|
|
@ -90,23 +90,24 @@ const uint16_t airPWM[] = {
|
|||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// INPUTS CH1-8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
|
||||
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM2 - PB8
|
||||
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM3 - PB9
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM4 - PC6
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM5 - PC7
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM6 - PC8
|
||||
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM7 - PF9
|
||||
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM8 - PF10
|
||||
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PD12
|
||||
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM10 - PD13
|
||||
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM11 - PD14
|
||||
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM12 - PD15
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM13 - PA1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM14 - PA2
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM15 - PA3
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM16 - PB0
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM17 - PB1
|
||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 } // PWM18 - PA4
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_6, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - PA8
|
||||
{ TIM16, IO_TAG(PB8), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_PWM }, // PWM2 - PB8
|
||||
{ TIM17, IO_TAG(PB9), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_PWM }, // PWM3 - PB9
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_4, TIM_USE_PWM }, // PWM4 - PC6
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_4, TIM_USE_PWM }, // PWM5 - PC7
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_4, TIM_USE_PWM }, // PWM6 - PC8
|
||||
{ TIM15, IO_TAG(PF9), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_3, TIM_USE_PWM }, // PWM7 - PF9
|
||||
{ TIM15, IO_TAG(PF10), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_3, TIM_USE_PWM }, // PWM8 - PF10
|
||||
|
||||
{ TIM4, IO_TAG(PD12), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - PD12
|
||||
{ TIM4, IO_TAG(PD13), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - PD13
|
||||
{ TIM4, IO_TAG(PD14), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - PD14
|
||||
{ TIM4, IO_TAG(PD15), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - PD15
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - PA1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM14 - PA2
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_ANY }, // PWM15 - PA3
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_ANY }, // PWM16 - PB0
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_ANY }, // PWM17 - PB1
|
||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_ANY } // PWM18 - PA4
|
||||
};
|
||||
|
||||
|
|
|
@ -54,19 +54,23 @@ const uint16_t airPWM[] = {
|
|||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_PWM }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11),TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_PWM }, // PWM10 - OUT2
|
||||
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM7 - RC7
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR } // PWM14 - OUT6
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM8 - RC8
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM13 - OUT5
|
||||
|
||||
/*
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD }, // PWM6 - RC6
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD }, // PWM12 - OUT4
|
||||
*/
|
||||
};
|
||||
|
||||
|
|
|
@ -23,102 +23,22 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM1 }, // S1_IN
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S2_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S3_IN
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // S4_IN
|
||||
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM2 }, // S5_IN
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM2 }, // S6_IN
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM5 }, // S7_IN
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM5 }, // S8_IN
|
||||
{ TIM1, IO_TAG(PA10), TIM_Channel_3, 0, IOCFG_IPD, GPIO_AF_TIM1, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_IPD, GPIO_AF_TIM8, TIM_USE_PWM }, // S2_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_IPD, GPIO_AF_TIM8, TIM_USE_PWM }, // S3_IN
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 0, IOCFG_IPD, GPIO_AF_TIM8, TIM_USE_PWM }, // S4_IN
|
||||
{ TIM2, IO_TAG(PA15), TIM_Channel_1, 0, IOCFG_IPD, GPIO_AF_TIM2, TIM_USE_PWM }, // S5_IN
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, 0, IOCFG_IPD, GPIO_AF_TIM2, TIM_USE_PWM }, // S6_IN
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, GPIO_AF_TIM5, TIM_USE_PWM }, // S7_IN
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, GPIO_AF_TIM5, TIM_USE_PWM }, // S8_IN
|
||||
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S1_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S2_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S3_OUT
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S4_OUT
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // S5_OUT
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12 }, // S6_OUT
|
||||
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM10 }, // S7_OUT
|
||||
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM11 }, // S8_OUT
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S1_OUT
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S2_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S5_OUT
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S6_OUT
|
||||
{ TIM10, IO_TAG(PB8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // S7_OUT
|
||||
{ TIM11, IO_TAG(PB9), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // S8_OUT
|
||||
};
|
||||
|
|
|
@ -22,57 +22,17 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7
|
||||
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8
|
||||
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3
|
||||
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14
|
||||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_6, TIM_USE_PPM }, // PWM1 - PA8
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PWM2 - PC6
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PWM3 - PC7
|
||||
{ TIM3, IO_TAG(PC8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PMW4 - PC8
|
||||
{ TIM3, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PWM5 - PC9
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM6 - PA0
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM7 - PA1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM8 - PA2
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM9 - PA3
|
||||
{ TIM15, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM10 - PB14
|
||||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM11 - PB15
|
||||
};
|
||||
|
||||
|
|
|
@ -12,5 +12,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_ak8975.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
||||
|
|
|
@ -22,86 +22,20 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
};
|
||||
|
||||
|
|
|
@ -23,5 +23,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
||||
|
|
|
@ -5,104 +5,25 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
|
||||
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
|
||||
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
|
||||
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
|
||||
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
|
||||
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
|
||||
{ TIM3, IO_TAG(PC9), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
|
||||
{ TIM3, IO_TAG(PC8), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_PWM }, // S2_IN
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_PWM }, // S3_IN
|
||||
{ TIM3, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_PWM }, // S4_IN
|
||||
{ TIM4, IO_TAG(PD15), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_PWM }, // S5_IN
|
||||
{ TIM4, IO_TAG(PD14), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_PWM }, // S6_IN
|
||||
{ TIM4, IO_TAG(PD13), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_PWM }, // S7_IN
|
||||
{ TIM4, IO_TAG(PD12), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_PWM }, // S8_IN
|
||||
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
|
||||
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
|
||||
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
|
||||
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
|
||||
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
|
||||
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
|
||||
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S1_OUT
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S2_OUT
|
||||
{ TIM5, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
||||
{ TIM5, IO_TAG(PA3), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S4_OUT
|
||||
{ TIM1, IO_TAG(PE9), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S5_OUT
|
||||
{ TIM1, IO_TAG(PE11), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S6_OUT
|
||||
{ TIM1, IO_TAG(PE13), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S7_OUT
|
||||
{ TIM1, IO_TAG(PE14), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S8_OUT
|
||||
|
||||
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
|
||||
{ TIM9, IO_TAG(PE6), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_ANY }, // sonar echo if needed
|
||||
};
|
||||
|
||||
|
|
|
@ -22,90 +22,21 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_AF_PP , GPIO_AF_TIM5 }, // S1_IN(PPM)
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_AF_PP , GPIO_AF_TIM5 }, // S2_IN
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP , GPIO_AF_TIM3 }, // S3_IN
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP , GPIO_AF_TIM2 }, // S4_IN
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP , GPIO_AF_TIM2 }, // S5_IN
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn,0, IOCFG_AF_PP , GPIO_AF_TIM1 }, // S6_IN
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP , GPIO_AF_TIM5, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN(PPM)
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP , GPIO_AF_TIM5, TIM_USE_PWM }, // S2_IN
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP , GPIO_AF_TIM3, TIM_USE_PWM }, // S3_IN
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, 0, IOCFG_AF_PP , GPIO_AF_TIM2, TIM_USE_PWM }, // S4_IN
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, 0, IOCFG_AF_PP , GPIO_AF_TIM2, TIM_USE_PWM }, // S5_IN
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 0, IOCFG_AF_PP , GPIO_AF_TIM1, TIM_USE_PWM }, // S6_IN
|
||||
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn,1, IOCFG_AF_PP, GPIO_AF_TIM12 },// S1_OUT
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn,1, IOCFG_AF_PP, GPIO_AF_TIM12 },// S2_OUT
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_OUT
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_OUT
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_OUT
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S6_OUT
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM12, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR },// S1_OUT
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM12, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR },// S2_OUT
|
||||
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S5_OUT
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S6_OUT
|
||||
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF_TIM3 }, // LED_STRIP
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP , GPIO_AF_TIM3, TIM_USE_LED }, // LED_STRIP
|
||||
};
|
||||
|
||||
|
|
|
@ -11,5 +11,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_ak8963.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c\
|
||||
drivers/light_ws2811strip_stdperiph.c\
|
||||
drivers/max7456.c
|
||||
|
|
|
@ -7,62 +7,17 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PPM IN
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
{ TIM2, IO_TAG(PB3), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PPM | TIM_USE_PWM }, // PPM IN
|
||||
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM4 - S1
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - S2
|
||||
{ TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3
|
||||
{ TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM7 - S4
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PWM4 - S1
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR }, // PWM5 - S2
|
||||
{ TIM17, IO_TAG(PB5), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR }, // PWM6 - S3
|
||||
{ TIM16, IO_TAG(PB4), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR }, // PWM7 - S4
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // GPIO TIMER - LED_STRIP
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_MOTOR }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_MOTOR }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_ANY }, // GPIO TIMER - LED_STRIP
|
||||
|
||||
};
|
||||
|
|
|
@ -13,6 +13,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/serial_softserial.c
|
||||
|
||||
|
|
|
@ -22,76 +22,16 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8 }, // PPM IN
|
||||
{TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM4
|
||||
{TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM2
|
||||
{TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM3
|
||||
{TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5 }, // PWM1
|
||||
{TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // PWM5
|
||||
{TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3 }, // PWM6
|
||||
{TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4 }, // PWM7
|
||||
{TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4 }, // PWM8
|
||||
{TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12}, // PWM9
|
||||
{TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12}, // PWM10
|
||||
{TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PPM }, // PPM IN
|
||||
{TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR }, // PWM2
|
||||
{TIM5, IO_TAG(PA3), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR }, // PWM3
|
||||
{TIM5, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR }, // PWM4
|
||||
{TIM5, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR }, // PWM5
|
||||
{TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR }, // PWM6
|
||||
{TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR }, // PWM7
|
||||
{TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4, TIM_USE_MC_MOTOR }, // PWM8
|
||||
{TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4, TIM_USE_MC_MOTOR }, // PWM9
|
||||
{TIM12, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_MOTOR }, // PWM10
|
||||
{TIM12, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_MOTOR }, // PWM11
|
||||
};
|
||||
|
|
|
@ -8,4 +8,4 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/max7456.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
|
@ -22,86 +22,21 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM}, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM8 - RC8
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
};
|
||||
|
||||
|
|
|
@ -172,7 +172,6 @@
|
|||
#define NAV_GPS_GLITCH_DETECTION
|
||||
|
||||
//#define LED_STRIP
|
||||
#define WS2811_TIMER TIM3
|
||||
#define WS2811_PIN PA6
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
||||
|
|
|
@ -11,6 +11,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
io/flashfs.c \
|
||||
hardware_revision.c
|
||||
|
|
|
@ -22,78 +22,18 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM IN
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S2_IN
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_IN
|
||||
{ TIM8, IO_TAG(PC7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_PPM | TIM_USE_PWM}, // PPM IN
|
||||
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_TIM12, TIM_USE_PWM}, // S2_IN
|
||||
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM12, TIM_USE_PWM}, // S3_IN - GPIO_PartialRemap_TIM3
|
||||
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_PWM}, // S4_IN
|
||||
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_PWM}, // S5_IN
|
||||
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S3_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S1_OUT
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR}, // S2_OUT
|
||||
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S3_OUT
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S4_OUT
|
||||
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S5_OUT - GPIO_PartialRemap_TIM3
|
||||
{ TIM5, IO_TAG(PA0), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO}, // S6_OUT
|
||||
};
|
||||
|
||||
|
|
|
@ -13,5 +13,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
||||
|
|
|
@ -22,101 +22,26 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t airPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
|
||||
PWM2 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PPM | TIM_USE_PWM }, // RC_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM}, // RC_CH2
|
||||
|
||||
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11
|
||||
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9
|
||||
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2
|
||||
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // RC_CH3
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // RC_CH4
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // RC_CH5
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // RC_CH6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // RC_CH7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // RC_CH8
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
|
||||
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM1
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM2
|
||||
{ TIM4, IO_TAG(PA11), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM3
|
||||
{ TIM4, IO_TAG(PA12), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6
|
||||
{ TIM15, IO_TAG(PA2), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM7
|
||||
{ TIM15, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM8
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_LED }, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
||||
|
|
|
@ -92,12 +92,8 @@
|
|||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define LED_STRIP
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_PIN PA8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define WS2811_DMA_STREAM DMA1_Channel2
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define SONAR
|
||||
|
|
|
@ -11,5 +11,5 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/serial_softserial.c
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue