diff --git a/Makefile b/Makefile index d234823bce..c6ccb2b20f 100644 --- a/Makefile +++ b/Makefile @@ -158,6 +158,10 @@ else STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S endif +ifeq ($(DEBUG_HARDFAULTS),F7) +CFLAGS += -DDEBUG_HARDFAULTS +endif + REVISION = $(shell git log -1 --format="%h") FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' ) @@ -364,7 +368,7 @@ endif ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS))) -DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT -DDEBUG_HARDFAULTS +DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld else $(error Unknown MCU for F7 target) @@ -557,7 +561,7 @@ HIGHEND_SRC = \ flight/gps_conversion.c \ io/gps.c \ io/ledstrip.c \ - io/display.c \ + io/dashboard.c \ sensors/sonar.c \ sensors/barometer.c \ telemetry/telemetry.c \ @@ -650,7 +654,7 @@ STM32F7xx_COMMON_SRC = \ drivers/pwm_output_hal.c \ drivers/system_stm32f7xx.c \ drivers/serial_uart_stm32f7xx.c \ - drivers/serial_uart_hal.c + drivers/serial_uart_hal.c F7EXCLUDES = drivers/bus_spi.c \ drivers/bus_i2c.c \ @@ -730,7 +734,11 @@ OPTIMIZE = -O0 LTO_FLAGS = $(OPTIMIZE) else OPTIMIZE = -Os +ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +else +LTO_FLAGS = -fuse-linker-plugin $(OPTIMIZE) +endif endif DEBUG_FLAGS = -ggdb3 -DDEBUG diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 98d82919e4..6fdf6e5c59 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -75,7 +75,7 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh const float cs = cosf(omega); const float alpha = sn / (2 * Q); - float b0, b1, b2, a0, a1, a2; + float b0 = 0, b1 = 0, b2 = 0, a0 = 0, a1 = 0, a2 = 0; switch (filterType) { case FILTER_LPF: diff --git a/src/main/drivers/accgyro_spi_icm20689.c b/src/main/drivers/accgyro_spi_icm20689.c index 648d3bd939..6458d2f510 100644 --- a/src/main/drivers/accgyro_spi_icm20689.c +++ b/src/main/drivers/accgyro_spi_icm20689.c @@ -73,7 +73,7 @@ static void icm20689SpiInit(void) IOInit(icmSpi20689CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(icmSpi20689CsPin, SPI_IO_CS_CFG); - spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD); hardwareInitialised = true; } @@ -101,7 +101,7 @@ bool icm20689SpiDetect(void) } } while (attemptsRemaining--); - spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD); return true; @@ -175,6 +175,6 @@ void icm20689GyroInit(uint8_t lpf) mpuConfiguration.write(MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable #endif - spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD); } diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index b4d4cfaa49..db41a01c7a 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -56,6 +56,12 @@ void EXTIInit(void) #if defined(STM32F3) || defined(STM32F4) /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); +#ifdef REMAP_TIM16_DMA + SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM16, ENABLE); +#endif +#ifdef REMAP_TIM17_DMA + SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, ENABLE); +#endif #endif memset(extiChannelRecs, 0, sizeof(extiChannelRecs)); memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority)); diff --git a/src/main/drivers/light_ws2811strip_hal.c b/src/main/drivers/light_ws2811strip_hal.c index a9e6061bba..28bafabbf7 100644 --- a/src/main/drivers/light_ws2811strip_hal.c +++ b/src/main/drivers/light_ws2811strip_hal.c @@ -85,7 +85,7 @@ void ws2811LedStripHardwareInit(void) __DMA1_CLK_ENABLE(); - + /* Set the parameters to be configured */ hdma_tim.Init.Channel = WS2811_DMA_CHANNEL; hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; @@ -103,23 +103,18 @@ void ws2811LedStripHardwareInit(void) /* Set hdma_tim instance */ hdma_tim.Instance = WS2811_DMA_STREAM; - uint32_t channelAddress = 0; switch (WS2811_TIMER_CHANNEL) { case TIM_CHANNEL_1: timDMASource = TIM_DMA_ID_CC1; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); break; case TIM_CHANNEL_2: timDMASource = TIM_DMA_ID_CC2; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); break; case TIM_CHANNEL_3: timDMASource = TIM_DMA_ID_CC3; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); break; case TIM_CHANNEL_4: timDMASource = TIM_DMA_ID_CC4; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); break; } diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 46f082a1dc..ea28c3e48e 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -156,7 +156,7 @@ void pwmCompleteMotorUpdate(uint8_t motorCount) void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount) { - uint32_t timerMhzCounter; + uint32_t timerMhzCounter = 0; pwmWriteFuncPtr pwmWritePtr; bool useUnsyncedPwm = motorConfig->useUnsyncedPwm; bool isDigital = false; @@ -208,7 +208,7 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot break; } - const timerHardware_t *timerHardware = timerGetByTag(tag, TIMER_OUTPUT_ENABLED); + const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_MOTOR); if (timerHardware == NULL) { /* flag failure and disable ability to arm */ @@ -271,7 +271,7 @@ void servoInit(const servoConfig_t *servoConfig) IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_OUTPUT, RESOURCE_INDEX(servoIndex)); IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP); - const timerHardware_t *timer = timerGetByTag(tag, TIMER_OUTPUT_ENABLED); + const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_SERVO); if (timer == NULL) { /* flag failure and disable ability to arm */ diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 53a0a7fc4b..4aa48905ae 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -71,7 +71,7 @@ typedef struct { #endif #if defined(STM32F7) TIM_HandleTypeDef TimHandle; - uint32_t Channel; + DMA_HandleTypeDef hdma_tim; #endif } motorDmaOutput_t; diff --git a/src/main/drivers/pwm_output_hal.c b/src/main/drivers/pwm_output_hal.c index 290b386007..5e3dd4a05c 100644 --- a/src/main/drivers/pwm_output_hal.c +++ b/src/main/drivers/pwm_output_hal.c @@ -202,6 +202,7 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot break; #ifdef USE_DSHOT case PWM_TYPE_DSHOT600: + case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT150: pwmCompleteWritePtr = pwmCompleteDigitalMotorUpdate; isDigital = true; diff --git a/src/main/drivers/pwm_output_stm32f3xx.c b/src/main/drivers/pwm_output_stm32f3xx.c index 80903ce19f..e72e03234c 100644 --- a/src/main/drivers/pwm_output_stm32f3xx.c +++ b/src/main/drivers/pwm_output_stm32f3xx.c @@ -84,7 +84,7 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount) { UNUSED(motorCount); - for (uint8_t i = 0; i < dmaMotorTimerCount; i++) { + for (int i = 0; i < dmaMotorTimerCount; i++) { TIM_SetCounter(dmaMotorTimers[i].timer, 0); TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE); } @@ -123,18 +123,18 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t RCC_ClockCmd(timerRCC(timer), ENABLE); TIM_Cmd(timer, DISABLE); - uint32_t hz; - switch (pwmProtocolType) { - case(PWM_TYPE_DSHOT600): - hz = MOTOR_DSHOT600_MHZ * 1000000; - break; - case(PWM_TYPE_DSHOT300): - hz = MOTOR_DSHOT300_MHZ * 1000000; - break; - default: - case(PWM_TYPE_DSHOT150): - hz = MOTOR_DSHOT150_MHZ * 1000000; - } + uint32_t hz; + switch (pwmProtocolType) { + case(PWM_TYPE_DSHOT600): + hz = MOTOR_DSHOT600_MHZ * 1000000; + break; + case(PWM_TYPE_DSHOT300): + hz = MOTOR_DSHOT300_MHZ * 1000000; + break; + default: + case(PWM_TYPE_DSHOT150): + hz = MOTOR_DSHOT150_MHZ * 1000000; + } TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1); TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH; @@ -146,20 +146,15 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { - TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable; TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; - TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset; - TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_Low; - TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_Low; + TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low; } else { TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; - TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; - 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_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); diff --git a/src/main/drivers/pwm_output_stm32f4xx.c b/src/main/drivers/pwm_output_stm32f4xx.c index 7e60c62f1d..d2bf798187 100644 --- a/src/main/drivers/pwm_output_stm32f4xx.c +++ b/src/main/drivers/pwm_output_stm32f4xx.c @@ -85,7 +85,7 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount) { UNUSED(motorCount); - for (uint8_t i = 0; i < dmaMotorTimerCount; i++) { + for (int i = 0; i < dmaMotorTimerCount; i++) { TIM_SetCounter(dmaMotorTimers[i].timer, 0); TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE); } @@ -124,18 +124,18 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t RCC_ClockCmd(timerRCC(timer), ENABLE); TIM_Cmd(timer, DISABLE); - uint32_t hz; - switch (pwmProtocolType) { - case(PWM_TYPE_DSHOT600): - hz = MOTOR_DSHOT600_MHZ * 1000000; - break; - case(PWM_TYPE_DSHOT300): - hz = MOTOR_DSHOT300_MHZ * 1000000; - break; - default: - case(PWM_TYPE_DSHOT150): - hz = MOTOR_DSHOT150_MHZ * 1000000; - } + uint32_t hz; + switch (pwmProtocolType) { + case(PWM_TYPE_DSHOT600): + hz = MOTOR_DSHOT600_MHZ * 1000000; + break; + case(PWM_TYPE_DSHOT300): + hz = MOTOR_DSHOT300_MHZ * 1000000; + break; + default: + case(PWM_TYPE_DSHOT150): + hz = MOTOR_DSHOT150_MHZ * 1000000; + } TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1; TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH; @@ -145,12 +145,15 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t } 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; + if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; + TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset; + TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low; + } 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); diff --git a/src/main/drivers/pwm_output_stm32f7xx.c b/src/main/drivers/pwm_output_stm32f7xx.c index 523b993df2..d2b7842435 100644 --- a/src/main/drivers/pwm_output_stm32f7xx.c +++ b/src/main/drivers/pwm_output_stm32f7xx.c @@ -175,23 +175,20 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t } dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource; - - static DMA_HandleTypeDef hdma_tim; - /* Set the parameters to be configured */ - hdma_tim.Init.Channel = timerHardware->dmaChannel; - hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; - hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE; - hdma_tim.Init.MemInc = DMA_MINC_ENABLE; - hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ; - hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ; - hdma_tim.Init.Mode = DMA_NORMAL; - hdma_tim.Init.Priority = DMA_PRIORITY_HIGH; - hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; - hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; - hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; + motor->hdma_tim.Init.Channel = timerHardware->dmaChannel; + motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; + motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE; + motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE; + motor->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ; + motor->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ; + motor->hdma_tim.Init.Mode = DMA_NORMAL; + motor->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH; + motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + motor->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; + motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; /* Set hdma_tim instance */ if(timerHardware->dmaStream == NULL) @@ -199,10 +196,10 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t /* Initialization Error */ return; } - hdma_tim.Instance = timerHardware->dmaStream; + motor->hdma_tim.Instance = timerHardware->dmaStream; /* Link hdma_tim to hdma[x] (channelx) */ - __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], hdma_tim); + __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim); dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index f055683976..13f074fad1 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -393,7 +393,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig) pwmInputPort_t *port = &pwmInputPorts[channel]; - const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIMER_INPUT_ENABLED); + const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_PWM); if (!timer) { /* TODO: maybe fail here if not enough channels? */ @@ -408,7 +408,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig) IO_t io = IOGetByTag(pwmConfig->ioTags[channel]); IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); - IOConfigGPIO(io, timer->ioMode); + IOConfigGPIO(io, IOCFG_IPD); #if defined(USE_HAL_DRIVER) pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING); @@ -459,7 +459,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol) pwmInputPort_t *port = &pwmInputPorts[FIRST_PWM_PORT]; - const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIMER_INPUT_ENABLED); + const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIM_USE_PPM); if (!timer) { /* TODO: fail here? */ return; @@ -472,7 +472,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol) IO_t io = IOGetByTag(ppmConfig->ioTag); IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); - IOConfigGPIO(io, timer->ioMode); + IOConfigGPIO(io, IOCFG_IPD); #if defined(USE_HAL_DRIVER) pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING); diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/serial_uart_hal.c index 8fc2573293..0a00d2aacc 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -57,7 +57,6 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) { static void uartReconfigure(uartPort_t *uartPort) { - HAL_StatusTypeDef status = HAL_ERROR; /*RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit; RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3| RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_USART6|RCC_PERIPHCLK_UART7|RCC_PERIPHCLK_UART8; @@ -90,11 +89,11 @@ static void uartReconfigure(uartPort_t *uartPort) if(uartPort->port.options & SERIAL_BIDIR) { - status = HAL_HalfDuplex_Init(&uartPort->Handle); + HAL_HalfDuplex_Init(&uartPort->Handle); } else { - status = HAL_UART_Init(&uartPort->Handle); + HAL_UART_Init(&uartPort->Handle); } // Receive DMA or IRQ @@ -216,7 +215,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, s->txDMAEmpty = true; - + // common serial initialisation code should move to serialPort::init() s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.txBufferHead = s->port.txBufferTail = 0; @@ -252,7 +251,7 @@ void uartStartTxDMA(uartPort_t *s) HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle); if((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX) return; - + if (s->port.txBufferHead > s->port.txBufferTail) { size = s->port.txBufferHead - s->port.txBufferTail; fromwhere = s->port.txBufferTail; @@ -387,4 +386,3 @@ const struct serialPortVTable uartVTable[] = { .endWrite = NULL, } }; - diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 5514b16ec8..41b222fd1b 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -99,6 +99,7 @@ static uartPort_t uartPort4; static uartPort_t uartPort5; #endif +#if defined(USE_UART1_TX_DMA) || defined(USE_UART2_TX_DMA) || defined(USE_UART3_TX_DMA) static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) { uartPort_t *s = (uartPort_t*)(descriptor->userParam); @@ -110,6 +111,7 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) else s->txDMAEmpty = true; } +#endif void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) { @@ -150,29 +152,33 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option s->port.baudRate = baudRate; - s->port.rxBuffer = rx1Buffer; - s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; - -#ifdef USE_UART1_RX_DMA - s->rxDMAChannel = DMA1_Channel5; -#endif -#ifdef USE_UART1_TX_DMA - s->txDMAChannel = DMA1_Channel4; -#endif + s->port.rxBuffer = rx1Buffer; + s->port.txBuffer = tx1Buffer; s->USARTx = USART1; +#ifdef USE_UART1_RX_DMA + s->rxDMAChannel = DMA1_Channel5; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; +#endif +#ifdef USE_UART1_TX_DMA + s->txDMAChannel = DMA1_Channel4; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; +#endif RCC_ClockCmd(RCC_APB2(USART1), ENABLE); + +#if defined(USE_UART1_TX_DMA) || defined(USE_UART1_RX_DMA) RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); +#endif serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1); +#ifdef USE_UART1_TX_DMA dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1); +#endif #ifndef USE_UART1_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 7dfef2033f..77096a1cb7 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -199,7 +199,7 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel) rccPeriphTag_t timerRCC(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].rcc; } @@ -686,14 +686,14 @@ 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); + IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), IOCFG_AF_PP, timerHardwarePtr->alternateFunction); } #endif @@ -755,14 +755,11 @@ void timerForceOverflow(TIM_TypeDef *tim) } } -const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag) +const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag) { - for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { + for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { if (timerHardware[i].tag == tag) { - if (flag && (timerHardware[i].output & flag) == flag) { - return &timerHardware[i]; - } else if (!flag && timerHardware[i].output == flag) { - // TODO: shift flag by one so not to be 0 + if (timerHardware[i].usageFlags & flag) { return &timerHardware[i]; } } diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index cf4d12b220..9a86a92101 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -54,6 +54,13 @@ typedef uint32_t timCNT_t; #error "Unknown CPU defined" #endif +typedef enum { + TIM_USE_PPM = 0x1, + TIM_USE_PWM = 0x2, + TIM_USE_MOTOR = 0x4, + TIM_USE_SERVO = 0x8, + TIM_USE_LED = 0x10 +} timerUsageFlag_e; // use different types from capture and overflow - multiple overflow handlers are implemented as linked list struct timerCCHandlerRec_s; @@ -80,8 +87,8 @@ typedef struct timerHardware_s { ioTag_t tag; uint8_t channel; uint8_t irq; + timerUsageFlag_e usageFlags; uint8_t output; - ioConfig_t ioMode; #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) uint8_t alternateFunction; #endif @@ -171,7 +178,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - rccPeriphTag_t timerRCC(TIM_TypeDef *tim); -const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag); +const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag); #if defined(USE_HAL_DRIVER) TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim); diff --git a/src/main/drivers/timer_hal.c b/src/main/drivers/timer_hal.c index 05c01a5210..8268bd3497 100644 --- a/src/main/drivers/timer_hal.c +++ b/src/main/drivers/timer_hal.c @@ -208,7 +208,7 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel) rccPeriphTag_t timerRCC(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].rcc; } @@ -787,14 +787,14 @@ 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) || defined(STM32F7) - 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); + IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), IOCFG_AF_PP, timerHardwarePtr->alternateFunction); } #endif @@ -856,16 +856,13 @@ void timerForceOverflow(TIM_TypeDef *tim) } } -const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag) +const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag) { - for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { + for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { if (timerHardware[i].tag == tag) { - if (flag && (timerHardware[i].output & flag) == flag) { + if (timerHardware[i].output & flag) { return &timerHardware[i]; - } else if (!flag && timerHardware[i].output == flag) { - // TODO: shift flag by one so not to be 0 - return &timerHardware[i]; - } + } } } return NULL; diff --git a/src/main/drivers/timer_stm32f7xx.c b/src/main/drivers/timer_stm32f7xx.c index 180116c0fd..e9992d9b19 100644 --- a/src/main/drivers/timer_stm32f7xx.c +++ b/src/main/drivers/timer_stm32f7xx.c @@ -96,6 +96,7 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { uint8_t timerClockDivisor(TIM_TypeDef *tim) { + UNUSED(tim); return 1; } diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3a3ca159d3..1e69c557ed 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -244,6 +244,14 @@ void resetServoConfig(servoConfig_t *servoConfig) { servoConfig->servoCenterPulse = 1500; servoConfig->servoPwmRate = 50; + + int servoIndex = 0; + for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) { + if (timerHardware[i].usageFlags & TIM_USE_SERVO) { + servoConfig->ioTags[servoIndex] = timerHardware[i].tag; + servoIndex++; + } + } } #endif @@ -263,9 +271,9 @@ void resetMotorConfig(motorConfig_t *motorConfig) motorConfig->mincommand = 1000; motorConfig->digitalIdleOffset = 40; - uint8_t motorIndex = 0; - for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && i < MAX_SUPPORTED_MOTORS; i++) { - if ((timerHardware[i].output & TIMER_OUTPUT_ENABLED) == TIMER_OUTPUT_ENABLED) { + int motorIndex = 0; + for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) { + if (timerHardware[i].usageFlags & TIM_USE_MOTOR) { motorConfig->ioTags[motorIndex] = timerHardware[i].tag; motorIndex++; } @@ -305,7 +313,7 @@ void resetPpmConfig(ppmConfig_t *ppmConfig) ppmConfig->ioTag = IO_TAG(PPM_PIN); #else for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { - if ((timerHardware[i].output == TIMER_INPUT_ENABLED)) { + if (timerHardware[i].usageFlags & TIM_USE_PPM) { ppmConfig->ioTag = timerHardware[i].tag; return; } @@ -317,9 +325,9 @@ void resetPpmConfig(ppmConfig_t *ppmConfig) void resetPwmConfig(pwmConfig_t *pwmConfig) { - uint8_t inputIndex = 0; + int inputIndex = 0; for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) { - if ((timerHardware[i].output == TIMER_INPUT_ENABLED)) { + if (timerHardware[i].usageFlags & TIM_USE_PWM) { pwmConfig->ioTags[inputIndex] = timerHardware[i].tag; inputIndex++; } @@ -896,8 +904,8 @@ void validateAndFixConfig(void) #endif #if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3) - if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) { - featureClear(FEATURE_DISPLAY); + if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) { + featureClear(FEATURE_DASHBOARD); } #endif diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 60c2f517c6..5da0c5b53b 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -45,7 +45,7 @@ typedef enum { FEATURE_RX_MSP = 1 << 14, FEATURE_RSSI_ADC = 1 << 15, FEATURE_LED_STRIP = 1 << 16, - FEATURE_DISPLAY = 1 << 17, + FEATURE_DASHBOARD = 1 << 17, FEATURE_OSD = 1 << 18, FEATURE_BLACKBOX = 1 << 19, FEATURE_CHANNEL_FORWARDING = 1 << 20, diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 9a99de11b9..d9ca1c027e 100644 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -43,7 +43,7 @@ #include "io/cms.h" #include "io/beeper.h" -#include "io/display.h" +#include "io/dashboard.h" #include "io/gps.h" #include "io/ledstrip.h" #include "io/cms.h" @@ -225,11 +225,11 @@ static void taskCalculateAltitude(uint32_t currentTime) }} #endif -#ifdef DISPLAY -static void taskUpdateDisplay(uint32_t currentTime) +#ifdef USE_DASHBOARD +static void taskUpdateDashboard(uint32_t currentTime) { - if (feature(FEATURE_DISPLAY)) { - displayUpdate(currentTime); + if (feature(FEATURE_DASHBOARD)) { + dashboardUpdate(currentTime); } } #endif @@ -310,8 +310,8 @@ void fcTasksInit(void) #if defined(BARO) || defined(SONAR) setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)); #endif -#ifdef DISPLAY - setTaskEnabled(TASK_DISPLAY, feature(FEATURE_DISPLAY)); +#ifdef USE_DASHBOARD + setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD)); #endif #ifdef TELEMETRY setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY)); @@ -453,10 +453,10 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif -#ifdef DISPLAY - [TASK_DISPLAY] = { - .taskName = "DISPLAY", - .taskFunc = taskUpdateDisplay, +#ifdef USE_DASHBOARD + [TASK_DASHBOARD] = { + .taskName = "DASHBOARD", + .taskFunc = taskUpdateDashboard, .desiredPeriod = 1000000 / 10, .staticPriority = TASK_PRIORITY_LOW, }, diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 1d410a9435..016c4287ec 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -46,7 +46,7 @@ #include "io/beeper.h" #include "io/motors.h" #include "io/vtx.h" -#include "io/display.h" +#include "io/dashboard.h" #include "sensors/barometer.h" #include "sensors/battery.h" @@ -293,13 +293,13 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat return; } -#ifdef DISPLAY +#ifdef USE_DASHBOARD if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_LO) { - displayDisablePageCycling(); + dashboardDisablePageCycling(); } if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_HI) { - displayEnablePageCycling(); + dashboardEnablePageCycling(); } #endif diff --git a/src/main/io/cms.c b/src/main/io/cms.c index 7c74a777ea..74fce20a91 100644 --- a/src/main/io/cms.c +++ b/src/main/io/cms.c @@ -41,7 +41,7 @@ #include "io/flashfs.h" #include "io/osd.h" -#include "io/display.h" +#include "io/dashboard.h" #include "fc/config.h" #include "fc/rc_controls.h" @@ -178,7 +178,7 @@ void cmsScreenInit(displayPort_t *pDisp, cmsDeviceInitFuncPtr cmsDeviceInitFunc) // #define LEFT_MENU_COLUMN 1 -#define RIGHT_MENU_COLUMN(p) ((p)->cols - 10) +#define RIGHT_MENU_COLUMN(p) ((p)->cols - 8) #define MAX_MENU_ITEMS(p) ((p)->rows - 2) displayPort_t currentDisplay; diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c new file mode 100644 index 0000000000..eb34084ca5 --- /dev/null +++ b/src/main/io/dashboard.c @@ -0,0 +1,823 @@ +/* + * 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 . + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_DASHBOARD + +#include "common/utils.h" + +#include "build/version.h" +#include "build/debug.h" + +#include "build/build_config.h" + +#include "drivers/system.h" +#include "drivers/display_ug2864hsweg01.h" + +#include "common/printf.h" +#include "common/maths.h" +#include "common/axis.h" +#include "common/typeconversion.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/gyro.h" + +#include "fc/config.h" +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" + +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" + +#include "io/cms.h" + +#ifdef CMS +void dashboardCmsInit(displayPort_t *pPort); // Forward +#endif + +#ifdef GPS +#include "io/gps.h" +#include "flight/navigation.h" +#endif + +#include "config/feature.h" +#include "config/config_profile.h" + +#include "io/dashboard.h" + +#include "rx/rx.h" + +#include "scheduler/scheduler.h" + +extern profile_t *currentProfile; + +controlRateConfig_t *getControlRateConfig(uint8_t profileIndex); + +#define MICROSECONDS_IN_A_SECOND (1000 * 1000) + +#define DISPLAY_UPDATE_FREQUENCY (MICROSECONDS_IN_A_SECOND / 5) +#define PAGE_CYCLE_FREQUENCY (MICROSECONDS_IN_A_SECOND * 5) + +static uint32_t nextDisplayUpdateAt = 0; +static bool dashboardPresent = false; + +static rxConfig_t *rxConfig; + +#define PAGE_TITLE_LINE_COUNT 1 + +static char lineBuffer[SCREEN_CHARACTER_COLUMN_COUNT + 1]; + +#define HALF_SCREEN_CHARACTER_COLUMN_COUNT (SCREEN_CHARACTER_COLUMN_COUNT / 2) +#define IS_SCREEN_CHARACTER_COLUMN_COUNT_ODD (SCREEN_CHARACTER_COLUMN_COUNT & 1) + +static const char* const pageTitles[] = { + "CLEANFLIGHT", + "ARMED", + "BATTERY", + "SENSORS", + "RX", + "PROFILE" +#ifndef SKIP_TASK_STATISTICS + ,"TASKS" +#endif +#ifdef GPS + ,"GPS" +#endif +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE + ,"DEBUG" +#endif +}; + +#define PAGE_COUNT (PAGE_RX + 1) + +const pageId_e cyclePageIds[] = { + PAGE_PROFILE, +#ifdef GPS + PAGE_GPS, +#endif + PAGE_RX, + PAGE_BATTERY, + PAGE_SENSORS +#ifndef SKIP_TASK_STATISTICS + ,PAGE_TASKS +#endif +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE + ,PAGE_DEBUG, +#endif +}; + +#define CYCLE_PAGE_ID_COUNT (sizeof(cyclePageIds) / sizeof(cyclePageIds[0])) + +static const char* tickerCharacters = "|/-\\"; // use 2/4/8 characters so that the divide is optimal. +#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) / sizeof(char)) + +typedef enum { + PAGE_STATE_FLAG_NONE = 0, + PAGE_STATE_FLAG_CYCLE_ENABLED = (1 << 0), + PAGE_STATE_FLAG_FORCE_PAGE_CHANGE = (1 << 1) +} pageFlags_e; + +typedef struct pageState_s { + bool pageChanging; + pageId_e pageId; + pageId_e pageIdBeforeArming; + uint8_t pageFlags; + uint8_t cycleIndex; + uint32_t nextPageAt; +} pageState_t; + +static pageState_t pageState; + +void resetDisplay(void) { + dashboardPresent = ug2864hsweg01InitI2C(); +} + +void LCDprint(uint8_t i) { + i2c_OLED_send_char(i); +} + +void padLineBuffer(void) +{ + uint8_t length = strlen(lineBuffer); + while (length < sizeof(lineBuffer) - 1) { + lineBuffer[length++] = ' '; + } + lineBuffer[length] = 0; +} + +void padHalfLineBuffer(void) +{ + uint8_t halfLineIndex = sizeof(lineBuffer) / 2; + uint8_t length = strlen(lineBuffer); + while (length < halfLineIndex - 1) { + lineBuffer[length++] = ' '; + } + lineBuffer[length] = 0; +} + +// LCDbar(n,v) : draw a bar graph - n number of chars for width, v value in % to display +void drawHorizonalPercentageBar(uint8_t width,uint8_t percent) { + uint8_t i, j; + + if (percent > 100) + percent = 100; + + j = (width * percent) / 100; + + for (i = 0; i < j; i++) + LCDprint(159); // full + + if (j < width) + LCDprint(154 + (percent * width * 5 / 100 - 5 * j)); // partial fill + + for (i = j + 1; i < width; i++) + LCDprint(154); // empty +} + +#if 0 +void fillScreenWithCharacters() +{ + for (uint8_t row = 0; row < SCREEN_CHARACTER_ROW_COUNT; row++) { + for (uint8_t column = 0; column < SCREEN_CHARACTER_COLUMN_COUNT; column++) { + i2c_OLED_set_xy(column, row); + i2c_OLED_send_char('A' + column); + } + } +} +#endif + + +void updateTicker(void) +{ + static uint8_t tickerIndex = 0; + i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 1, 0); + i2c_OLED_send_char(tickerCharacters[tickerIndex]); + tickerIndex++; + tickerIndex = tickerIndex % TICKER_CHARACTER_COUNT; +} + +void updateRxStatus(void) +{ + i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 2, 0); + char rxStatus = '!'; + if (rxIsReceivingSignal()) { + rxStatus = 'r'; + } if (rxAreFlightChannelsValid()) { + rxStatus = 'R'; + } + i2c_OLED_send_char(rxStatus); +} + +void updateFailsafeStatus(void) +{ + char failsafeIndicator = '?'; + switch (failsafePhase()) { + case FAILSAFE_IDLE: + failsafeIndicator = '-'; + break; + case FAILSAFE_RX_LOSS_DETECTED: + failsafeIndicator = 'R'; + break; + case FAILSAFE_LANDING: + failsafeIndicator = 'l'; + break; + case FAILSAFE_LANDED: + failsafeIndicator = 'L'; + break; + case FAILSAFE_RX_LOSS_MONITORING: + failsafeIndicator = 'M'; + break; + case FAILSAFE_RX_LOSS_RECOVERED: + failsafeIndicator = 'r'; + break; + } + i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 3, 0); + i2c_OLED_send_char(failsafeIndicator); +} + +void showTitle() +{ + i2c_OLED_set_line(0); + i2c_OLED_send_string(pageTitles[pageState.pageId]); +} + +void handlePageChange(void) +{ + i2c_OLED_clear_display_quick(); + showTitle(); +} + +void drawRxChannel(uint8_t channelIndex, uint8_t width) +{ + uint32_t percentage; + + LCDprint(rcChannelLetters[channelIndex]); + + percentage = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); + drawHorizonalPercentageBar(width - 1, percentage); +} + +#define RX_CHANNELS_PER_PAGE_COUNT 14 +void showRxPage(void) +{ + + for (uint8_t channelIndex = 0; channelIndex < rxRuntimeConfig.channelCount && channelIndex < RX_CHANNELS_PER_PAGE_COUNT; channelIndex += 2) { + i2c_OLED_set_line((channelIndex / 2) + PAGE_TITLE_LINE_COUNT); + + drawRxChannel(channelIndex, HALF_SCREEN_CHARACTER_COLUMN_COUNT); + + if (channelIndex >= rxRuntimeConfig.channelCount) { + continue; + } + + if (IS_SCREEN_CHARACTER_COLUMN_COUNT_ODD) { + LCDprint(' '); + } + + drawRxChannel(channelIndex + PAGE_TITLE_LINE_COUNT, HALF_SCREEN_CHARACTER_COLUMN_COUNT); + } +} + +void showWelcomePage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + + tfp_sprintf(lineBuffer, "v%s (%s)", FC_VERSION_STRING, shortGitRevision); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(targetName); +} + +void showArmedPage(void) +{ +} + +void showProfilePage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + + tfp_sprintf(lineBuffer, "Profile: %d", getCurrentProfile()); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + static const char* const axisTitles[3] = {"ROL", "PIT", "YAW"}; + const pidProfile_t *pidProfile = ¤tProfile->pidProfile; + for (int axis = 0; axis < 3; ++axis) { + tfp_sprintf(lineBuffer, "%s P:%3d I:%3d D:%3d", + axisTitles[axis], + pidProfile->P8[axis], + pidProfile->I8[axis], + pidProfile->D8[axis] + ); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + } + + const uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); + tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + const controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); + tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d", + controlRateConfig->rcExpo8, + controlRateConfig->rcRate8 + ); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "RR:%d PR:%d YR:%d", + controlRateConfig->rates[FD_ROLL], + controlRateConfig->rates[FD_PITCH], + controlRateConfig->rates[FD_YAW] + ); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); +} +#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0])) +#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2) + +#ifdef GPS +void showGpsPage() { + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + + static uint8_t gpsTicker = 0; + static uint32_t lastGPSSvInfoReceivedCount = 0; + if (GPS_svInfoReceivedCount != lastGPSSvInfoReceivedCount) { + lastGPSSvInfoReceivedCount = GPS_svInfoReceivedCount; + gpsTicker++; + gpsTicker = gpsTicker % TICKER_CHARACTER_COUNT; + } + + i2c_OLED_set_xy(0, rowIndex); + i2c_OLED_send_char(tickerCharacters[gpsTicker]); + + i2c_OLED_set_xy(MAX(0, SATELLITE_GRAPH_LEFT_OFFSET), rowIndex++); + + uint32_t index; + for (index = 0; index < SATELLITE_COUNT && index < SCREEN_CHARACTER_COLUMN_COUNT; index++) { + uint8_t bargraphOffset = ((uint16_t) GPS_svinfo_cno[index] * VERTICAL_BARGRAPH_CHARACTER_COUNT) / (GPS_DBHZ_MAX - 1); + bargraphOffset = MIN(bargraphOffset, VERTICAL_BARGRAPH_CHARACTER_COUNT - 1); + i2c_OLED_send_char(VERTICAL_BARGRAPH_ZERO_CHARACTER + bargraphOffset); + } + + + char fixChar = STATE(GPS_FIX) ? 'Y' : 'N'; + tfp_sprintf(lineBuffer, "Sats: %d Fix: %c", GPS_numSat, fixChar); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "La/Lo: %d/%d", GPS_coord[LAT] / GPS_DEGREES_DIVIDER, GPS_coord[LON] / GPS_DEGREES_DIVIDER); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "Spd: %d", GPS_speed); + padHalfLineBuffer(); + i2c_OLED_set_line(rowIndex); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "GC: %d", GPS_ground_course); + padHalfLineBuffer(); + i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "RX: %d", GPS_packetCount); + padHalfLineBuffer(); + i2c_OLED_set_line(rowIndex); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "ERRs: %d", gpsData.errors, gpsData.timeouts); + padHalfLineBuffer(); + i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "Dt: %d", gpsData.lastMessage - gpsData.lastLastMessage); + padHalfLineBuffer(); + i2c_OLED_set_line(rowIndex); + i2c_OLED_send_string(lineBuffer); + + tfp_sprintf(lineBuffer, "TOs: %d", gpsData.timeouts); + padHalfLineBuffer(); + i2c_OLED_set_xy(HALF_SCREEN_CHARACTER_COLUMN_COUNT, rowIndex++); + i2c_OLED_send_string(lineBuffer); + + strncpy(lineBuffer, gpsPacketLog, GPS_PACKET_LOG_ENTRY_COUNT); + padHalfLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + +#ifdef GPS_PH_DEBUG + tfp_sprintf(lineBuffer, "Angles: P:%d R:%d", GPS_angle[PITCH], GPS_angle[ROLL]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); +#endif + +#if 0 + tfp_sprintf(lineBuffer, "%d %d %d %d", debug[0], debug[1], debug[2], debug[3]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); +#endif +} +#endif + +void showBatteryPage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + + if (feature(FEATURE_VBAT)) { + tfp_sprintf(lineBuffer, "Volts: %d.%1d Cells: %d", vbat / 10, vbat % 10, batteryCellCount); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + uint8_t batteryPercentage = calculateBatteryPercentage(); + i2c_OLED_set_line(rowIndex++); + drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, batteryPercentage); + } + + if (feature(FEATURE_CURRENT_METER)) { + tfp_sprintf(lineBuffer, "Amps: %d.%2d mAh: %d", amperage / 100, amperage % 100, mAhDrawn); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + uint8_t capacityPercentage = calculateBatteryCapacityRemainingPercentage(); + i2c_OLED_set_line(rowIndex++); + drawHorizonalPercentageBar(SCREEN_CHARACTER_COLUMN_COUNT, capacityPercentage); + } +} + +void showSensorsPage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + static const char *format = "%s %5d %5d %5d"; + + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(" X Y Z"); + + if (sensors(SENSOR_ACC)) { + tfp_sprintf(lineBuffer, format, "ACC", accSmooth[X], accSmooth[Y], accSmooth[Z]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + } + + if (sensors(SENSOR_GYRO)) { + tfp_sprintf(lineBuffer, format, "GYR", gyroADC[X], gyroADC[Y], gyroADC[Z]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + } + +#ifdef MAG + if (sensors(SENSOR_MAG)) { + tfp_sprintf(lineBuffer, format, "MAG", magADC[X], magADC[Y], magADC[Z]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + } +#endif + + tfp_sprintf(lineBuffer, format, "I&H", attitude.values.roll, attitude.values.pitch, DECIDEGREES_TO_DEGREES(attitude.values.yaw)); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + /* + uint8_t length; + + ftoa(EstG.A[X], lineBuffer); + length = strlen(lineBuffer); + while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) { + lineBuffer[length++] = ' '; + lineBuffer[length+1] = 0; + } + ftoa(EstG.A[Y], lineBuffer + length); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + + ftoa(EstG.A[Z], lineBuffer); + length = strlen(lineBuffer); + while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) { + lineBuffer[length++] = ' '; + lineBuffer[length+1] = 0; + } + ftoa(smallAngle, lineBuffer + length); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + */ + +} + +#ifndef SKIP_TASK_STATISTICS +void showTasksPage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + static const char *format = "%2d%6d%5d%4d%4d"; + + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string("Task max avg mx% av%"); + cfTaskInfo_t taskInfo; + for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; ++taskId) { + getTaskInfo(taskId, &taskInfo); + if (taskInfo.isEnabled && taskId != TASK_SERIAL) {// don't waste a line of the display showing serial taskInfo + const int taskFrequency = (int)(1000000.0f / ((float)taskInfo.latestDeltaTime)); + const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 10000; + const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 10000; + tfp_sprintf(lineBuffer, format, taskId, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, maxLoad, averageLoad); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + if (rowIndex > SCREEN_CHARACTER_ROW_COUNT) { + break; + } + } + } +} +#endif + +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE + +void showDebugPage(void) +{ + uint8_t rowIndex; + + for (rowIndex = 0; rowIndex < 4; rowIndex++) { + tfp_sprintf(lineBuffer, "%d = %5d", rowIndex, debug[rowIndex]); + padLineBuffer(); + i2c_OLED_set_line(rowIndex + PAGE_TITLE_LINE_COUNT); + i2c_OLED_send_string(lineBuffer); + } +} +#endif + +#ifdef OLEDCMS +static bool dashboardInCMS = false; +#endif + +void dashboardUpdate(uint32_t currentTime) +{ + static uint8_t previousArmedState = 0; + +#ifdef OLEDCMS + if (dashboardInCMS) + return; +#endif + + const bool updateNow = (int32_t)(currentTime - nextDisplayUpdateAt) >= 0L; + if (!updateNow) { + return; + } + + nextDisplayUpdateAt = currentTime + DISPLAY_UPDATE_FREQUENCY; + + bool armedState = ARMING_FLAG(ARMED) ? true : false; + bool armedStateChanged = armedState != previousArmedState; + previousArmedState = armedState; + + if (armedState) { + if (!armedStateChanged) { + return; + } + pageState.pageIdBeforeArming = pageState.pageId; + pageState.pageId = PAGE_ARMED; + pageState.pageChanging = true; + } else { + if (armedStateChanged) { + pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; + pageState.pageId = pageState.pageIdBeforeArming; + } + + pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) || + (((int32_t)(currentTime - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED))); + if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) { + pageState.cycleIndex++; + pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT; + pageState.pageId = cyclePageIds[pageState.cycleIndex]; + } + } + + if (pageState.pageChanging) { + pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; + pageState.nextPageAt = currentTime + PAGE_CYCLE_FREQUENCY; + + // Some OLED displays do not respond on the first initialisation so refresh the display + // when the page changes in the hopes the hardware responds. This also allows the + // user to power off/on the display or connect it while powered. + resetDisplay(); + + if (!dashboardPresent) { + return; + } + handlePageChange(); + } + + if (!dashboardPresent) { + return; + } + + switch(pageState.pageId) { + case PAGE_WELCOME: + showWelcomePage(); + break; + case PAGE_ARMED: + showArmedPage(); + break; + case PAGE_BATTERY: + showBatteryPage(); + break; + case PAGE_SENSORS: + showSensorsPage(); + break; + case PAGE_RX: + showRxPage(); + break; + case PAGE_PROFILE: + showProfilePage(); + break; +#ifndef SKIP_TASK_STATISTICS + case PAGE_TASKS: + showTasksPage(); + break; +#endif +#ifdef GPS + case PAGE_GPS: + if (feature(FEATURE_GPS)) { + showGpsPage(); + } else { + pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; + } + break; +#endif +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE + case PAGE_DEBUG: + showDebugPage(); + break; +#endif + } + if (!armedState) { + updateFailsafeStatus(); + updateRxStatus(); + updateTicker(); + } + +} + +void dashboardSetPage(pageId_e pageId) +{ + pageState.pageId = pageId; + pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; +} + +void dashboardInit(rxConfig_t *rxConfigToUse) +{ + delay(200); + resetDisplay(); + delay(200); + +#if defined(CMS) && defined(OLEDCMS) + cmsDeviceRegister(dashboardCmsInit); +#endif + + rxConfig = rxConfigToUse; + + memset(&pageState, 0, sizeof(pageState)); + dashboardSetPage(PAGE_WELCOME); + + dashboardUpdate(micros()); + + dashboardSetNextPageChangeAt(micros() + (1000 * 1000 * 5)); +} + +void dashboardShowFixedPage(pageId_e pageId) +{ + dashboardSetPage(pageId); + dashboardDisablePageCycling(); +} + +void dashboardSetNextPageChangeAt(uint32_t futureMicros) +{ + pageState.nextPageAt = futureMicros; +} + +void dashboardEnablePageCycling(void) +{ + pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED; +} + +void dashboardResetPageCycling(void) +{ + pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page + +} + +void dashboardDisablePageCycling(void) +{ + pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED; +} + +#ifdef OLEDCMS +#include "io/cms.h" + +int dashboardCmsBegin(void) +{ + dashboardInCMS = true; + + debug[1]++; + delay(300); + + return 0; +} + +int dashboardCmsEnd(void) +{ + dashboardInCMS = false; + + return 0; +} + +int dashboardCmsClear(void) +{ + i2c_OLED_clear_display_quick(); + + return 0; +} + +int dashboardCmsWrite(uint8_t x, uint8_t y, char *s) +{ + i2c_OLED_set_xy(x, y); + i2c_OLED_send_string(s); + + return 0; +} + +int dashboardCmsHeartbeat(void) +{ + return 0; +} + +void dashboardCmsResync(displayPort_t *pPort) +{ + UNUSED(pPort); +} + +uint32_t dashboardCmsTxBytesFree(void) +{ + return UINT32_MAX; +} + +displayPortVTable_t dashboardCmsVTable = { + dashboardCmsBegin, + dashboardCmsEnd, + dashboardCmsClear, + dashboardCmsWrite, + dashboardCmsHeartbeat, + dashboardCmsResync, + dashboardCmsTxBytesFree, +}; + +void dashboardCmsInit(displayPort_t *pPort) +{ +debug[1]++; +delay(300); + pPort->rows = SCREEN_CHARACTER_ROW_COUNT; + pPort->cols = SCREEN_CHARACTER_COLUMN_COUNT; + pPort->vTable = &dashboardCmsVTable; +} +#endif // OLEDCMS + +#endif diff --git a/src/main/io/display.c b/src/main/io/dashboard.c.orig similarity index 95% rename from src/main/io/display.c rename to src/main/io/dashboard.c.orig index bc44e6552d..4bb7b63774 100644 --- a/src/main/io/display.c +++ b/src/main/io/dashboard.c.orig @@ -21,7 +21,7 @@ #include "platform.h" -#ifdef DISPLAY +#ifdef USE_DASHBOARD #include "common/utils.h" @@ -62,7 +62,7 @@ #include "config/feature.h" #include "config/config_profile.h" -#include "io/display.h" +#include "io/dashboard.h" #include "rx/rx.h" @@ -78,7 +78,7 @@ controlRateConfig_t *getControlRateConfig(uint8_t profileIndex); #define PAGE_CYCLE_FREQUENCY (MICROSECONDS_IN_A_SECOND * 5) static uint32_t nextDisplayUpdateAt = 0; -static bool displayPresent = false; +static bool dashboardPresent = false; static rxConfig_t *rxConfig; @@ -102,7 +102,7 @@ static const char* const pageTitles[] = { #ifdef GPS ,"GPS" #endif -#ifdef ENABLE_DEBUG_OLED_PAGE +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE ,"DEBUG" #endif }; @@ -120,7 +120,7 @@ const pageId_e cyclePageIds[] = { #ifndef SKIP_TASK_STATISTICS ,PAGE_TASKS #endif -#ifdef ENABLE_DEBUG_OLED_PAGE +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE ,PAGE_DEBUG, #endif }; @@ -148,7 +148,7 @@ typedef struct pageState_s { static pageState_t pageState; void resetDisplay(void) { - displayPresent = ug2864hsweg01InitI2C(); + dashboardPresent = ug2864hsweg01InitI2C(); } void LCDprint(uint8_t i) { @@ -566,7 +566,7 @@ void showTasksPage(void) } #endif -#ifdef ENABLE_DEBUG_OLED_PAGE +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE void showDebugPage(void) { @@ -581,11 +581,15 @@ void showDebugPage(void) } #endif +<<<<<<< HEAD:src/main/io/display.c #ifdef OLEDCMS static bool displayInCMS = false; #endif void displayUpdate(uint32_t currentTime) +======= +void dashboardUpdate(uint32_t currentTime) +>>>>>>> betaflight/master:src/main/io/dashboard.c { static uint8_t previousArmedState = 0; @@ -636,13 +640,13 @@ void displayUpdate(uint32_t currentTime) // user to power off/on the display or connect it while powered. resetDisplay(); - if (!displayPresent) { + if (!dashboardPresent) { return; } handlePageChange(); } - if (!displayPresent) { + if (!dashboardPresent) { return; } @@ -679,7 +683,7 @@ void displayUpdate(uint32_t currentTime) } break; #endif -#ifdef ENABLE_DEBUG_OLED_PAGE +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE case PAGE_DEBUG: showDebugPage(); break; @@ -693,13 +697,13 @@ void displayUpdate(uint32_t currentTime) } -void displaySetPage(pageId_e pageId) +void dashboardSetPage(pageId_e pageId) { pageState.pageId = pageId; pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; } -void displayInit(rxConfig_t *rxConfigToUse) +void dashboardInit(rxConfig_t *rxConfigToUse) { delay(200); resetDisplay(); @@ -712,36 +716,36 @@ void displayInit(rxConfig_t *rxConfigToUse) rxConfig = rxConfigToUse; memset(&pageState, 0, sizeof(pageState)); - displaySetPage(PAGE_WELCOME); + dashboardSetPage(PAGE_WELCOME); - displayUpdate(micros()); + dashboardUpdate(micros()); - displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5)); + dashboardSetNextPageChangeAt(micros() + (1000 * 1000 * 5)); } -void displayShowFixedPage(pageId_e pageId) +void dashboardShowFixedPage(pageId_e pageId) { - displaySetPage(pageId); - displayDisablePageCycling(); + dashboardSetPage(pageId); + dashboardDisablePageCycling(); } -void displaySetNextPageChangeAt(uint32_t futureMicros) +void dashboardSetNextPageChangeAt(uint32_t futureMicros) { pageState.nextPageAt = futureMicros; } -void displayEnablePageCycling(void) +void dashboardEnablePageCycling(void) { pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED; } -void displayResetPageCycling(void) +void dashboardResetPageCycling(void) { pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page } -void displayDisablePageCycling(void) +void dashboardDisablePageCycling(void) { pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED; } diff --git a/src/main/io/display.h b/src/main/io/dashboard.h similarity index 72% rename from src/main/io/display.h rename to src/main/io/dashboard.h index f2cf782bd1..5b98b4c282 100644 --- a/src/main/io/display.h +++ b/src/main/io/dashboard.h @@ -15,7 +15,7 @@ * along with Cleanflight. If not, see . */ -#define ENABLE_DEBUG_OLED_PAGE +#define ENABLE_DEBUG_DASHBOARD_PAGE typedef enum { PAGE_WELCOME, @@ -30,22 +30,26 @@ typedef enum { #ifdef GPS PAGE_GPS, #endif -#ifdef ENABLE_DEBUG_OLED_PAGE +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE PAGE_DEBUG, #endif } pageId_e; struct rxConfig_s; -void displayInit(struct rxConfig_s *intialRxConfig); -void displayUpdate(uint32_t currentTime); +void dashboardInit(struct rxConfig_s *intialRxConfig); +void dashboardUpdate(uint32_t currentTime); -void displayShowFixedPage(pageId_e pageId); +void dashboardShowFixedPage(pageId_e pageId); +void dashboardEnablePageCycling(void); +void dashboardDisablePageCycling(void); +void dashboardResetPageCycling(void); +void dashboardSetNextPageChangeAt(uint32_t futureMicros); void displayEnablePageCycling(void); void displayDisablePageCycling(void); void displayResetPageCycling(void); void displaySetNextPageChangeAt(uint32_t futureMicros); #ifdef CMS -void displayCmsInit(displayPort_t *pPort); +//void dashboardCmsInit(displayPort_t *pPort); #endif diff --git a/src/main/io/dashboard.h.orig b/src/main/io/dashboard.h.orig new file mode 100644 index 0000000000..9a8c9971b5 --- /dev/null +++ b/src/main/io/dashboard.h.orig @@ -0,0 +1,58 @@ +/* + * 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 . + */ + +#define ENABLE_DEBUG_DASHBOARD_PAGE + +typedef enum { + PAGE_WELCOME, + PAGE_ARMED, + PAGE_BATTERY, + PAGE_SENSORS, + PAGE_RX, + PAGE_PROFILE, +#ifndef SKIP_TASK_STATISTICS + PAGE_TASKS, +#endif +#ifdef GPS + PAGE_GPS, +#endif +#ifdef ENABLE_DEBUG_DASHBOARD_PAGE + PAGE_DEBUG, +#endif +} pageId_e; + +struct rxConfig_s; +void dashboardInit(struct rxConfig_s *intialRxConfig); +void dashboardUpdate(uint32_t currentTime); + +void dashboardShowFixedPage(pageId_e pageId); + +<<<<<<< HEAD:src/main/io/display.h +void displayEnablePageCycling(void); +void displayDisablePageCycling(void); +void displayResetPageCycling(void); +void displaySetNextPageChangeAt(uint32_t futureMicros); + +#ifdef CMS +void displayCmsInit(displayPort_t *pPort); +#endif +======= +void dashboardEnablePageCycling(void); +void dashboardDisablePageCycling(void); +void dashboardResetPageCycling(void); +void dashboardSetNextPageChangeAt(uint32_t futureMicros); +>>>>>>> betaflight/master:src/main/io/dashboard.h diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 07d8a33f8b..d4bdc01261 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -41,7 +41,7 @@ #include "io/cms.h" #include "io/serial.h" -#include "io/display.h" +#include "io/dashboard.h" #include "io/gps.h" #include "flight/gps_conversion.h" @@ -1074,9 +1074,9 @@ static bool gpsNewFrameUBLOX(uint8_t data) static void gpsHandlePassthrough(uint8_t data) { gpsNewData(data); - #ifdef DISPLAY - if (feature(FEATURE_DISPLAY)) { - displayUpdate(micros()); + #ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { + dashboardUpdate(micros()); } #endif @@ -1090,9 +1090,9 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) if(!(gpsPort->mode & MODE_TX)) serialSetMode(gpsPort, gpsPort->mode | MODE_TX); -#ifdef DISPLAY - if (feature(FEATURE_DISPLAY)) { - displayShowFixedPage(PAGE_GPS); +#ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { + dashboardShowFixedPage(PAGE_GPS); } #endif diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index d0e021691e..71b5f2e0fc 100755 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -148,7 +148,8 @@ static void cliTasks(char *cmdline); #endif static void cliVersion(char *cmdline); static void cliRxRange(char *cmdline); -#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY) +#if (FLASH_SIZE > 64) +static void printResource(uint8_t dumpMask, master_t *defaultConfig); static void cliResource(char *cmdline); #endif #ifdef GPS @@ -203,6 +204,7 @@ typedef enum { DUMP_ALL = (1 << 3), DO_DIFF = (1 << 4), SHOW_DEFAULTS = (1 << 5), + HIDE_UNUSED = (1 << 6), } dumpFlags_e; static const char* const emptyName = "-"; @@ -237,7 +239,7 @@ static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET } }; -#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY) +#if (FLASH_SIZE > 64) // sync this with sensors_e static const char * const sensorTypeNames[] = { "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL @@ -331,7 +333,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("profile", "change profile", "[]", cliProfile), CLI_COMMAND_DEF("rateprofile", "change rate profile", "[]", cliRateProfile), -#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY) +#if (FLASH_SIZE > 64) CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), #endif CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), @@ -2740,6 +2742,11 @@ static void printConfig(char *cmdline, bool doDiff) #endif printName(dumpMask); +#ifndef CLI_MINIMAL_VERBOSITY + cliPrint("\r\n# resources\r\n"); +#endif + printResource(dumpMask, &defaultConfig); + #ifndef USE_QUAD_MIXER_ONLY #ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\n# mixer\r\n"); @@ -3722,7 +3729,7 @@ void cliProcess(void) } } -#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY) +#if (FLASH_SIZE > 64) typedef struct { const uint8_t owner; @@ -3748,13 +3755,72 @@ const cliResourceValue_t resourceTable[] = { #endif }; +static void printResource(uint8_t dumpMask, master_t *defaultConfig) +{ + for (unsigned int i = 0; i < ARRAYLEN(resourceTable); i++) { + const char* owner; + owner = ownerNames[resourceTable[i].owner]; + + if (resourceTable[i].maxIndex > 0) { + for (int index = 0; index < resourceTable[i].maxIndex; index++) { + ioTag_t ioPtr = *(resourceTable[i].ptr + index); + ioTag_t ioPtrDefault = *(resourceTable[i].ptr + index - (uint32_t)&masterConfig + (uint32_t)defaultConfig); + + IO_t io = IOGetByTag(ioPtr); + IO_t ioDefault = IOGetByTag(ioPtrDefault); + bool equalsDefault = io == ioDefault; + const char *format = "resource %s %d %c%02d\r\n"; + const char *formatUnassigned = "resource %s %d NONE\r\n"; + if (DEFIO_TAG_ISEMPTY(ioDefault)) { + cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index)); + } else { + cliDefaultPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(ioDefault) + 'A', IO_GPIOPinIdx(ioDefault)); + } + if (DEFIO_TAG_ISEMPTY(io)) { + if (!(dumpMask & HIDE_UNUSED)) { + cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index)); + } + } else { + cliDumpPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io)); + } + } + } else { + ioTag_t ioPtr = *resourceTable[i].ptr; + ioTag_t ioPtrDefault = *(resourceTable[i].ptr - (uint32_t)&masterConfig + (uint32_t)defaultConfig); + + IO_t io = IOGetByTag(ioPtr); + IO_t ioDefault = IOGetByTag(ioPtrDefault); + bool equalsDefault = io == ioDefault; + const char *format = "resource %s %c%02d\r\n"; + const char *formatUnassigned = "resource %s NONE\r\n"; + if (DEFIO_TAG_ISEMPTY(ioDefault)) { + cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner); + } else { + cliDefaultPrintf(dumpMask, equalsDefault, format, owner, IO_GPIOPortIdx(ioDefault) + 'A', IO_GPIOPinIdx(ioDefault)); + } + if (DEFIO_TAG_ISEMPTY(io)) { + if (!(dumpMask & HIDE_UNUSED)) { + cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner); + } + } else { + cliDumpPrintf(dumpMask, equalsDefault, format, owner, IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io)); + } + } + } +} + static void cliResource(char *cmdline) { - int len; - len = strlen(cmdline); + int len = strlen(cmdline); if (len == 0) { - cliPrintf("IO:\r\n----------------------\r\n"); + printResource(DUMP_MASTER | HIDE_UNUSED, NULL); + + return; + } else if (strncasecmp(cmdline, "list", len) == 0) { +#ifndef CLI_MINIMAL_VERBOSITY + cliPrintf("Currently active IO resource assignments:\r\n(reboot to update)\r\n----------------------\r\n"); +#endif for (uint32_t i = 0; i < DEFIO_IO_USED_COUNT; i++) { const char* owner; owner = ownerNames[ioRecs[i].owner]; @@ -3768,34 +3834,10 @@ static void cliResource(char *cmdline) cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource); } } - cliPrintf("\r\nUse: 'resource list' to see how to change resources.\r\n"); - return; - } else if (strncasecmp(cmdline, "list", len) == 0) { - for (uint8_t i = 0; i < ARRAYLEN(resourceTable); i++) { - const char* owner; - owner = ownerNames[resourceTable[i].owner]; +#ifndef CLI_MINIMAL_VERBOSITY + cliPrintf("\r\nUse: 'resource' to see how to change resources.\r\n"); +#endif - if (resourceTable[i].maxIndex > 0) { - for (int index = 0; index < resourceTable[i].maxIndex; index++) { - - if (DEFIO_TAG_ISEMPTY(*(resourceTable[i].ptr + index))) { - continue; - } - - IO_t io = IOGetByTag(*(resourceTable[i].ptr + index)); - if (!io) { - continue; - } - cliPrintf("resource %s %d %c%02d\r\n", owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io)); - } - } else { - if (DEFIO_TAG_ISEMPTY(*(resourceTable[i].ptr))) { - continue; - } - IO_t io = IOGetByTag(*resourceTable[i].ptr); - cliPrintf("resource %s %c%02d\r\n", owner, IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io)); - } - } return; } @@ -3836,7 +3878,11 @@ static void cliResource(char *cmdline) cliPrintf("Resource is freed!"); return; } else { - uint8_t port = (*pch)-'A'; + uint8_t port = (*pch) - 'A'; + if (port >= 8) { + port = (*pch) - 'a'; + } + if (port < 8) { pch++; pin = atoi(pch); @@ -3861,7 +3907,9 @@ static void cliResource(char *cmdline) void cliDfu(char *cmdLine) { UNUSED(cmdLine); +#ifndef CLI_MINIMAL_VERBOSITY cliPrint("\r\nRestarting in DFU mode"); +#endif cliRebootEx(true); } diff --git a/src/main/main.c b/src/main/main.c index 618409f3a9..7a9b8eb27c 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -84,14 +84,13 @@ #include "io/servos.h" #include "io/gimbal.h" #include "io/ledstrip.h" -#include "io/display.h" +#include "io/dashboard.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/serial_cli.h" #include "io/transponder_ir.h" -#include "io/cms.h" #include "io/osd.h" -#include "io/vtx.h" #include "io/canvas.h" +#include "io/vtx.h" #include "scheduler/scheduler.h" @@ -403,9 +402,9 @@ void init(void) cmsInit(); #endif -#ifdef DISPLAY - if (feature(FEATURE_DISPLAY)) { - displayInit(&masterConfig.rxConfig); +#ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { + dashboardInit(&masterConfig.rxConfig); } #endif @@ -599,13 +598,13 @@ void init(void) if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER)) batteryInit(&masterConfig.batteryConfig); -#ifdef DISPLAY - if (feature(FEATURE_DISPLAY)) { +#ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { #ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY - displayShowFixedPage(PAGE_GPS); + dashboardShowFixedPage(PAGE_GPS); #else - displayResetPageCycling(); - displayEnablePageCycling(); + dashboardResetPageCycling(); + dashboardEnablePageCycling(); #endif } #endif diff --git a/src/main/main.c.orig b/src/main/main.c.orig new file mode 100644 index 0000000000..5fc05be537 --- /dev/null +++ b/src/main/main.c.orig @@ -0,0 +1,750 @@ +/* + * 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 . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#include "blackbox/blackbox.h" + +#include "common/axis.h" +#include "common/color.h" +#include "common/maths.h" +#include "common/printf.h" + +#include "drivers/nvic.h" + +#include "drivers/sensor.h" +#include "drivers/system.h" +#include "drivers/dma.h" +#include "drivers/gpio.h" +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/sound_beeper.h" +#include "drivers/timer.h" +#include "drivers/serial.h" +#include "drivers/serial_softserial.h" +#include "drivers/serial_uart.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/pwm_rx.h" +#include "drivers/pwm_output.h" +#include "drivers/adc.h" +#include "drivers/bus_i2c.h" +#include "drivers/bus_spi.h" +#include "drivers/inverter.h" +#include "drivers/flash_m25p16.h" +#include "drivers/sonar_hcsr04.h" +#include "drivers/sdcard.h" +#include "drivers/usb_io.h" +#include "drivers/transponder_ir.h" +#include "drivers/io.h" +#include "drivers/exti.h" +#include "drivers/vtx_soft_spi_rtc6705.h" + +#ifdef USE_BST +#include "bus_bst.h" +#endif + +#include "fc/config.h" +#include "fc/fc_tasks.h" +#include "fc/fc_msp.h" +#include "fc/rc_controls.h" +#include "fc/runtime_config.h" + +#include "msp/msp_serial.h" + +#include "rx/rx.h" +#include "rx/spektrum.h" + +#include "io/cms.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/flashfs.h" +#include "io/gps.h" +#include "io/motors.h" +#include "io/servos.h" +#include "io/gimbal.h" +#include "io/ledstrip.h" +#include "io/dashboard.h" +#include "io/asyncfatfs/asyncfatfs.h" +#include "io/serial_cli.h" +#include "io/transponder_ir.h" +#include "io/cms.h" +#include "io/osd.h" +#include "io/vtx.h" +#include "io/canvas.h" + +#include "scheduler/scheduler.h" + +#include "sensors/sensors.h" +#include "sensors/sonar.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/gyro.h" +#include "sensors/battery.h" +#include "sensors/boardalignment.h" +#include "sensors/initialisation.h" + +#include "telemetry/telemetry.h" + +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/mixer.h" +#include "flight/failsafe.h" +#include "flight/navigation.h" + +#include "config/config_eeprom.h" +#include "config/config_profile.h" +#include "config/config_master.h" +#include "config/feature.h" + +#ifdef USE_HARDWARE_REVISION_DETECTION +#include "hardware_revision.h" +#endif + +#include "build/build_config.h" +#include "build/debug.h" + +extern uint8_t motorControlEnable; + +#ifdef SOFTSERIAL_LOOPBACK +serialPort_t *loopbackPort; +#endif + +typedef enum { + SYSTEM_STATE_INITIALISING = 0, + SYSTEM_STATE_CONFIG_LOADED = (1 << 0), + SYSTEM_STATE_SENSORS_READY = (1 << 1), + SYSTEM_STATE_MOTORS_READY = (1 << 2), + SYSTEM_STATE_TRANSPONDER_ENABLED = (1 << 3), + SYSTEM_STATE_READY = (1 << 7) +} systemState_e; + +static uint8_t systemState = SYSTEM_STATE_INITIALISING; + +void init(void) +{ +#ifdef USE_HAL_DRIVER + HAL_Init(); +#endif + + printfSupportInit(); + + initEEPROM(); + + ensureEEPROMContainsValidData(); + readEEPROM(); + + systemState |= SYSTEM_STATE_CONFIG_LOADED; + + systemInit(); + + //i2cSetOverclock(masterConfig.i2c_overclock); + + // initialize IO (needed for all IO operations) + IOInitGlobal(); + + debugMode = masterConfig.debug_mode; + +#ifdef USE_HARDWARE_REVISION_DETECTION + detectHardwareRevision(); +#endif + + // Latch active features to be used for feature() in the remainder of init(). + latchActiveFeatures(); + +#ifdef ALIENFLIGHTF3 + ledInit(hardwareRevision == AFF3_REV_1 ? false : true); +#else + ledInit(false); +#endif + LED2_ON; + +#ifdef USE_EXTI + EXTIInit(); +#endif + +#if defined(BUTTONS) + gpio_config_t buttonAGpioConfig = { + BUTTON_A_PIN, + Mode_IPU, + Speed_2MHz + }; + gpioInit(BUTTON_A_PORT, &buttonAGpioConfig); + + gpio_config_t buttonBGpioConfig = { + BUTTON_B_PIN, + Mode_IPU, + Speed_2MHz + }; + gpioInit(BUTTON_B_PORT, &buttonBGpioConfig); + + // Check status of bind plug and exit if not active + delayMicroseconds(10); // allow GPIO configuration to settle + + if (!isMPUSoftReset()) { + uint8_t secondsRemaining = 5; + bool bothButtonsHeld; + do { + bothButtonsHeld = !digitalIn(BUTTON_A_PORT, BUTTON_A_PIN) && !digitalIn(BUTTON_B_PORT, BUTTON_B_PIN); + if (bothButtonsHeld) { + if (--secondsRemaining == 0) { + resetEEPROM(); + systemReset(); + } + delay(1000); + LED0_TOGGLE; + } + } while (bothButtonsHeld); + } +#endif + +#ifdef SPEKTRUM_BIND + if (feature(FEATURE_RX_SERIAL)) { + switch (masterConfig.rxConfig.serialrx_provider) { + case SERIALRX_SPEKTRUM1024: + case SERIALRX_SPEKTRUM2048: + // Spektrum satellite binding if enabled on startup. + // Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup. + // The rest of Spektrum initialization will happen later - via spektrumInit() + spektrumBind(&masterConfig.rxConfig); + break; + } + } +#endif + + delay(100); + + timerInit(); // timer must be initialized before any channel is allocated + +#if !defined(USE_HAL_DRIVER) + dmaInit(); +#endif + +#if defined(AVOID_UART1_FOR_PWM_PPM) + serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL), + feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE); +#elif defined(AVOID_UART2_FOR_PWM_PPM) + serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL), + feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE); +#elif defined(AVOID_UART3_FOR_PWM_PPM) + serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL), + feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE); +#else + serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE); +#endif + + mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer); +#ifdef USE_SERVOS + servoMixerInit(masterConfig.customServoMixer); +#endif + + uint16_t idlePulse = masterConfig.motorConfig.mincommand; + if (feature(FEATURE_3D)) { + idlePulse = masterConfig.flight3DConfig.neutral3d; + } + + if (masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED) { + featureClear(FEATURE_3D); + idlePulse = 0; // brushed motors + } + +#ifdef USE_QUAD_MIXER_ONLY + motorInit(&masterConfig.motorConfig, idlePulse, QUAD_MOTOR_COUNT); +#else + motorInit(&masterConfig.motorConfig, idlePulse, mixers[masterConfig.mixerMode].motorCount); +#endif + +#ifdef USE_SERVOS + if (isMixerUsingServos()) { + //pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING); + servoInit(&masterConfig.servoConfig); + } +#endif + +#ifndef SKIP_RX_PWM_PPM + if (feature(FEATURE_RX_PPM)) { + ppmRxInit(&masterConfig.ppmConfig, masterConfig.motorConfig.motorPwmProtocol); + } else if (feature(FEATURE_RX_PARALLEL_PWM)) { + pwmRxInit(&masterConfig.pwmConfig); + } + pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode); +#endif + + mixerConfigureOutput(); +#ifdef USE_SERVOS + servoConfigureOutput(); +#endif + systemState |= SYSTEM_STATE_MOTORS_READY; + +#ifdef BEEPER + beeperInit(&masterConfig.beeperConfig); +#endif +/* temp until PGs are implemented. */ +#ifdef INVERTER + initInverter(); +#endif + +#ifdef USE_BST + bstInit(BST_DEVICE); +#endif + +#ifdef USE_SPI +#ifdef USE_SPI_DEVICE_1 + spiInit(SPIDEV_1); +#endif +#ifdef USE_SPI_DEVICE_2 + spiInit(SPIDEV_2); +#endif +#ifdef USE_SPI_DEVICE_3 +#ifdef ALIENFLIGHTF3 + if (hardwareRevision == AFF3_REV_2) { + spiInit(SPIDEV_3); + } +#else + spiInit(SPIDEV_3); +#endif +#endif +#ifdef USE_SPI_DEVICE_4 + spiInit(SPIDEV_4); +#endif +#endif + +#ifdef VTX + vtxInit(); +#endif + +#ifdef USE_HARDWARE_REVISION_DETECTION + updateHardwareRevision(); +#endif + +#if defined(NAZE) + if (hardwareRevision == NAZE32_SP) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL2); + } else { + serialRemovePort(SERIAL_PORT_USART3); + } +#endif + +#if defined(SPRACINGF3) && defined(SONAR) && defined(USE_SOFTSERIAL2) + if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL2); + } +#endif + +#if defined(SPRACINGF3MINI) || defined(OMNIBUS) || defined(X_RACERSPI) +#if defined(SONAR) && defined(USE_SOFTSERIAL1) + if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL1); + } +#endif +#endif + +#ifdef USE_I2C +#if defined(NAZE) + if (hardwareRevision != NAZE32_SP) { + i2cInit(I2C_DEVICE); + } else { + if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { + i2cInit(I2C_DEVICE); + } + } +#elif defined(CC3D) + if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { + i2cInit(I2C_DEVICE); + } +#else + i2cInit(I2C_DEVICE); +#endif +#endif + +#ifdef USE_ADC + drv_adc_config_t adc_params; + + adc_params.enableVBat = feature(FEATURE_VBAT); + adc_params.enableRSSI = feature(FEATURE_RSSI_ADC); + adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER); + adc_params.enableExternal1 = false; +#ifdef OLIMEXINO + adc_params.enableExternal1 = true; +#endif +#ifdef NAZE + // optional ADC5 input on rev.5 hardware + adc_params.enableExternal1 = (hardwareRevision >= NAZE32_REV5); +#endif + + adcInit(&adc_params); +#endif + + + initBoardAlignment(&masterConfig.boardAlignment); + +<<<<<<< HEAD +#ifdef CMS + cmsInit(); +#endif + +#ifdef DISPLAY + if (feature(FEATURE_DISPLAY)) { + displayInit(&masterConfig.rxConfig); +======= +#ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { + dashboardInit(&masterConfig.rxConfig); +>>>>>>> betaflight/master + } +#endif + +#ifdef USE_RTC6705 + if (feature(FEATURE_VTX)) { + rtc6705_soft_spi_init(); + current_vtx_channel = masterConfig.vtx_channel; + rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]); + rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power); + } +#endif + +#ifdef OSD + if (feature(FEATURE_OSD)) { + osdInit(); + } +#endif + + if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, + masterConfig.acc_hardware, + masterConfig.mag_hardware, + masterConfig.baro_hardware, + masterConfig.mag_declination, + masterConfig.gyro_lpf, + masterConfig.gyro_sync_denom)) { + // if gyro was not detected due to whatever reason, we give up now. + failureMode(FAILURE_MISSING_ACC); + } + + systemState |= SYSTEM_STATE_SENSORS_READY; + + LED1_ON; + LED0_OFF; + LED2_OFF; + + for (int i = 0; i < 10; i++) { + LED1_TOGGLE; + LED0_TOGGLE; + delay(25); + if (!(getBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON; + delay(25); + BEEP_OFF; + } + LED0_OFF; + LED1_OFF; + +#ifdef MAG + if (sensors(SENSOR_MAG)) + compassInit(); +#endif + + imuInit(); + + mspFcInit(); + mspSerialInit(); + +#ifdef CANVAS + if (feature(FEATURE_CANVAS)) { + canvasInit(); + } +#endif + +#ifdef USE_CLI + cliInit(&masterConfig.serialConfig); +#endif + + failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); + + rxInit(&masterConfig.rxConfig, masterConfig.modeActivationConditions); + +#ifdef GPS + if (feature(FEATURE_GPS)) { + gpsInit( + &masterConfig.serialConfig, + &masterConfig.gpsConfig + ); + navigationInit( + &masterConfig.gpsProfile, + ¤tProfile->pidProfile + ); + } +#endif + +#ifdef SONAR + if (feature(FEATURE_SONAR)) { + sonarInit(&masterConfig.sonarConfig); + } +#endif + +#ifdef LED_STRIP + ledStripInit(masterConfig.ledConfigs, masterConfig.colors, masterConfig.modeColors, &masterConfig.specialColors); + + if (feature(FEATURE_LED_STRIP)) { + ledStripEnable(); + } +#endif + +#ifdef TELEMETRY + if (feature(FEATURE_TELEMETRY)) { + telemetryInit(); + } +#endif + +#ifdef USB_CABLE_DETECTION + usbCableDetectInit(); +#endif + +#ifdef TRANSPONDER + if (feature(FEATURE_TRANSPONDER)) { + transponderInit(masterConfig.transponderData); + transponderEnable(); + transponderStartRepeating(); + systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED; + } +#endif + +#ifdef USE_FLASHFS +#ifdef NAZE + if (hardwareRevision == NAZE32_REV5) { + m25p16_init(IO_TAG_NONE); + } +#elif defined(USE_FLASH_M25P16) + m25p16_init(IO_TAG_NONE); +#endif + + flashfsInit(); +#endif + +#ifdef USE_SDCARD + bool sdcardUseDMA = false; + + sdcardInsertionDetectInit(); + +#ifdef SDCARD_DMA_CHANNEL_TX + +#if defined(LED_STRIP) && defined(WS2811_DMA_CHANNEL) + // Ensure the SPI Tx DMA doesn't overlap with the led strip +#if defined(STM32F4) || defined(STM32F7) + sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_STREAM; +#else + sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_CHANNEL; +#endif +#else + sdcardUseDMA = true; +#endif + +#endif + + sdcard_init(sdcardUseDMA); + + afatfs_init(); +#endif + + if (masterConfig.gyro_lpf > 0 && masterConfig.gyro_lpf < 7) { + masterConfig.pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed + masterConfig.gyro_sync_denom = 1; + } + + setTargetPidLooptime((gyro.targetLooptime + LOOPTIME_SUSPEND_TIME) * masterConfig.pid_process_denom); // Initialize pid looptime + +#ifdef BLACKBOX + initBlackbox(); +#endif + + if (masterConfig.mixerMode == MIXER_GIMBAL) { + accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); + } + gyroSetCalibrationCycles(); +#ifdef BARO + baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES); +#endif + + // start all timers + // TODO - not implemented yet + timerStart(); + + ENABLE_STATE(SMALL_ANGLE); + DISABLE_ARMING_FLAG(PREVENT_ARMING); + +#ifdef SOFTSERIAL_LOOPBACK + // FIXME this is a hack, perhaps add a FUNCTION_LOOPBACK to support it properly + loopbackPort = (serialPort_t*)&(softSerialPorts[0]); + if (!loopbackPort->vTable) { + loopbackPort = openSoftSerial(0, NULL, 19200, SERIAL_NOT_INVERTED); + } + serialPrint(loopbackPort, "LOOPBACK\r\n"); +#endif + + // Now that everything has powered up the voltage and cell count be determined. + + if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER)) + batteryInit(&masterConfig.batteryConfig); + +#ifdef USE_DASHBOARD + if (feature(FEATURE_DASHBOARD)) { +#ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY + dashboardShowFixedPage(PAGE_GPS); +#else + dashboardResetPageCycling(); + dashboardEnablePageCycling(); +#endif + } +#endif + +#ifdef CJMCU + LED2_ON; +#endif + + // Latch active features AGAIN since some may be modified by init(). + latchActiveFeatures(); + motorControlEnable = true; + + fcTasksInit(); + systemState |= SYSTEM_STATE_READY; +} + +#ifdef SOFTSERIAL_LOOPBACK +void processLoopback(void) { + if (loopbackPort) { + uint8_t bytesWaiting; + while ((bytesWaiting = serialRxBytesWaiting(loopbackPort))) { + uint8_t b = serialRead(loopbackPort); + serialWrite(loopbackPort, b); + }; + } +} +#else +#define processLoopback() +#endif + + +void main_step(void) +{ + scheduler(); + processLoopback(); +} + +#ifndef NOMAIN +int main(void) +{ + init(); + while (true) { + main_step(); + } +} +#endif + +#ifdef DEBUG_HARDFAULTS +//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ +/** + * hard_fault_handler_c: + * This is called from the HardFault_HandlerAsm with a pointer the Fault stack + * as the parameter. We can then read the values from the stack and place them + * into local variables for ease of reading. + * We then read the various Fault Status and Address Registers to help decode + * cause of the fault. + * The function ends with a BKPT instruction to force control back into the debugger + */ +void hard_fault_handler_c(unsigned long *hardfault_args) +{ + volatile unsigned long stacked_r0 ; + volatile unsigned long stacked_r1 ; + volatile unsigned long stacked_r2 ; + volatile unsigned long stacked_r3 ; + volatile unsigned long stacked_r12 ; + volatile unsigned long stacked_lr ; + volatile unsigned long stacked_pc ; + volatile unsigned long stacked_psr ; + volatile unsigned long _CFSR ; + volatile unsigned long _HFSR ; + volatile unsigned long _DFSR ; + volatile unsigned long _AFSR ; + volatile unsigned long _BFAR ; + volatile unsigned long _MMAR ; + + stacked_r0 = ((unsigned long)hardfault_args[0]) ; + stacked_r1 = ((unsigned long)hardfault_args[1]) ; + stacked_r2 = ((unsigned long)hardfault_args[2]) ; + stacked_r3 = ((unsigned long)hardfault_args[3]) ; + stacked_r12 = ((unsigned long)hardfault_args[4]) ; + stacked_lr = ((unsigned long)hardfault_args[5]) ; + stacked_pc = ((unsigned long)hardfault_args[6]) ; + stacked_psr = ((unsigned long)hardfault_args[7]) ; + + // Configurable Fault Status Register + // Consists of MMSR, BFSR and UFSR + _CFSR = (*((volatile unsigned long *)(0xE000ED28))) ; + + // Hard Fault Status Register + _HFSR = (*((volatile unsigned long *)(0xE000ED2C))) ; + + // Debug Fault Status Register + _DFSR = (*((volatile unsigned long *)(0xE000ED30))) ; + + // Auxiliary Fault Status Register + _AFSR = (*((volatile unsigned long *)(0xE000ED3C))) ; + + // Read the Fault Address Registers. These may not contain valid values. + // Check BFARVALID/MMARVALID to see if they are valid values + // MemManage Fault Address Register + _MMAR = (*((volatile unsigned long *)(0xE000ED34))) ; + // Bus Fault Address Register + _BFAR = (*((volatile unsigned long *)(0xE000ED38))) ; + + __asm("BKPT #0\n") ; // Break into the debugger +} + +#else +void HardFault_Handler(void) +{ + LED2_ON; + + // fall out of the sky + uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY; + if ((systemState & requiredStateForMotors) == requiredStateForMotors) { + stopMotors(); + } +#ifdef TRANSPONDER + // prevent IR LEDs from burning out. + uint8_t requiredStateForTransponder = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_TRANSPONDER_ENABLED; + if ((systemState & requiredStateForTransponder) == requiredStateForTransponder) { + transponderIrDisable(); + } +#endif + + LED1_OFF; + LED0_OFF; + + while (1) { +#ifdef LED2 + delay(50); + LED2_TOGGLE; +#endif + } +} +#endif diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 5b5eccaca1..d43b778aa5 100644 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -67,8 +67,8 @@ typedef enum { #if defined(BARO) || defined(SONAR) TASK_ALTITUDE, #endif -#ifdef DISPLAY - TASK_DISPLAY, +#ifdef USE_DASHBOARD + TASK_DASHBOARD, #endif #ifdef TELEMETRY TASK_TELEMETRY, diff --git a/src/main/target/AIORACERF3/target.c b/src/main/target/AIORACERF3/target.c index acb1586cfe..591219e747 100644 --- a/src/main/target/AIORACERF3/target.c +++ b/src/main/target/AIORACERF3/target.c @@ -24,16 +24,16 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM / UART2 RX - { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM4 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_RX (AF7) - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, //LED_STRIP + { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM3 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM4 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // UART3_RX (AF7) + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, //LED_STRIP }; diff --git a/src/main/target/AIR32/target.c b/src/main/target/AIR32/target.c index 6ead0d6fee..1709455c7d 100644 --- a/src/main/target/AIR32/target.c +++ b/src/main/target/AIR32/target.c @@ -23,13 +23,13 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 1b8f6c2111..0cff2b6aab 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -89,7 +89,6 @@ #define SENSORS_SET (SENSOR_ACC) #undef GPS -#define DISPLAY #define USE_FLASHFS #define USE_FLASH_M25P16 diff --git a/src/main/target/AIRHEROF3/target.c b/src/main/target/AIRHEROF3/target.c index 242a1945f9..e7ca5a7261 100755 --- a/src/main/target/AIRHEROF3/target.c +++ b/src/main/target/AIRHEROF3/target.c @@ -23,19 +23,18 @@ #include "drivers/timer.h" 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 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM8 - RC8 - - { 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 - { 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 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF_1}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_11}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2} // PWM14 - OUT6 }; diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c index e838c785ba..baa453c020 100644 --- a/src/main/target/ALIENFLIGHTF1/target.c +++ b/src/main/target/ALIENFLIGHTF1/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" 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, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0 }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6 }; diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index fc7861550b..4673d05a46 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -24,18 +24,16 @@ 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 - - // 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 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 }; diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index dcdce3e43c..1fddc56b96 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -23,19 +23,18 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1 - { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2 - { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3 - { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4 - { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5 - - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2 - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3 - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4 - { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5 - { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6 - { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7 - { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1 + { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2 + { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3 + { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4 + { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3 + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8 }; diff --git a/src/main/target/ANYFCF7/README.md b/src/main/target/ANYFCF7/README.md new file mode 100644 index 0000000000..bf8b4c7406 --- /dev/null +++ b/src/main/target/ANYFCF7/README.md @@ -0,0 +1,21 @@ +# AnyFC-F7 + +* The first F7 board flown with betaflight and inavflight, made by [@sambas](https://github.com/sambas) +* OSHW CC BY-SA 3.0 +* Source: https://github.com/sambas/hw/tree/master/AnyFCF7 +* 1st betaflight: https://www.youtube.com/watch?v=tv7k3A0FG80 +* 1st inavflight: https://www.youtube.com/watch?v=kJvlZAzprBs + +## HW info + +* STM32F745VGT6 100lqfp 216MHz +* MPU6000 SPI +* MS5611 baro +* All 8 uarts available + VCP +* 10 pwm outputs + 6 inputs +* external I2C +* external SPI (shared with U4/5) +* support for CAN +* SD card logging (SPI) +* 3 AD channels, one with 10k/1k divider, two with 1k series resistor + diff --git a/src/main/target/ANYFCF7/target.c b/src/main/target/ANYFCF7/target.c index d3b944ee70..e2f55aa290 100644 --- a/src/main/target/ANYFCF7/target.c +++ b/src/main/target/ANYFCF7/target.c @@ -23,48 +23,49 @@ #include "drivers/timer.h" +#if defined(USE_DSHOT) // DSHOT TEST const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN - { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN - { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN - { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN - { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN + { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN + { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN + { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN + { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN + { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN + { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN - { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_5, DMA1_ST7_HANDLER }, // S10_OUT 1 - { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2 - { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4 - { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT - { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT - { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3 - { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT - { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT - { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT + { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1 + { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2 + { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4 + { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT + { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT + { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT + { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3 + { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT + { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT + { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT }; - -/* STANDARD LAYOUT +#else +// STANDARD LAYOUT const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S1_IN - { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S2_IN - { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S3_IN - { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S4_IN - { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S5_IN - { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S6_IN + { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12}, // S1_IN + { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12}, // S2_IN + { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S3_IN + { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S4_IN + { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S5_IN + { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S6_IN - { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4}, // S10_OUT 1 - { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S6_OUT 2 - { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4}, // S5_OUT 3 - { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S1_OUT 4 - { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S2_OUT - { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9}, // S3_OUT - { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S7_OUT - { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S8_OUT - { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S9_OUT + { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4}, // S10_OUT 1 + { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S6_OUT 2 + { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4}, // S5_OUT 3 + { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S1_OUT 4 + { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5}, // S2_OUT + { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9}, // S3_OUT + { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3}, // S4_OUT + { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5}, // S7_OUT + { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S8_OUT + { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3}, // S9_OUT }; -*/ +#endif // ALTERNATE LAYOUT //const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { diff --git a/src/main/target/BETAFLIGHTF3/target.c b/src/main/target/BETAFLIGHTF3/target.c index d6e93c8a89..e88dce7400 100755 --- a/src/main/target/BETAFLIGHTF3/target.c +++ b/src/main/target/BETAFLIGHTF3/target.c @@ -24,17 +24,17 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // RC PPM - PB7 - TIM17_CH1N AF1, TIM4_CH2 AF2, TIM8_BKIN AF5, TIM3_CH4 AF10 - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // 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, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, DMA1_Channel1, DMA1_CH1_HANDLER }, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, DMA1_Channel4, DMA1_CH4_HANDLER }, // PWM4 - PB9 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM1 - PA6 - TIM3_CH1 AF2, TIM8_BKIN AF4, TIM1_BKIN AF6, *TIM16_CH1 AF1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2 AF2, TIM8_CH1 AF4, TIM1_CH1N AF6, *TIM17_CH1 AF1 + { TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10,DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PB8 - TIM16_CH1 AF1, TIM4_CH3 AF2, TIM8_CH2 AF10, TIM1_BKIN AF12 + { TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM4 - PB9 - TIM17_CH1 AF1, TIM4_CH4 AF2, TIM8_CH3 AF10 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL RX - TIM3_CH3 AF2, TIM8_CH2N AF4, TIM1_CH2N AF6 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL TX - TIM3_CH4 AF2, TIM8_CH3N AF4, TIM1_CH3N AF6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0 - TIM2_CH1 AF1, TIM8_BKIN AF9, TIM8_ETR AF10 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - TIM2_CH3 AF1, TIM15_CH1 AF9 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index 1dc435b492..4806240672 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -45,11 +45,8 @@ #define USE_EXTI #define USE_DSHOT - -// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4 -#if defined(USE_UART1_TX_DMA) && defined(USE_DSHOT) -#undef USE_UART1_TX_DMA -#endif +#define REMAP_TIM16_DMA +#define REMAP_TIM17_DMA #define USB_IO @@ -66,11 +63,11 @@ #define UART1_TX_PIN PA9 #define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_TX_PIN PA2 #define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define SOFTSERIAL_2_TIMER TIM3 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 5 @@ -81,7 +78,6 @@ #define USE_SPI #define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -//GPIO_AF_1 #define SPI1_NSS_PIN PA15 #define SPI1_SCK_PIN PB3 @@ -150,4 +146,4 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) \ No newline at end of file +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) \ No newline at end of file diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index c82953b221..3e7a18ac30 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -23,12 +23,12 @@ #include "drivers/dma.h" 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, NULL, 0, 0 }, // PPM IN - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT }; diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index c0a1dd07c2..71a6462bb4 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -23,17 +23,17 @@ #include "drivers/timer.h" 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 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, }, // S1_IN + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, }, // S4_IN - Current + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, }, // S5_IN - Vbattery + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, }, // S6_IN - PPM IN + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S1_OUT + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S2_OUT + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S3_OUT + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, }, // S4_OUT + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, } // S6_OUT }; diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 8867ca53e6..1986a350ce 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -24,23 +24,23 @@ 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, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM1 - PA8 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM2 - PB8 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM3 - PB9 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM4 - PC6 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM5 - PC7 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM6 - PC8 + { TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM7 - PF9 + { TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM8 - PF10 + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PD12 + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM10 - PD13 + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM11 - PD14 + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM12 - PD15 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM13 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM14 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM15 - PA3 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM16 - PB0 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM17 - PB1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 } // PWM18 - PA4 }; diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index d784dfcb9f..30f0e1b00e 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" 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, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6 }; diff --git a/src/main/target/COLIBRI/target.c b/src/main/target/COLIBRI/target.c index b9cb1b1704..fd5c5d4272 100644 --- a/src/main/target/COLIBRI/target.c +++ b/src/main/target/COLIBRI/target.c @@ -24,21 +24,20 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_IN - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S2_IN - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S5_IN - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S7_IN - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S8_IN - - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_OUT - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S4_OUT - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S6_OUT - { TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM10 }, // S7_OUT - { TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM11 }, // S8_OUT + { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // S1_IN + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S2_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S3_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S5_IN + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 }, // S7_IN + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 }, // S8_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S3_OUT + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12 }, // S4_OUT + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S5_OUT + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12 }, // S6_OUT + { TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM10 }, // S7_OUT + { TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM11 }, // S8_OUT }; diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c index 9bf7e986c0..08fd1255e1 100644 --- a/src/main/target/COLIBRI_RACE/target.c +++ b/src/main/target/COLIBRI_RACE/target.c @@ -23,16 +23,16 @@ #include "drivers/timer.h" 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, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM11 - PB15 }; diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index b75f0e7dd8..58f98c9a5c 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -23,17 +23,14 @@ #include "drivers/timer.h" 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 - - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9 - - { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10 - { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9 - { 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 - - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM8 - PB1 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM9 - PB0 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB9 + { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PMW4 - PA10 + { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM5 - PA9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM8 - PB1 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM9 - PB0 }; diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index 42608606e9..cf7aab2df1 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -6,24 +6,22 @@ #include "drivers/timer.h" 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 - - { 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 - - { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S1_IN + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S5_IN + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S6_IN + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S7_IN + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S8_IN + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT + { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S3_OUT + { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S4_OUT + { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S5_OUT + { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S6_OUT + { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S7_OUT + { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S8_OUT + { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_TIM9 }, // sonar echo if needed }; diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 504e3b6c2d..4f50ab5d01 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -25,16 +25,13 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PPM IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - - { TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1 - { TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2 - { TIM8, IO_TAG(PB5), TIM_Channel_3, TIM8_CC_IRQn, (1 | TIMER_OUTPUT_N_CHANNEL), IOCFG_AF_PP, GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3 - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4 - - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO TIMER - LED_STRIP - + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1 + { TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2 + { TIM8, IO_TAG(PB5), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, (1 | TIMER_OUTPUT_N_CHANNEL), GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO TIMER - LED_STRIP }; diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c index af6feb53c6..322753dd75 100644 --- a/src/main/target/FURYF4/target.c +++ b/src/main/target/FURYF4/target.c @@ -24,12 +24,11 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN - - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT // { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip }; diff --git a/src/main/target/FURYF7/README.md b/src/main/target/FURYF7/README.md new file mode 100644 index 0000000000..9b6255a618 --- /dev/null +++ b/src/main/target/FURYF7/README.md @@ -0,0 +1,18 @@ +# FURYF7 + +* STM32F745VGT6 +* ICM20689 SPI Gyro +* MS5611 baro - SPI (Not Currently Woerking. Need to write driver for MS5611 SPI) +* VCP +* 3 UARTS (UART1, UART3, UART6) +* 4 PWM outputs +* No PWM inputs (SBUS, PPM, Spek Sat) +* SD card (Not currently working, Fatal Error) +* 16MB Flash (Not currently working, no chip detected) +* ADC (RSSI, CURR, VBAT) +* I2C +* LED Strip +* Built in 5v 2A Regulator +* Spek Sat Connector +* SWD Port +* Beeper output \ No newline at end of file diff --git a/src/main/target/FURYF7/stm32f7xx_hal_conf.h b/src/main/target/FURYF7/stm32f7xx_hal_conf.h new file mode 100644 index 0000000000..20a305def5 --- /dev/null +++ b/src/main/target/FURYF7/stm32f7xx_hal_conf.h @@ -0,0 +1,446 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @author MCD Application Team + * @version V1.0.0 + * @date 22-April-2016 + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED + #define HAL_ADC_MODULE_ENABLED +/* #define HAL_CAN_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ + #define HAL_DMA_MODULE_ENABLED +// #define HAL_DMA2D_MODULE_ENABLED +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED + #define HAL_I2C_MODULE_ENABLED +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +//#define HAL_RTC_MODULE_ENABLED +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ + #define HAL_SPI_MODULE_ENABLED + #define HAL_TIM_MODULE_ENABLED + #define HAL_UART_MODULE_ENABLED + #define HAL_USART_MODULE_ENABLED +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +#define HAL_PCD_MODULE_ENABLED +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)5) /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ +/* LAN8742A PHY Address*/ +#define LAN8742A_PHY_ADDRESS 0x00 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x00000FFF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ + + +#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ +#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/main/target/FURYF7/target.c b/src/main/target/FURYF7/target.c new file mode 100644 index 0000000000..9d934b12c6 --- /dev/null +++ b/src/main/target/FURYF7/target.c @@ -0,0 +1,36 @@ + +/* + * 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 . + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/dma.h" + +#include "drivers/timer.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF3_TIM8, NULL, 0, 0 }, // PPM_IN + + { TIM3, IO_TAG(PB0), TIM_CHANNEL_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, DMA1_Stream7, DMA_CHANNEL_5, DMA1_ST7_HANDLER }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_CHANNEL_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, DMA1_Stream2, DMA_CHANNEL_5, DMA1_ST2_HANDLER }, // S2_OUT + { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S4_OUT + +// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip +}; \ No newline at end of file diff --git a/src/main/target/FURYF7/target.h b/src/main/target/FURYF7/target.h new file mode 100644 index 0000000000..8da6562712 --- /dev/null +++ b/src/main/target/FURYF7/target.h @@ -0,0 +1,176 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FYF7" + +#define CONFIG_START_FLASH_ADDRESS (0x080C0000) + +#define USBD_PRODUCT_STRING "FuryF7" + +#define USE_DSHOT + +#define LED0 PB5 +#define LED1 PB4 + +#define BEEPER PD10 +#define BEEPER_INVERTED + +#define USE_EXTI +#define MPU_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + +#define ICM20689_CS_PIN PA4 +#define ICM20689_SPI_INSTANCE SPI1 + +#define GYRO +#define USE_GYRO_SPI_ICM20689 +#define GYRO_ICM20689_ALIGN CW180_DEG + +#define ACC +#define USE_ACC_SPI_ICM20689 +#define ACC_ICM20689_ALIGN CW180_DEG + +//#define BARO +//#define USE_BARO_MS5611 +//#define MS5611_I2C_INSTANCE I2CDEV_1 + +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +//#define USE_SPI_DEVICE_2 +//#define SPI2_NSS_PIN PB12 +//#define SPI2_SCK_PIN PB13 +//#define SPI2_MISO_PIN PB14 +//#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_SPI_DEVICE_4 +#define SPI4_NSS_PIN PE11 +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 + +#define USE_SDCARD +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN PD2 +#define SDCARD_DETECT_EXTI_LINE EXTI_Line2 +#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2 +#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD +#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn + +#define SDCARD_SPI_INSTANCE SPI4 +#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN + +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 13.5MHz + +#define SDCARD_DMA_CHANNEL_TX DMA2_Stream1 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5 +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2 +#define SDCARD_DMA_CHANNEL DMA_CHANNEL_4 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PA15 +#define M25P16_SPI_INSTANCE SPI3 + +#define USE_VCP +#define VBUS_SENSING_PIN PC5 + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART3 +#define UART3_RX_PIN PD9 +#define UART3_TX_PIN PD8 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA +#define USE_I2C_PULLUP +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define VBAT_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define CURRENT_METER_ADC_PIN PC3 + +//#define LED_STRIP +//#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 + +// LED Strip can run off Pin 6 (PA0) of the ESC outputs. + +//#define WS2811_PIN PA1 +//#define WS2811_TIMER TIM5 +//#define WS2811_TIMER_CHANNEL TIM_CHANNEL_2 +//#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER +//#define WS2811_DMA_STREAM DMA1_Stream4 +//#define WS2811_DMA_FLAG DMA_FLAG_TCIF4 +//#define WS2811_DMA_IT DMA_IT_TCIF4 +//#define WS2811_DMA_CHANNEL DMA_CHANNEL_6 +//#define WS2811_DMA_IRQ DMA1_Stream4_IRQn + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define SENSORS_SET (SENSOR_ACC) + +#define DEFAULT_FEATURES (FEATURE_BLACKBOX) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define SPEKTRUM_BIND +// USART3 Rx, PB11 +#define BIND_PIN PB11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define USABLE_TIMER_CHANNEL_COUNT 5 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8)) \ No newline at end of file diff --git a/src/main/target/FURYF7/target.mk b/src/main/target/FURYF7/target.mk new file mode 100644 index 0000000000..77cfc3e5f7 --- /dev/null +++ b/src/main/target/FURYF7/target.mk @@ -0,0 +1,7 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += SDCARD VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_spi_icm20689.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_hal.c \ No newline at end of file diff --git a/src/main/target/IMPULSERCF3/target.c b/src/main/target/IMPULSERCF3/target.c index 04200bc0b4..6e8a09cba2 100644 --- a/src/main/target/IMPULSERCF3/target.c +++ b/src/main/target/IMPULSERCF3/target.c @@ -22,13 +22,13 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PPM/SERIAL RX - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM2 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM3 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM4 - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM5 - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM6 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // LED_STRIP + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1}, // PPM/SERIAL RX + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM2 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM3 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM4 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM5 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM6 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6}, // LED_STRIP }; diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 370f9eb358..5add051e06 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -23,22 +23,22 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, 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 - { 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 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, 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, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/ISHAPEDF3/target.c b/src/main/target/ISHAPEDF3/target.c index d998cdba92..5a4f973de0 100644 --- a/src/main/target/ISHAPEDF3/target.c +++ b/src/main/target/ISHAPEDF3/target.c @@ -23,25 +23,24 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM |TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, 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(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, 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, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3 - { 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 - - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index d36fa9903a..6c27661b0d 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -24,18 +24,18 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM15, IO_TAG(PB15), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_6, DMA1_Channel5, DMA1_CH5_HANDLER }, - { TIM8, IO_TAG(PB0), TIM_Channel_2, TIM8_CC_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_2, DMA2_Channel5, DMA2_CH5_HANDLER }, - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel2, DMA1_CH2_HANDLER }, - { TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER }, - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, + { TIM8, IO_TAG(PB0), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, + { TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel3, DMA1_CH3_HANDLER }, + { TIM15, IO_TAG(PB15), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel5, DMA1_CH5_HANDLER }, + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0}, - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0}, - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0}, - { TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_10, NULL, 0}, - { TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5, NULL, 0}, + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, + //{ TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_10, NULL, 0}, + //{ TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_5, NULL, 0}, }; diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index f8a6062776..fcb2c38a03 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -84,5 +84,5 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTF (BIT(4)) -#define USABLE_TIMER_CHANNEL_COUNT 12 +#define USABLE_TIMER_CHANNEL_COUNT 10 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index 07c5716f90..9352353f82 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -23,16 +23,16 @@ #include "drivers/timer.h" 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, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM11 - PB15 }; diff --git a/src/main/target/MICROSCISKY/target.c b/src/main/target/MICROSCISKY/target.c index e838c785ba..4319f6fb45 100644 --- a/src/main/target/MICROSCISKY/target.c +++ b/src/main/target/MICROSCISKY/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" 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, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0 }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6 }; diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h index 2628264522..f61806f3b7 100644 --- a/src/main/target/MICROSCISKY/target.h +++ b/src/main/target/MICROSCISKY/target.h @@ -91,7 +91,6 @@ #undef GPS #undef USE_SERVOS #define USE_QUAD_MIXER_ONLY -#define DISPLAY // IO - assuming all IOs on 48pin package diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index 43db149492..10cb9ad654 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -23,14 +23,14 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 6a7ae42a0b..93e92d61cb 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -91,7 +91,6 @@ #define SENSORS_SET (SENSOR_ACC) #undef GPS -#define DISPLAY #define USE_FLASHFS #define USE_FLASH_M25P16 diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index af48f988d7..c9bc95fe04 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" 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, 1, IOCFG_IPD }, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_IPD }, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_IPD }, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_IPD } // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0 }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1 } // PWM14 - OUT6 }; diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index eb8ab5503a..d7586fe858 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -118,8 +118,6 @@ //#define SONAR_TRIGGER_PIN_PWM PB8 //#define SONAR_ECHO_PIN_PWM PB9 -//#define DISPLAY - #define USE_UART1 #define USE_UART2 /* only 2 uarts available on the NAZE, add ifdef here if present on other boards */ diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index c194fc9752..0e15861a61 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -25,18 +25,18 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM Pad - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PPM - PB4 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent - { TIM8, IO_TAG(PB8), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8 - { TIM8, IO_TAG(PB9), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2 + { TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8 + { TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2 // UART3 RX/TX - //{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7) - //{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7) - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6 - //{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP + //{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7) + //{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7) + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6 + //{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 9bc30bf941..13c52bed2f 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -92,6 +92,8 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 +#define USE_DASHBOARD + // Configuratoin Menu System #define CMS @@ -138,9 +140,13 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. +#define USE_DSHOT + +// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative +#ifndef USE_DSHOT #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 +#endif // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING @@ -154,8 +160,6 @@ //#define RSSI_ADC_PIN PB1 //#define ADC_INSTANCE ADC3 -#define USE_DSHOT - #define LED_STRIP #define WS2811_PIN PA8 #define WS2811_TIMER TIM1 diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index 5e63b90590..e088371565 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -24,17 +24,17 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port) - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3 - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port) + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT }; diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c index 43db149492..10cb9ad654 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/PIKOBLX/target.c @@ -23,14 +23,14 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/RACEBASE/target.c b/src/main/target/RACEBASE/target.c index cc2c688932..dc726133e3 100755 --- a/src/main/target/RACEBASE/target.c +++ b/src/main/target/RACEBASE/target.c @@ -23,12 +23,11 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, - - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM2 - PC6 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM3 - PC7 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PMW4 - PC8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 1, GPIO_AF_1}, + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM2 - PC6 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM3 - PC7 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PMW4 - PC8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM5 - PC9 }; diff --git a/src/main/target/RCEXPLORERF3/target.c b/src/main/target/RCEXPLORERF3/target.c index 8ac51e6713..730d71b682 100644 --- a/src/main/target/RCEXPLORERF3/target.c +++ b/src/main/target/RCEXPLORERF3/target.c @@ -24,10 +24,10 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM1 - PA4 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - PA7 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM3 - PA8 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM4 - PB0 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PB1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM6 - PPM + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM1 - PA4 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM2 - PA7 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6}, // PWM3 - PA8 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM4 - PB0 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM5 - PB1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1}, // PWM6 - PPM }; diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h index a1f5f8527d..2f19300b0d 100644 --- a/src/main/target/RCEXPLORERF3/target.h +++ b/src/main/target/RCEXPLORERF3/target.h @@ -130,7 +130,6 @@ #define TELEMETRY #define SERIAL_RX #define AUTOTUNE -#define DISPLAY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index f8be6e2eab..66da4ce854 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -24,16 +24,16 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port) - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port) + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT }; diff --git a/src/main/target/REVONANO/target.c b/src/main/target/REVONANO/target.c index 9349b40100..1ddf9641cc 100644 --- a/src/main/target/REVONANO/target.c +++ b/src/main/target/REVONANO/target.c @@ -23,18 +23,18 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // PPM - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_IN - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S4_IN - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_IN - { TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN - { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_OUT - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S2_OUT - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S3_OUT - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM2 }, // PPM + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S5_IN + { TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN + { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S1_OUT + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S3_OUT + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S4_OUT + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 }, // S5_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT }; diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 61603c7b4e..72523ef2b9 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -23,22 +23,22 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, 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 - { 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 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, 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, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c index 0926431f19..7176e7bc7d 100644 --- a/src/main/target/SINGULARITY/target.c +++ b/src/main/target/SINGULARITY/target.c @@ -23,15 +23,15 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PPM/SERIAL RX - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 RX (NC) - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 TX - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // LED_STRIP + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM/SERIAL RX + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // SOFTSERIAL1 RX (NC) + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // SOFTSERIAL1 TX + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // LED_STRIP }; diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c index be26986a86..2927c0b960 100644 --- a/src/main/target/SIRINFPV/target.c +++ b/src/main/target/SIRINFPV/target.c @@ -24,15 +24,13 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PB6 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB6 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 - - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4 - - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PB6 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB6 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4 + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y }; diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 9a9f16e331..d1fb69fc83 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -137,6 +137,8 @@ //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_DASHBOARD + #define OSD // Configuratoin Menu System diff --git a/src/main/target/SOULF4/target.c b/src/main/target/SOULF4/target.c index f0673d116c..0b8819b4a3 100644 --- a/src/main/target/SOULF4/target.c +++ b/src/main/target/SOULF4/target.c @@ -22,16 +22,16 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port) - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3 - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_IN - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S6_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 + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port) + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S3_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S6_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT }; diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index 44aa07090a..f7a44f00d7 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -24,18 +24,18 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // 6 3-pin headers - { 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 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 // PWM7 - PMW10 - { 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 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // 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, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 }; diff --git a/src/main/target/SPARKY2/target.c b/src/main/target/SPARKY2/target.c index 87abe2834b..359c09910c 100644 --- a/src/main/target/SPARKY2/target.c +++ b/src/main/target/SPARKY2/target.c @@ -23,17 +23,16 @@ #include "drivers/timer.h" 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 - - { 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 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM8 }, // PPM IN + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT }; diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index b96e424066..fe9518d8a9 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -24,25 +24,25 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // 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, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // 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, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + // Production boards swapped RC_CH3/4 swapped to make it easierTIM_USE_MOTOR, to using supplied cables - compared to first prototype. + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // 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, DMA1_Channel7, DMA1_CH7_HANDLER }, // 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, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 7a53ebdbcd..da2e8eaca6 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -140,6 +140,8 @@ #define USABLE_TIMER_CHANNEL_COUNT 17 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define USE_DASHBOARD + // Configuratoin Menu System #define CMS diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index 16541c9aeb..3aeac1bd84 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -24,17 +24,17 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM / UART2 RX - { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8 - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM3 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM8 + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 13e7ee222c..6d40631b0a 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -25,27 +25,27 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM Pad #ifdef SPRACINGF3MINI_MKII_REVA - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB5 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM - PB5 // PB4 / TIM3 CH1 is connected to USBPresent #else - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB4 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent #endif - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM5 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM6 - PA3 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM5 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM6 - PA3 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, 1, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, 1, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) // LED Strip Pad - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 8cd9a3584f..54a5dbded7 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -24,19 +24,19 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, NULL, 0 }, - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, NULL, 0 }, - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER }, - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, NULL, 0 }, - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, NULL, 0 }, - { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, - { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, - { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, - { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 } + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, 0, GPIO_AF_1, NULL, 0 }, + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER }, + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 }, + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, 0, GPIO_AF_1, NULL, 0 }, + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, 0, GPIO_AF_1, NULL, 0 } }; diff --git a/src/main/target/VRRACE/target.c b/src/main/target/VRRACE/target.c index af85c900d0..c5fc07b418 100644 --- a/src/main/target/VRRACE/target.c +++ b/src/main/target/VRRACE/target.c @@ -23,17 +23,16 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PPM - { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S2_IN - { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S3_IN - { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S4_IN - { TIM9, IO_TAG(PE6), TIM_Channel_1, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S5_IN - { TIM9, IO_TAG(PE7), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S6_IN - - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S1_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S2_OUT - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S4_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT + { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PPM + { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S2_IN + { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S3_IN + { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S4_IN + { TIM9, IO_TAG(PE6), TIM_Channel_1, TIM1_BRK_TIM9_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S5_IN + { TIM9, IO_TAG(PE7), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S6_IN + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S3_OUT + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S4_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S5_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S6_OUT }; diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index b59d0ba6a3..d83ee38e58 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -8,22 +8,20 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, 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(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - - { 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 - - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, 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, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/YUPIF4/target.c b/src/main/target/YUPIF4/target.c index 951a147791..20dbd87572 100644 --- a/src/main/target/YUPIF4/target.c +++ b/src/main/target/YUPIF4/target.c @@ -22,11 +22,11 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM IN - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // MS1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // MS2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // MS3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // MS4 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // MS5 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // MS6 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8 }, // PPM IN + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // MS1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // MS2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // MS3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // MS4 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // MS5 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // MS6 }; diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c index d6197448da..9f99cf2be4 100644 --- a/src/main/target/ZCOREF3/target.c +++ b/src/main/target/ZCOREF3/target.c @@ -8,24 +8,22 @@ #include "drivers/timer.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, 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 - - { 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 - - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, 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, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/common.h b/src/main/target/common.h index 8d0ea828d2..42dfed36de 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -55,7 +55,7 @@ #endif #if (FLASH_SIZE > 128) -#define DISPLAY +#define USE_DASHBOARD #define TELEMETRY_MAVLINK #else #define SKIP_CLI_COMMAND_HELP diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index c54f0f3c2a..b9023cc6d2 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -14,6 +14,7 @@ #include "common/axis.h" #include "common/color.h" #include "common/maths.h" +#include "common/utils.h" #include "drivers/system.h" #include "drivers/sensor.h" @@ -23,6 +24,7 @@ #include "fc/config.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" +#include "fc/fc_msp.h" #include "io/beeper.h" #include "io/motors.h" @@ -53,6 +55,8 @@ #include "config/config_profile.h" #include "config/feature.h" +#include "msp/msp.h" + extern profile_t *currentProfile; extern controlRateConfig_t *currentControlRateProfile; @@ -67,7 +71,13 @@ enum enum { FSSP_START_STOP = 0x7E, + + FSSP_DLE = 0x7D, + FSSP_DLE_XOR = 0x20, + FSSP_DATA_FRAME = 0x10, + FSSP_MSPC_FRAME = 0x30, // MSP client frame + FSSP_MSPS_FRAME = 0x32, // MSP server frame // ID of sensor. Must be something that is polled by FrSky RX FSSP_SENSOR_ID1 = 0x1B, @@ -149,33 +159,116 @@ static uint8_t smartPortHasRequest = 0; static uint8_t smartPortIdCnt = 0; static uint32_t smartPortLastRequestTime = 0; +typedef struct smartPortFrame_s { + uint8_t sensorId; + uint8_t frameId; + uint16_t valueId; + uint32_t data; + uint8_t crc; +} __attribute__((packed)) smartPortFrame_t; + +#define SMARTPORT_FRAME_SIZE sizeof(smartPortFrame_t) +#define SMARTPORT_TX_BUF_SIZE 256 + +#define SMARTPORT_PAYLOAD_OFFSET offsetof(smartPortFrame_t, valueId) +#define SMARTPORT_PAYLOAD_SIZE (SMARTPORT_FRAME_SIZE - SMARTPORT_PAYLOAD_OFFSET - 1) + +static smartPortFrame_t smartPortRxBuffer; +static uint8_t smartPortRxBytes = 0; +static bool smartPortFrameReceived = false; + +#define SMARTPORT_MSP_VERSION 1 +#define SMARTPORT_MSP_VER_SHIFT 5 +#define SMARTPORT_MSP_VER_MASK (0x7 << SMARTPORT_MSP_VER_SHIFT) +#define SMARTPORT_MSP_VERSION_S (SMARTPORT_MSP_VERSION << SMARTPORT_MSP_VER_SHIFT) + +#define SMARTPORT_MSP_ERROR_FLAG (1 << 5) +#define SMARTPORT_MSP_START_FLAG (1 << 4) +#define SMARTPORT_MSP_SEQ_MASK 0x0F + +#define SMARTPORT_MSP_RX_BUF_SIZE 64 + +static uint8_t smartPortMspTxBuffer[SMARTPORT_TX_BUF_SIZE]; +static mspPacket_t smartPortMspReply; +static bool smartPortMspReplyPending = false; + +#define SMARTPORT_MSP_RES_ERROR (-10) + +enum { + SMARTPORT_MSP_VER_MISMATCH=0, + SMARTPORT_MSP_CRC_ERROR=1, + SMARTPORT_MSP_ERROR=2 +}; + static void smartPortDataReceive(uint16_t c) { + static bool skipUntilStart = true; + static bool byteStuffing = false; + static uint16_t checksum = 0; + uint32_t now = millis(); - // look for a valid request sequence - static uint8_t lastChar; - if (lastChar == FSSP_START_STOP) { - smartPortState = SPSTATE_WORKING; - if (c == FSSP_SENSOR_ID1 && (serialRxBytesWaiting(smartPortSerialPort) == 0)) { + if (c == FSSP_START_STOP) { + smartPortRxBytes = 0; + smartPortHasRequest = 0; + skipUntilStart = false; + return; + } else if (skipUntilStart) { + return; + } + + uint8_t* rxBuffer = (uint8_t*)&smartPortRxBuffer; + if (smartPortRxBytes == 0) { + if ((c == FSSP_SENSOR_ID1) && (serialRxBytesWaiting(smartPortSerialPort) == 0)) { + + // our slot is starting... smartPortLastRequestTime = now; smartPortHasRequest = 1; - // we only responde to these IDs - // the X4R-SB does send other IDs, we ignore them, but take note of the time + } else if (c == FSSP_SENSOR_ID2) { + rxBuffer[smartPortRxBytes++] = c; + checksum = 0; + } + else { + skipUntilStart = true; + } + } + else { + + if (c == FSSP_DLE) { + byteStuffing = true; + return; + } + + if (byteStuffing) { + c ^= FSSP_DLE_XOR; + byteStuffing = false; + } + + rxBuffer[smartPortRxBytes++] = c; + + if(smartPortRxBytes == SMARTPORT_FRAME_SIZE) { + if (c == (0xFF - checksum)) { + smartPortFrameReceived = true; + } + skipUntilStart = true; + } else if (smartPortRxBytes < SMARTPORT_FRAME_SIZE) { + checksum += c; + checksum += checksum >> 8; + checksum &= 0x00FF; } } - lastChar = c; } static void smartPortSendByte(uint8_t c, uint16_t *crcp) { // smart port escape sequence - if (c == 0x7D || c == 0x7E) { - serialWrite(smartPortSerialPort, 0x7D); - c ^= 0x20; + if (c == FSSP_DLE || c == FSSP_START_STOP) { + serialWrite(smartPortSerialPort, FSSP_DLE); + serialWrite(smartPortSerialPort, c ^ FSSP_DLE_XOR); + } + else { + serialWrite(smartPortSerialPort, c); } - - serialWrite(smartPortSerialPort, c); if (crcp == NULL) return; @@ -187,21 +280,30 @@ static void smartPortSendByte(uint8_t c, uint16_t *crcp) *crcp = crc; } -static void smartPortSendPackage(uint16_t id, uint32_t val) +static void smartPortSendPackageEx(uint8_t frameId, uint8_t* data) { uint16_t crc = 0; - smartPortSendByte(FSSP_DATA_FRAME, &crc); - uint8_t *u8p = (uint8_t*)&id; - smartPortSendByte(u8p[0], &crc); - smartPortSendByte(u8p[1], &crc); - u8p = (uint8_t*)&val; - smartPortSendByte(u8p[0], &crc); - smartPortSendByte(u8p[1], &crc); - smartPortSendByte(u8p[2], &crc); - smartPortSendByte(u8p[3], &crc); + smartPortSendByte(frameId, &crc); + for(unsigned i = 0; i < SMARTPORT_PAYLOAD_SIZE; i++) { + smartPortSendByte(*data++, &crc); + } smartPortSendByte(0xFF - (uint8_t)crc, NULL); } +static void smartPortSendPackage(uint16_t id, uint32_t val) +{ + uint8_t payload[SMARTPORT_PAYLOAD_SIZE]; + uint8_t *dst = payload; + *dst++ = id & 0xFF; + *dst++ = id >> 8; + *dst++ = val & 0xFF; + *dst++ = (val >> 8) & 0xFF; + *dst++ = (val >> 16) & 0xFF; + *dst++ = (val >> 24) & 0xFF; + + smartPortSendPackageEx(FSSP_DATA_FRAME,payload); +} + void initSmartPortTelemetry(telemetryConfig_t *initialTelemetryConfig) { telemetryConfig = initialTelemetryConfig; @@ -267,6 +369,196 @@ void checkSmartPortTelemetryState(void) freeSmartPortTelemetryPort(); } +static void initSmartPortMspReply(int16_t cmd) +{ + smartPortMspReply.buf.ptr = smartPortMspTxBuffer; + smartPortMspReply.buf.end = ARRAYEND(smartPortMspTxBuffer); + + smartPortMspReply.cmd = cmd; + smartPortMspReply.result = 0; +} + +static void processMspPacket(mspPacket_t* packet) +{ + initSmartPortMspReply(0); + + if (mspFcProcessCommand(packet, &smartPortMspReply, NULL) == MSP_RESULT_ERROR) { + sbufWriteU8(&smartPortMspReply.buf, SMARTPORT_MSP_ERROR); + } + + // change streambuf direction + sbufSwitchToReader(&smartPortMspReply.buf, smartPortMspTxBuffer); + smartPortMspReplyPending = true; +} + +/** + * Request frame format: + * - Header: 1 byte + * - Reserved: 2 bits (future use) + * - Error-flag: 1 bit + * - Start-flag: 1 bit + * - CSeq: 4 bits + * + * - MSP payload: + * - if Error-flag == 0: + * - size: 1 byte + * - payload + * - CRC (request type included) + * - if Error-flag == 1: + * - size: 1 byte (== 1) + * - error: 1 Byte + * - 0: Version mismatch (type=0) + * - 1: Sequence number error + * - 2: MSP error + * - CRC (request type included) + */ +bool smartPortSendMspReply() +{ + static uint8_t checksum = 0; + static uint8_t seq = 0; + + uint8_t packet[SMARTPORT_PAYLOAD_SIZE]; + uint8_t* p = packet; + uint8_t* end = p + SMARTPORT_PAYLOAD_SIZE; + + sbuf_t* txBuf = &smartPortMspReply.buf; + + // detect first reply packet + if (txBuf->ptr == smartPortMspTxBuffer) { + + // header + uint8_t head = SMARTPORT_MSP_START_FLAG | (seq++ & SMARTPORT_MSP_SEQ_MASK); + if (smartPortMspReply.result < 0) { + head |= SMARTPORT_MSP_ERROR_FLAG; + } + *p++ = head; + + uint8_t size = sbufBytesRemaining(txBuf); + *p++ = size; + + checksum = size ^ smartPortMspReply.cmd; + } + else { + // header + *p++ = (seq++ & SMARTPORT_MSP_SEQ_MASK); + } + + while ((p < end) && (sbufBytesRemaining(txBuf) > 0)) { + *p = sbufReadU8(txBuf); + checksum ^= *p++; // MSP checksum + } + + // to be continued... + if (p == end) { + smartPortSendPackageEx(FSSP_MSPS_FRAME,packet); + return true; + } + + // nothing left in txBuf, + // append the MSP checksum + *p++ = checksum; + + // pad with zeros + while (p < end) + *p++ = 0; + + smartPortSendPackageEx(FSSP_MSPS_FRAME,packet); + return false; +} + +void smartPortSendErrorReply(uint8_t error, int16_t cmd) +{ + initSmartPortMspReply(cmd); + sbufWriteU8(&smartPortMspReply.buf,error); + smartPortMspReply.result = SMARTPORT_MSP_RES_ERROR; + + sbufSwitchToReader(&smartPortMspReply.buf, smartPortMspTxBuffer); + smartPortMspReplyPending = true; +} + +/** + * Request frame format: + * - Header: 1 byte + * - Version: 3 bits + * - Start-flag: 1 bit + * - CSeq: 4 bits + * + * - MSP payload: + * - Size: 1 Byte + * - Type: 1 Byte + * - payload... + * - CRC + */ +void handleSmartPortMspFrame(smartPortFrame_t* sp_frame) +{ + static uint8_t mspBuffer[SMARTPORT_MSP_RX_BUF_SIZE]; + static uint8_t mspStarted = 0; + static uint8_t lastSeq = 0; + static uint8_t checksum = 0; + static mspPacket_t cmd; + + // re-assemble MSP frame & forward to MSP port when complete + uint8_t* p = ((uint8_t*)sp_frame) + SMARTPORT_PAYLOAD_OFFSET; + uint8_t* end = p + SMARTPORT_PAYLOAD_SIZE; + + uint8_t head = *p++; + uint8_t seq = head & SMARTPORT_MSP_SEQ_MASK; + uint8_t version = (head & SMARTPORT_MSP_VER_MASK) >> SMARTPORT_MSP_VER_SHIFT; + + if (version != SMARTPORT_MSP_VERSION) { + mspStarted = 0; + smartPortSendErrorReply(SMARTPORT_MSP_VER_MISMATCH,0); + return; + } + + // check start-flag + if (head & SMARTPORT_MSP_START_FLAG) { + + //TODO: if (p_size > SMARTPORT_MSP_RX_BUF_SIZE) error! + uint8_t p_size = *p++; + cmd.cmd = *p++; + cmd.result = 0; + + cmd.buf.ptr = mspBuffer; + cmd.buf.end = mspBuffer + p_size; + + checksum = p_size ^ cmd.cmd; + mspStarted = 1; + } else if (!mspStarted) { + // no start packet yet, throw this one away + return; + } else if (((lastSeq + 1) & SMARTPORT_MSP_SEQ_MASK) != seq) { + // packet loss detected! + mspStarted = 0; + return; + } + + // copy payload bytes + while ((p < end) && sbufBytesRemaining(&cmd.buf)) { + checksum ^= *p; + sbufWriteU8(&cmd.buf,*p++); + } + + // reached end of smart port frame + if (p == end) { + lastSeq = seq; + return; + } + + // last byte must be the checksum + if (checksum != *p) { + mspStarted = 0; + smartPortSendErrorReply(SMARTPORT_MSP_CRC_ERROR,cmd.cmd); + return; + } + + // end of MSP packet reached + mspStarted = 0; + sbufSwitchToReader(&cmd.buf,mspBuffer); + + processMspPacket(&cmd); +} + void handleSmartPortTelemetry(void) { uint32_t smartPortLastServiceTime = millis(); @@ -292,6 +584,17 @@ void handleSmartPortTelemetry(void) return; } + if(smartPortFrameReceived) { + smartPortFrameReceived = false; + // do not check the physical ID here again + // unless we start receiving other sensors' packets + if(smartPortRxBuffer.frameId == FSSP_MSPC_FRAME) { + + // Pass only the payload: skip sensorId & frameId + handleSmartPortMspFrame(&smartPortRxBuffer); + } + } + while (smartPortHasRequest) { // Ensure we won't get stuck in the loop if there happens to be nothing available to send in a timely manner - dump the slot if we loop in there for too long. if ((millis() - smartPortLastServiceTime) > SMARTPORT_SERVICE_TIMEOUT_MS) { @@ -299,6 +602,12 @@ void handleSmartPortTelemetry(void) return; } + if(smartPortMspReplyPending) { + smartPortMspReplyPending = smartPortSendMspReply(); + smartPortHasRequest = 0; + return; + } + // we can send back any data we want, our table keeps track of the order and frequency of each data type we send uint16_t id = frSkyDataIdTable[smartPortIdCnt]; if (id == 0) { // end of table reached, loop back @@ -308,7 +617,7 @@ void handleSmartPortTelemetry(void) smartPortIdCnt++; int32_t tmpi; - uint32_t tmp2; + uint32_t tmp2 = 0; static uint8_t t1Cnt = 0; static uint8_t t2Cnt = 0; @@ -455,13 +764,10 @@ void handleSmartPortTelemetry(void) smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + GPS_numSat); smartPortHasRequest = 0; #endif - } - else if (feature(FEATURE_GPS)) { + } else if (feature(FEATURE_GPS)) { smartPortSendPackage(id, 0); smartPortHasRequest = 0; - } - - else if (telemetryConfig->pidValuesAsTelemetry){ + } else if (telemetryConfig->pidValuesAsTelemetry){ switch (t2Cnt) { case 0: tmp2 = currentProfile->pidProfile.P8[ROLL]; diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index dbddd6850c..3723a7bc65 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -48,7 +48,6 @@ extern uint32_t APP_Rx_ptr_in; APP TX is the circular buffer for data that is transmitted from the APP (host) to the USB device (flight controller). */ -#define APP_TX_DATA_SIZE 1024 static uint8_t APP_Tx_Buffer[APP_TX_DATA_SIZE]; static uint32_t APP_Tx_ptr_out = 0; static uint32_t APP_Tx_ptr_in = 0; @@ -195,7 +194,9 @@ static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len) APP_Rx_Buffer[APP_Rx_ptr_in] = Buf[i]; APP_Rx_ptr_in = (APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE; - while (CDC_Send_FreeBytes() <= 0); + while (CDC_Send_FreeBytes() == 0) { + delay(1); + } } return USBD_OK; @@ -247,15 +248,11 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) return USBD_FAIL; } - __disable_irq(); - for (uint32_t i = 0; i < Len; i++) { APP_Tx_Buffer[APP_Tx_ptr_in] = Buf[i]; APP_Tx_ptr_in = (APP_Tx_ptr_in + 1) % APP_TX_DATA_SIZE; } - __enable_irq(); - return USBD_OK; } diff --git a/src/main/vcpf4/usbd_conf.h b/src/main/vcpf4/usbd_conf.h index 87481c2ef1..d062c1e431 100644 --- a/src/main/vcpf4/usbd_conf.h +++ b/src/main/vcpf4/usbd_conf.h @@ -42,19 +42,21 @@ /* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */ #ifdef USE_USB_OTG_HS - #define CDC_DATA_MAX_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */ - #define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */ +#define CDC_DATA_MAX_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */ +#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */ - #define CDC_IN_FRAME_INTERVAL 40 /* Number of micro-frames between IN transfers */ - #define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer: +#define CDC_IN_FRAME_INTERVAL 40 /* Number of micro-frames between IN transfers */ +#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer: APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL*8 */ +#define APP_TX_DATA_SIZE 2048 /* total size of the OUT (inbound to FC) buffer */ #else - #define CDC_DATA_MAX_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */ - #define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */ +#define CDC_DATA_MAX_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */ +#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */ - #define CDC_IN_FRAME_INTERVAL 15 /* Number of frames between IN transfers */ - #define APP_RX_DATA_SIZE 1024 /* Total size of IN buffer: +#define CDC_IN_FRAME_INTERVAL 15 /* Number of frames between IN transfers */ +#define APP_RX_DATA_SIZE 2048 /* Total size of IN (outbound from FC) buffer: APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL */ +#define APP_TX_DATA_SIZE 2048 /* total size of the OUT (inbound to FC) buffer */ #endif /* USE_USB_OTG_HS */ #define APP_FOPS VCP_fops diff --git a/src/test/SpMsp.lua b/src/test/SpMsp.lua new file mode 100644 index 0000000000..93b47131be --- /dev/null +++ b/src/test/SpMsp.lua @@ -0,0 +1,207 @@ +-- +-- Test script for the MSP/SPORT bridge +-- + +-- Protocol version +SPORT_MSP_VERSION = 1 + +-- Sensor ID used by the local LUA script +LOCAL_SENSOR_ID = 0x0D + +-- Sensor ID used by the MSP server (BF, CF, MW, etc...) +REMOTE_SENSOR_ID = 0x1B + +REQUEST_FRAME_ID = 0x30 +REPLY_FRAME_ID = 0x32 + +-- Sequence number for next MSP/SPORT packet +local sportMspSeq = 0 + +local mspRxBuf = {} +local mspRxIdx = 1 +local mspRxCRC = 0 +local mspStarted = false + +-- Stats +mspRequestsSent = 0 +mspRepliesReceived = 0 +mspPkRxed = 0 +mspErrorPk = 0 +mspStartPk = 0 +mspOutOfOrder = 0 +mspCRCErrors = 0 + +local function mspResetStats() + mspRequestsSent = 0 + mspRepliesReceived = 0 + mspPkRxed = 0 + mspErrorPk = 0 + mspStartPk = 0 + mspOutOfOrderPk = 0 + mspCRCErrors = 0 +end + +local function mspSendRequest(cmd) + + local dataId = 0 + dataId = sportMspSeq -- sequence number + dataId = dataId + bit32.lshift(1,4) -- start flag + dataId = dataId + bit32.lshift(SPORT_MSP_VERSION,5) -- MSP/SPORT version + -- size is 0 for now, no need to add it to dataId + -- dataId = dataId + bit32.lshift(0,8) + sportMspSeq = bit32.band(sportMspSeq + 1, 0x0F) + + local value = 0 + value = bit32.band(cmd,0xFF) -- MSP command + value = value + bit32.lshift(cmd,8) -- CRC + + mspRequestsSent = requestsSent + 1 + return sportTelemetryPush(LOCAL_SENSOR_ID, REQUEST_FRAME_ID, dataId, value) +end + +local function mspReceivedReply(payload) + + mspPkRxed = mspPkRxed + 1 + + local idx = 1 + local head = payload[idx] + local err_flag = (bit32.band(head,0x20) ~= 0) + idx = idx + 1 + + if err_flag then + -- error flag set + mspStarted = false + + mspErrorPk = mspErrorPk + 1 + + -- return error + -- CRC checking missing + + --return payload[idx] + return nil + end + + local start = (bit32.band(head,0x10) ~= 0) + local seq = bit32.band(head,0x0F) + + if start then + -- start flag set + mspRxIdx = 1 + mspRxBuf = {} + + mspRxSize = payload[idx] + mspRxCRC = mspRxSize + idx = idx + 1 + mspStarted = true + + mspStartPk = mspStartPk + 1 + + elseif not mspStarted then + mspOutOfOrder = mspOutOfOrder + 1 + return nil + + elseif bit32.band(lastSeq+1,0x0F) ~= seq then + mspOutOfOrder = mspOutOfOrder + 1 + mspStarted = false + return nil + end + + while (idx <= 6) and (mspRxIdx <= mspRxSize) do + mspRxBuf[mspRxIdx] = payload[idx] + mspRxCRC = bit32.bxor(mspRxCRC,payload[idx]) + mspRxIdx = mspRxIdx + 1 + idx = idx + 1 + end + + if idx > 6 then + lastRxSeq = seq + return + end + + -- check CRC + if mspRxCRC ~= payload[idx] then + mspStarted = false + mspCRCErrors = mspCRCErrors + 1 + end + + mspRepliesReceived = mspRepliesReceived + 1 + mspStarted = false + return mspRxBuf +end + +local function mspPollReply() + local sensorId, frameId, dataId, value = sportTelemetryPop() + if sensorId == REMOTE_SENSOR_ID and frameId == REPLY_FRAME_ID then + + local payload = {} + payload[1] = bit32.band(dataId,0xFF) + dataId = bit32.rshift(dataId,8) + payload[2] = bit32.band(dataId,0xFF) + + payload[3] = bit32.band(value,0xFF) + value = bit32.rshift(value,8) + payload[4] = bit32.band(value,0xFF) + value = bit32.rshift(value,8) + payload[5] = bit32.band(value,0xFF) + value = bit32.rshift(value,8) + payload[6] = bit32.band(value,0xFF) + + return mspReceivedReply(payload) + end +end + +local lastReqTS = 0 + +local function run(event) + + local now = getTime() + + if event == EVT_MINUS_FIRST or event == EVT_ROT_LEFT or event == EVT_MINUS_REPT then + requestsSent = 0 + repliesReceived = 0 + mspReceivedReply_cnt = 0 + mspReceivedReply_cnt1 = 0 + mspReceivedReply_cnt2 = 0 + mspReceivedReply_cnt3 = 0 + end + + lcd.clear() + + -- do we have valid telemetry data? + if getValue("rssi") > 0 then + + -- draw screen + lcd.drawText(1,11,"Requests:",0) + lcd.drawNumber(60,11,mspRequestsSent) + + lcd.drawText(1,21,"Replies:",0) + lcd.drawNumber(60,21,mspRepliesReceived) + + lcd.drawText(1,31,"PkRxed:",0) + lcd.drawNumber(30,31,mspPkRxed) + + lcd.drawText(1,41,"ErrorPk:",0) + lcd.drawNumber(30,41,mspErrorPk) + + lcd.drawText(71,31,"StartPk:",0) + lcd.drawNumber(100,31,mspStartPk) + + lcd.drawText(71,41,"OutOfOrder:",0) + lcd.drawNumber(100,41,mspOutOfOrder) + + lcd.drawText(1,51,"CRCErrors:",0) + lcd.drawNumber(30,51,mspCRCErrors) + + -- last request is at least 2s old + if lastReqTS + 200 <= now then + mspSendRequest(117) -- MSP_PIDNAMES + lastReqTS = now + end + else + lcd.drawText(20,30,"No telemetry signal", XXLSIZE + BLINK) + end + + pollReply() +end + +return {run=run}