diff --git a/boards/holybro/durandal-v1/src/CMakeLists.txt b/boards/holybro/durandal-v1/src/CMakeLists.txt index 58887a4ccc2a..cfac87b66666 100644 --- a/boards/holybro/durandal-v1/src/CMakeLists.txt +++ b/boards/holybro/durandal-v1/src/CMakeLists.txt @@ -51,7 +51,7 @@ else() manifest.c sdio.c spi.cpp - timer_config.c + timer_config.cpp usb.c ) add_dependencies(drivers_board arch_board_hw_info) diff --git a/boards/holybro/durandal-v1/src/board_config.h b/boards/holybro/durandal-v1/src/board_config.h index a2d170450cf7..a53d1b1be7a2 100644 --- a/boards/holybro/durandal-v1/src/board_config.h +++ b/boards/holybro/durandal-v1/src/board_config.h @@ -312,58 +312,12 @@ #define DIRECT_PWM_CAPTURE_CHANNELS 6 /* PWM - * - * 5 PWM outputs are configured. - * - * Pins: - * - * FMU_CH1 : PE14 : TIM1_CH4 - * FMU_CH2 : PA10 : TIM1_CH3 - * FMU_CH3 : PE11 : TIM1_CH2 - * FMU_CH4 : PE9 : TIM1_CH1 - * FMU_CH5 : PD13 : TIM4_CH2 - * */ -#define GPIO_TIM4_CH2OUT /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2OUT_2 -#define GPIO_TIM1_CH1OUT /* PE9 T1C1 FMU4 */ GPIO_TIM1_CH1OUT_2 -#define GPIO_TIM1_CH2OUT /* PE11 T1C2 FMU3 */ GPIO_TIM1_CH2OUT_2 -#define GPIO_TIM1_CH3OUT /* PA10 T1C3 FMU2 */ GPIO_TIM1_CH3OUT_1 -#define GPIO_TIM1_CH4OUT /* PE14 T1C4 FMU1 */ GPIO_TIM1_CH4OUT_2 - #define DIRECT_PWM_OUTPUT_CHANNELS 5 - -#define GPIO_TIM4_CH2IN /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2IN_2 -#define GPIO_TIM1_CH1IN /* PE9 T1C1 FMU4 */ GPIO_TIM1_CH1IN_2 -#define GPIO_TIM1_CH2IN /* PE11 T1C2 FMU3 */ GPIO_TIM1_CH2IN_2 -#define GPIO_TIM1_CH3IN /* PA10 T1C3 FMU2 */ GPIO_TIM1_CH3IN_1 -#define GPIO_TIM1_CH4IN /* PE14 T1C4 FMU1 */ GPIO_TIM1_CH4IN_2 - #define DIRECT_INPUT_TIMER_CHANNELS 5 #define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4}; -/* User GPIOs - * - * GPIO0-4 are the PWM servo outputs. - */ - -#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP)) - -#define GPIO_GPIO4_INPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_INPUT(GPIO_TIM4_CH2IN) -#define GPIO_GPIO3_INPUT /* PE9 T1C1 FMU4 */ _MK_GPIO_INPUT(GPIO_TIM1_CH1IN) -#define GPIO_GPIO2_INPUT /* PE11 T1C2 FMU3 */ _MK_GPIO_INPUT(GPIO_TIM1_CH2IN) -#define GPIO_GPIO1_INPUT /* PA10 T1C3 FMU2 */ _MK_GPIO_INPUT(GPIO_TIM1_CH3IN) -#define GPIO_GPIO0_INPUT /* PE14 T1C4 FMU1 */ _MK_GPIO_INPUT(GPIO_TIM1_CH4IN) - -#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR)) - -#define GPIO_GPIO4_OUTPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH2OUT) -#define GPIO_GPIO3_OUTPUT /* PE9 T1C1 FMU4 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT) -#define GPIO_GPIO2_OUTPUT /* PE11 T1C2 FMU3 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH2OUT) -#define GPIO_GPIO1_OUTPUT /* PA10 T1C3 FMU2 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH3OUT) -#define GPIO_GPIO0_OUTPUT /* PE14 T1C4 FMU1 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH4OUT) - - /* Power supply control and monitoring GPIOs */ #define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) @@ -502,16 +456,6 @@ #define BOARD_HAS_ON_RESET 1 -/* The list of GPIO that will be initialized */ - -#define PX4_GPIO_PWM_INIT_LIST { \ - GPIO_GPIO4_INPUT, \ - GPIO_GPIO3_INPUT, \ - GPIO_GPIO2_INPUT, \ - GPIO_GPIO1_INPUT, \ - GPIO_GPIO0_INPUT, \ - } - #define PX4_GPIO_INIT_LIST { \ PX4_ADC_GPIO, \ GPIO_HW_REV_DRIVE, \ diff --git a/boards/holybro/durandal-v1/src/init.c b/boards/holybro/durandal-v1/src/init.c index bcde8cb95712..54c0468aba36 100644 --- a/boards/holybro/durandal-v1/src/init.c +++ b/boards/holybro/durandal-v1/src/init.c @@ -68,6 +68,7 @@ #include #include #include +#include #include #include #include @@ -136,10 +137,9 @@ __EXPORT void board_peripheral_reset(int ms) ************************************************************************************/ __EXPORT void board_on_reset(int status) { - /* configure the GPIO pins to outputs and keep them low */ - - const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST; - px4_gpio_init(gpio, arraySize(gpio)); + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } if (status >= 0) { up_mdelay(6); diff --git a/boards/holybro/durandal-v1/src/timer_config.c b/boards/holybro/durandal-v1/src/timer_config.c deleted file mode 100644 index 8385855b4832..000000000000 --- a/boards/holybro/durandal-v1/src/timer_config.c +++ /dev/null @@ -1,132 +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_TIMCC, - .dshot = { - .dma_base = STM32_DMA1_BASE, - .dmamap = DMAMAP_DMA12_TIM1UP_0, - } - }, - { - .base = STM32_TIM4_BASE, - .clock_register = STM32_RCC_APB1LENR, - .clock_bit = RCC_APB1LENR_TIM4EN, - .clock_freq = STM32_APB1_TIM4_CLKIN, - .vectorno = STM32_IRQ_TIM4, - .dshot = { - .dma_base = STM32_DMA1_BASE, - .dmamap = DMAMAP_DMA12_TIM4UP_0, - } - }, -}; - -__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 = 1, - } - } -}; - -__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 - }, -}; diff --git a/boards/holybro/durandal-v1/src/timer_config.cpp b/boards/holybro/durandal-v1/src/timer_config.cpp new file mode 100644 index 000000000000..1263efa20143 --- /dev/null +++ b/boards/holybro/durandal-v1/src/timer_config.cpp @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * 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::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); +