diff --git a/boards/av/x-v1/src/CMakeLists.txt b/boards/av/x-v1/src/CMakeLists.txt index 7e0ef44d31..2fde5e91ec 100644 --- a/boards/av/x-v1/src/CMakeLists.txt +++ b/boards/av/x-v1/src/CMakeLists.txt @@ -35,7 +35,7 @@ add_library(drivers_board init.c sdio.c spi.cpp - timer_config.c + timer_config.cpp ) target_link_libraries(drivers_board diff --git a/boards/av/x-v1/src/board_config.h b/boards/av/x-v1/src/board_config.h index cb9e359827..7493398403 100644 --- a/boards/av/x-v1/src/board_config.h +++ b/boards/av/x-v1/src/board_config.h @@ -193,74 +193,9 @@ #define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) /* PWM - * - * 9 PWM outputs are configured. - * - * Pins: - * - * FMU_CH1 : PA8 : TIM1_CH1 - * FMU_CH2 : PA9 : TIM1_CH2 - * FMU_CH3 : PA10 : TIM1_CH3 - * FMU_CH4 : PA11 : TIM1_CH4 - * FMU_CH5 : PA3 : TIM2_CH4 - * FMU_CH6 : PI6 : TIM8_CH2 - * FMU_CH7 : PF7 : TIM11_CH1 - * FMU_CH8 : PF6 : TIM10_CH1 - * FMU_CH9 : PF6 : TIM4_CH3 - * */ -#define GPIO_TIM1_CH1OUT /* PA8 T1C1 FMU1 */ GPIO_TIM1_CH1OUT_1 -#define GPIO_TIM1_CH2OUT /* PA9 T1C2 FMU2 */ GPIO_TIM1_CH2OUT_1 -#define GPIO_TIM1_CH3OUT /* PA10 T1C3 FMU3 */ GPIO_TIM1_CH3OUT_1 -#define GPIO_TIM1_CH4OUT /* PA11 T1C4 FMU4 */ GPIO_TIM1_CH4OUT_1 -#define GPIO_TIM2_CH4OUT /* PA3 T2C4 FMU5 */ GPIO_TIM2_CH4OUT_1 -#define GPIO_TIM8_CH2OUT /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2 -#define GPIO_TIM11_CH1OUT /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1OUT_2 -#define GPIO_TIM10_CH1OUT /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1OUT_2 -#define GPIO_TIM4_CH3OUT /* PD14 T4C3 FMU9 */ GPIO_TIM4_CH3OUT_1 - -#define DIRECT_PWM_OUTPUT_CHANNELS 8 - -#define GPIO_TIM1_CH1IN /* PA8 T1C1 FMU1 */ GPIO_TIM1_CH1IN_1 -#define GPIO_TIM1_CH2IN /* PA9 T1C2 FMU2 */ GPIO_TIM1_CH2IN_1 -#define GPIO_TIM1_CH3IN /* PA10 T1C3 FMU3 */ GPIO_TIM1_CH3IN_1 -#define GPIO_TIM1_CH4IN /* PA11 T1C4 FMU4 */ GPIO_TIM1_CH4IN_1 -#define GPIO_TIM2_CH4IN /* PA3 T2C4 FMU5 */ GPIO_TIM2_CH4IN_1 -#define GPIO_TIM8_CH2IN /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2 -#define GPIO_TIM11_CH1IN /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1IN_2 -#define GPIO_TIM10_CH1IN /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1IN_2 -#define GPIO_TIM4_CH3IN /* PD14 T4C3 FMU9 */ GPIO_TIM4_CH3IN_1 - -#define DIRECT_INPUT_TIMER_CHANNELS 8 - -/* User GPIOs - * - * GPIO0-5 are the PWM servo outputs. - */ - -#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP)) - -#define GPIO_GPIO0_INPUT /* PA8 T1C1 FMU1 */ _MK_GPIO_INPUT(GPIO_TIM1_CH1IN) -#define GPIO_GPIO1_INPUT /* PA9 T1C2 FMU2 */ _MK_GPIO_INPUT(GPIO_TIM1_CH2IN) -#define GPIO_GPIO2_INPUT /* PA10 T1C3 FMU3 */ _MK_GPIO_INPUT(GPIO_TIM1_CH3IN) -#define GPIO_GPIO3_INPUT /* PA11 T1C4 FMU4 */ _MK_GPIO_INPUT(GPIO_TIM1_CH4IN) -#define GPIO_GPIO4_INPUT /* PA3 T2C4 FMU5 */ _MK_GPIO_INPUT(GPIO_TIM2_CH4IN_1) -#define GPIO_GPIO5_INPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_INPUT(GPIO_TIM8_CH2IN_2) -#define GPIO_GPIO6_INPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_INPUT(GPIO_TIM11_CH1IN_2) -#define GPIO_GPIO7_INPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_INPUT(GPIO_TIM10_CH1IN_2) -#define GPIO_GPIO8_INPUT /* PD14 T4C3 FMU9 */ _MK_GPIO_INPUT(GPIO_TIM4_CH3IN_2) - -#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR)) - -#define GPIO_GPIO0_OUTPUT /* PA8 T1C1 FMU1 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT) -#define GPIO_GPIO1_OUTPUT /* PA9 T1C2 FMU2 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH2OUT) -#define GPIO_GPIO2_OUTPUT /* PA10 T1C3 FMU3 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH3OUT) -#define GPIO_GPIO3_OUTPUT /* PA11 T1C4 FMU4 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH4OUT) -#define GPIO_GPIO4_OUTPUT /* PA3 T2C4 FMU5 */ _MK_GPIO_OUTPUT(GPIO_TIM2_CH4OUT_1) -#define GPIO_GPIO5_OUTPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_OUTPUT(GPIO_TIM8_CH2OUT_2) -#define GPIO_GPIO6_OUTPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_OUTPUT(GPIO_TIM11_CH1OUT_2) -#define GPIO_GPIO7_OUTPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_OUTPUT(GPIO_TIM10_CH1OUT_2) -#define GPIO_GPIO8_OUTPUT /* PF6 T10C1 FMU9 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH3OUT_2) +#define DIRECT_PWM_OUTPUT_CHANNELS 9 +#define DIRECT_INPUT_TIMER_CHANNELS 9 /* High-resolution timer */ #define HRT_TIMER 5 /* use timer5 for the HRT */ @@ -306,20 +241,6 @@ #define BOARD_HAS_ON_RESET 1 -/* The list of GPIO that will be initialized */ - -#define PX4_GPIO_PWM_INIT_LIST { \ - GPIO_GPIO8_INPUT, \ - GPIO_GPIO7_INPUT, \ - GPIO_GPIO6_INPUT, \ - GPIO_GPIO5_INPUT, \ - GPIO_GPIO4_INPUT, \ - GPIO_GPIO3_INPUT, \ - GPIO_GPIO2_INPUT, \ - GPIO_GPIO1_INPUT, \ - GPIO_GPIO0_INPUT, \ - } - #define PX4_GPIO_INIT_LIST { \ PX4_ADC_GPIO, \ GPIO_CAN1_RX, \ @@ -328,7 +249,7 @@ #define BOARD_ENABLE_CONSOLE_BUFFER -#define BOARD_NUM_IO_TIMERS 5 +#define BOARD_NUM_IO_TIMERS 6 __BEGIN_DECLS diff --git a/boards/av/x-v1/src/init.c b/boards/av/x-v1/src/init.c index d85d255423..f738902026 100644 --- a/boards/av/x-v1/src/init.c +++ b/boards/av/x-v1/src/init.c @@ -66,6 +66,7 @@ #include #include "up_internal.h" +#include #include #include #include @@ -88,10 +89,9 @@ static int configure_switch(void); ************************************************************************************/ __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/av/x-v1/src/timer_config.c b/boards/av/x-v1/src/timer_config.c deleted file mode 100644 index ea51b9837b..0000000000 --- a/boards/av/x-v1/src/timer_config.c +++ /dev/null @@ -1,196 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2018 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, - }, - { - .base = STM32_TIM2_BASE, - .clock_register = STM32_RCC_APB1ENR, - .clock_bit = RCC_APB1ENR_TIM2EN, - .clock_freq = STM32_APB1_TIM2_CLKIN, - .vectorno = STM32_IRQ_TIM2, - }, - { - .base = STM32_TIM8_BASE, - .clock_register = STM32_RCC_APB2ENR, - .clock_bit = RCC_APB2ENR_TIM8EN, - .clock_freq = STM32_APB2_TIM8_CLKIN, - .vectorno = STM32_IRQ_TIM8CC, - }, - { - .base = STM32_TIM11_BASE, - .clock_register = STM32_RCC_APB2ENR, - .clock_bit = RCC_APB2ENR_TIM11EN, - .clock_freq = STM32_APB2_TIM11_CLKIN, - .vectorno = STM32_IRQ_TIM11, - }, - { - .base = STM32_TIM10_BASE, - .clock_register = STM32_RCC_APB2ENR, - .clock_bit = RCC_APB2ENR_TIM10EN, - .clock_freq = STM32_APB2_TIM10_CLKIN, - .vectorno = STM32_IRQ_TIM10, - }, - // { - // .base = STM32_TIM4_BASE, - // .clock_register = STM32_RCC_APB1ENR, - // .clock_bit = RCC_APB1ENR_TIM4EN, - // .clock_freq = STM32_APB1_TIM4_CLKIN, - // .vectorno = STM32_IRQ_TIM4, - // } -}; - -__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, - }, - { - .first_channel_index = 5, - .channel_count = 1, - }, - { - .first_channel_index = 6, - .channel_count = 1, - }, - { - .first_channel_index = 7, - .channel_count = 1, - }, - } -}; - -__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - { - .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_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_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_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_TIM2_CH4OUT, - .gpio_in = GPIO_TIM2_CH4IN, - .timer_index = 1, - .timer_channel = 4, - .ccr_offset = STM32_GTIM_CCR4_OFFSET, - .masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF - }, - { - .gpio_out = GPIO_TIM8_CH2OUT, - .gpio_in = GPIO_TIM8_CH2IN, - .timer_index = 2, - .timer_channel = 2, - .ccr_offset = STM32_GTIM_CCR2_OFFSET, - .masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF - }, - { - .gpio_out = GPIO_TIM11_CH1OUT, - .gpio_in = GPIO_TIM11_CH1IN, - .timer_index = 3, - .timer_channel = 1, - .ccr_offset = STM32_GTIM_CCR1_OFFSET, - .masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF - }, - { - .gpio_out = GPIO_TIM10_CH1OUT, - .gpio_in = GPIO_TIM10_CH1IN, - .timer_index = 4, - .timer_channel = 1, - .ccr_offset = STM32_GTIM_CCR1_OFFSET, - .masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF - }, - // { - // .gpio_out = GPIO_TIM4_CH3OUT, - // .gpio_in = GPIO_TIM4_CH3IN, - // .timer_index = 5, - // .timer_channel = 3, - // .ccr_offset = STM32_GTIM_CCR3_OFFSET, - // .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF - // } -}; diff --git a/boards/av/x-v1/src/timer_config.cpp b/boards/av/x-v1/src/timer_config.cpp new file mode 100644 index 0000000000..eccdc3cca4 --- /dev/null +++ b/boards/av/x-v1/src/timer_config.cpp @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2018 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), + initIOTimer(Timer::Timer2), + initIOTimer(Timer::Timer8), + initIOTimer(Timer::Timer11), + initIOTimer(Timer::Timer10), + initIOTimer(Timer::Timer4), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortA, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortA, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer11, Timer::Channel1}, {GPIO::PortF, GPIO::Pin7}), + initIOTimerChannel(io_timers, {Timer::Timer10, Timer::Channel1}, {GPIO::PortF, GPIO::Pin6}), + initIOTimerChannel(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); +