diff --git a/boards/px4/fmu-v3/src/CMakeLists.txt b/boards/px4/fmu-v3/src/CMakeLists.txt index cd2ab00c64..beb8034f8a 100644 --- a/boards/px4/fmu-v3/src/CMakeLists.txt +++ b/boards/px4/fmu-v3/src/CMakeLists.txt @@ -37,7 +37,7 @@ add_library(drivers_board init.c led.c spi.c - timer_config.c + timer_config.cpp usb.c manifest.c ) diff --git a/boards/px4/fmu-v3/src/board_config.h b/boards/px4/fmu-v3/src/board_config.h index f09140ab50..7d0c52c066 100644 --- a/boards/px4/fmu-v3/src/board_config.h +++ b/boards/px4/fmu-v3/src/board_config.h @@ -374,23 +374,6 @@ #define BOARD_BATTERY1_V_DIV (10.177939394f) #define BOARD_BATTERY1_A_PER_V (15.391030303f) -/* User GPIOs - * - * GPIO0-5 are the PWM servo outputs. - */ -#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14) -#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13) -#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) -#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9) -#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13) -#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14) -#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) -#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) -#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) -#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) -#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) -#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) - /* Power supply control and monitoring GPIOs */ #define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) #define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5) @@ -407,32 +390,8 @@ #define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) /* PWM - * - * Six PWM outputs are configured. - * - * Pins: - * - * CH1 : PE14 : TIM1_CH4 - * CH2 : PE13 : TIM1_CH3 - * CH3 : PE11 : TIM1_CH2 - * CH4 : PE9 : TIM1_CH1 - * CH5 : PD13 : TIM4_CH2 - * CH6 : PD14 : TIM4_CH3 */ -#define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) -#define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) -#define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) -#define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) -#define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13) -#define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14) #define DIRECT_PWM_OUTPUT_CHANNELS 6 - -#define GPIO_TIM1_CH1IN GPIO_TIM1_CH1IN_2 -#define GPIO_TIM1_CH2IN GPIO_TIM1_CH2IN_2 -#define GPIO_TIM1_CH3IN GPIO_TIM1_CH3IN_2 -#define GPIO_TIM1_CH4IN GPIO_TIM1_CH4IN_2 -#define GPIO_TIM4_CH2IN GPIO_TIM4_CH2IN_2 -#define GPIO_TIM4_CH3IN GPIO_TIM4_CH3IN_2 #define DIRECT_INPUT_TIMER_CHANNELS 6 /* USB OTG FS diff --git a/boards/px4/fmu-v3/src/init.c b/boards/px4/fmu-v3/src/init.c index a290ad1d85..7fb8f87663 100644 --- a/boards/px4/fmu-v3/src/init.c +++ b/boards/px4/fmu-v3/src/init.c @@ -72,6 +72,7 @@ #include +#include #include #include @@ -136,14 +137,11 @@ __EXPORT void board_peripheral_reset(int ms) __EXPORT void board_on_reset(int status) { UNUSED(status); - /* configure the GPIO pins to outputs and keep them low */ - stm32_configgpio(GPIO_GPIO0_OUTPUT); - stm32_configgpio(GPIO_GPIO1_OUTPUT); - stm32_configgpio(GPIO_GPIO2_OUTPUT); - stm32_configgpio(GPIO_GPIO3_OUTPUT); - stm32_configgpio(GPIO_GPIO4_OUTPUT); - stm32_configgpio(GPIO_GPIO5_OUTPUT); + /* configure the GPIO pins to outputs and keep them low */ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } /* On resets invoked from system (not boot) insure we establish a low * output state (discharge the pins) on PWM pins before they become inputs. diff --git a/boards/px4/fmu-v3/src/timer_config.c b/boards/px4/fmu-v3/src/timer_config.c deleted file mode 100644 index 67e93ef04c..0000000000 --- a/boards/px4/fmu-v3/src/timer_config.c +++ /dev/null @@ -1,140 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * - * 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 PX4 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 OWNER 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. - * - ****************************************************************************/ - -/* - * @file px4fmu_timer_config.c - * - * Configuration data for the stm32 pwm_servo, input capture and pwm input driver. - * - * Note that these arrays must always be fully-sized. - */ - -#include - -#include -#include -#include - -#include -#include - -#include "board_config.h" - -__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = { - { - .base = STM32_TIM1_BASE, - .clock_register = STM32_RCC_APB2ENR, - .clock_bit = RCC_APB2ENR_TIM1EN, - .clock_freq = STM32_APB2_TIM1_CLKIN, - .vectorno = STM32_IRQ_TIM1CC, - .dshot = { - .dma_base = STM32_DMA2_BASE, - .dmamap = DMAMAP_TIM1_UP, - } - }, - { - .base = STM32_TIM4_BASE, - .clock_register = STM32_RCC_APB1ENR, - .clock_bit = RCC_APB1ENR_TIM4EN, - .clock_freq = STM32_APB1_TIM4_CLKIN, - .vectorno = STM32_IRQ_TIM4, - .dshot = { - .dma_base = STM32_DMA1_BASE, - .dmamap = DMAMAP_TIM4_UP, - } - } -}; - -__EXPORT const io_timers_channel_mapping_t io_timers_channel_mapping = { - .element = { - { - .first_channel_index = 0, - .channel_count = 4, - }, - { - .first_channel_index = 4, - .channel_count = 2, - } - } -}; - -__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - { - .gpio_out = GPIO_TIM1_CH4OUT, - .gpio_in = GPIO_TIM1_CH4IN, - .timer_index = 0, - .timer_channel = 4, - .ccr_offset = STM32_GTIM_CCR4_OFFSET, - .masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF - }, - { - .gpio_out = GPIO_TIM1_CH3OUT, - .gpio_in = GPIO_TIM1_CH3IN, - .timer_index = 0, - .timer_channel = 3, - .ccr_offset = STM32_GTIM_CCR3_OFFSET, - .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF - }, - { - .gpio_out = GPIO_TIM1_CH2OUT, - .gpio_in = GPIO_TIM1_CH2IN, - .timer_index = 0, - .timer_channel = 2, - .ccr_offset = STM32_GTIM_CCR2_OFFSET, - .masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF - }, - { - .gpio_out = GPIO_TIM1_CH1OUT, - .gpio_in = GPIO_TIM1_CH1IN, - .timer_index = 0, - .timer_channel = 1, - .ccr_offset = STM32_GTIM_CCR1_OFFSET, - .masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF - }, - { - .gpio_out = GPIO_TIM4_CH2OUT, - .gpio_in = GPIO_TIM4_CH2IN, - .timer_index = 1, - .timer_channel = 2, - .ccr_offset = STM32_GTIM_CCR2_OFFSET, - .masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF - }, - { - .gpio_out = GPIO_TIM4_CH3OUT, - .gpio_in = GPIO_TIM4_CH3IN, - .timer_index = 1, - .timer_channel = 3, - .ccr_offset = STM32_GTIM_CCR3_OFFSET, - .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF - } -}; diff --git a/boards/px4/fmu-v3/src/timer_config.cpp b/boards/px4/fmu-v3/src/timer_config.cpp new file mode 100644 index 0000000000..02b5ffb68a --- /dev/null +++ b/boards/px4/fmu-v3/src/timer_config.cpp @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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 PX4 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 OWNER 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. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); +