diff --git a/platforms/common/include/px4_platform_common/constexpr_util.h b/platforms/common/include/px4_platform_common/constexpr_util.h new file mode 100644 index 0000000000..e41c75bf09 --- /dev/null +++ b/platforms/common/include/px4_platform_common/constexpr_util.h @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ + +#pragma once + +static inline int _constexpr_assert_failure(const char *msg) +{ + // we do 2 things that the compiler will refuse to execute at compile-time + // (and therefore trigger a compilation error): + // - define a local static variable + // - declare the method as non constexpr + static int i = 0; + return i; +} + +/** + * Assertion that fails compilation if used in a constexpr context (that is executed at + * compile-time). + * + * Important: you need to ensure the code is executed at compile-time, e.g. by + * assigning the returned value of a constexpr method (where the assert is used) + * to a variable marked as constexpr. Otherwise the compiler might silently move + * execution to runtime. + * + * If executed at runtime, it has no effect other than slight runtime overhead. + */ +#define constexpr_assert(expr, msg) if (!(expr)) { _constexpr_assert_failure(msg); } + + diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/io_timer_init.h b/platforms/nuttx/src/px4/common/include/px4_platform/io_timer_init.h new file mode 100644 index 0000000000..14576759b0 --- /dev/null +++ b/platforms/nuttx/src/px4/common/include/px4_platform/io_timer_init.h @@ -0,0 +1,101 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include +#include +#include +#include + + +/** + * Initialize the IO channel mapping from timer and channel configurations. + * @param io_timers_conf configured timers + * @param timer_io_channels_conf configured channels + */ +static inline constexpr io_timers_channel_mapping_t initIOTimerChannelMapping(const io_timers_t + io_timers_conf[MAX_IO_TIMERS], + const timer_io_channels_t timer_io_channels_conf[MAX_TIMER_IO_CHANNELS]) +{ + io_timers_channel_mapping_t ret{}; + + // requirement: channels of the same timer must be grouped together, but the ordering does not matter + + for (unsigned i = 0; i < MAX_IO_TIMERS; ++i) { + if (io_timers_conf[i].base == 0) { + break; + } + + uint32_t first_channel = UINT32_MAX; + uint32_t channel_count = 0; + + for (uint32_t channel = 0; channel < MAX_TIMER_IO_CHANNELS; ++channel) { + if (timer_io_channels_conf[channel].timer_channel == 0) { + break; + } + + if (timer_io_channels_conf[channel].timer_index == i) { + if (first_channel == UINT32_MAX) { + first_channel = channel; + + } else { + constexpr_assert(timer_io_channels_conf[channel - 1].timer_index == i, "Timers are not grouped together"); + } + + ++channel_count; + } + } + + if (first_channel == UINT32_MAX) { //unused timer, channel_count is 0 + first_channel = 0; + } + + ret.element[i].first_channel_index = first_channel; + ret.element[i].channel_count = channel_count; + } + + // validate that the number of configured channels matches DIRECT_PWM_OUTPUT_CHANNELS + uint32_t num_channels = 0; + + while (num_channels < MAX_TIMER_IO_CHANNELS && timer_io_channels_conf[num_channels].timer_channel != 0) { + ++num_channels; + } + + constexpr_assert(DIRECT_PWM_OUTPUT_CHANNELS == num_channels, "DIRECT_PWM_OUTPUT_CHANNELS misconfigured"); + constexpr_assert(DIRECT_PWM_OUTPUT_CHANNELS <= MAX_TIMER_IO_CHANNELS, + "DIRECT_PWM_OUTPUT_CHANNELS > MAX_TIMER_IO_CHANNELS"); + + return ret; +} + diff --git a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..cb6096b49c --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/hw_description.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../kinetis/include/px4_arch/hw_description.h" + diff --git a/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..03952138ec --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/k66/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../kinetis/include/px4_arch/io_timer_hw_description.h" + diff --git a/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..ae5fc61c29 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/hw_description.h @@ -0,0 +1,228 @@ +/**************************************************************************** + * + * Copyright (C) 2019 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. + * + ****************************************************************************/ + +#pragma once + + +#include + +#include +#include "hardware/kinetis_sim.h" +#include "hardware/kinetis_ftm.h" + +#include + +/* + * Timers + */ + +namespace Timer +{ +enum Timer { + FTM0 = 0, + FTM1, + FTM2, + FTM3, +}; +enum Channel { + Channel0 = 0, + Channel1, + Channel2, + Channel3, + Channel4, + Channel5, + Channel6, + Channel7, +}; +struct TimerChannel { + Timer timer; + Channel channel; +}; +} + +static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer) +{ + switch (timer) { + case Timer::FTM0: return KINETIS_FTM0_BASE; + + case Timer::FTM1: return KINETIS_FTM1_BASE; + + case Timer::FTM2: return KINETIS_FTM2_BASE; + + case Timer::FTM3: return KINETIS_FTM3_BASE; + } + + return 0; +} + +/* + * GPIO + */ + +namespace GPIO +{ +enum Port { + PortA = 0, + PortB, + PortC, + PortD, + PortE, +}; +enum Pin { + Pin0 = 0, + Pin1, + Pin2, + Pin3, + Pin4, + Pin5, + Pin6, + Pin7, + Pin8, + Pin9, + Pin10, + Pin11, + Pin12, + Pin13, + Pin14, + Pin15, + Pin16, + Pin17, + Pin18, + Pin19, + Pin20, + Pin21, + Pin22, + Pin23, + Pin24, + Pin25, + Pin26, + Pin27, + Pin28, + Pin29, + Pin30, + Pin31, +}; +struct GPIOPin { + Port port; + Pin pin; +}; +} + +static inline constexpr uint32_t getGPIOPort(GPIO::Port port) +{ + switch (port) { + case GPIO::PortA: return PIN_PORTA; + + case GPIO::PortB: return PIN_PORTB; + + case GPIO::PortC: return PIN_PORTC; + + case GPIO::PortD: return PIN_PORTD; + + case GPIO::PortE: return PIN_PORTE; + } + + return 0; +} + +static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin) +{ + switch (pin) { + case GPIO::Pin0: return PIN0; + + case GPIO::Pin1: return PIN1; + + case GPIO::Pin2: return PIN2; + + case GPIO::Pin3: return PIN3; + + case GPIO::Pin4: return PIN4; + + case GPIO::Pin5: return PIN5; + + case GPIO::Pin6: return PIN6; + + case GPIO::Pin7: return PIN7; + + case GPIO::Pin8: return PIN8; + + case GPIO::Pin9: return PIN9; + + case GPIO::Pin10: return PIN10; + + case GPIO::Pin11: return PIN11; + + case GPIO::Pin12: return PIN12; + + case GPIO::Pin13: return PIN13; + + case GPIO::Pin14: return PIN14; + + case GPIO::Pin15: return PIN15; + + case GPIO::Pin16: return PIN16; + + case GPIO::Pin17: return PIN17; + + case GPIO::Pin18: return PIN18; + + case GPIO::Pin19: return PIN19; + + case GPIO::Pin20: return PIN20; + + case GPIO::Pin21: return PIN21; + + case GPIO::Pin22: return PIN22; + + case GPIO::Pin23: return PIN23; + + case GPIO::Pin24: return PIN24; + + case GPIO::Pin25: return PIN25; + + case GPIO::Pin26: return PIN26; + + case GPIO::Pin27: return PIN27; + + case GPIO::Pin28: return PIN28; + + case GPIO::Pin29: return PIN29; + + case GPIO::Pin30: return PIN30; + + case GPIO::Pin31: return PIN31; + } + + return 0; +} + diff --git a/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..879c819699 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,149 @@ +/**************************************************************************** + * + * Copyright (C) 2019 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. + * + ****************************************************************************/ + +#pragma once + + +#include +#include +#include +#include +#include +#include "hardware/kinetis_ftm.h" +#include "hardware/kinetis_sim.h" + + +static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t io_timers_conf[MAX_IO_TIMERS], + Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret{}; + + uint32_t gpio_af = 0; + + switch (pin.port) { + case GPIO::PortA: + gpio_af = PIN_ALT3; + break; + + case GPIO::PortB: + if (pin.pin == GPIO::Pin12 || pin.pin == GPIO::Pin13) { + gpio_af = PIN_ALT4; + + } else { + gpio_af = PIN_ALT3; + } + + break; + + case GPIO::PortC: + if (pin.pin == GPIO::Pin5) { + gpio_af = PIN_ALT7; + + } else if (pin.pin == GPIO::Pin8 || pin.pin == GPIO::Pin9 || pin.pin == GPIO::Pin10 || pin.pin == GPIO::Pin11) { + gpio_af = PIN_ALT3; + + } else { + gpio_af = PIN_ALT4; + } + + break; + + case GPIO::PortD: + gpio_af = PIN_ALT4; + break; + + case GPIO::PortE: + gpio_af = PIN_ALT6; + break; + } + + uint32_t gpio_pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin); + ret.gpio_in = gpio_af | gpio_pin_port; + ret.gpio_out = gpio_af | gpio_pin_port; + + ret.timer_channel = (int)timer.channel + 1; + + // find timer index + ret.timer_index = 0xff; + const uint32_t timer_base = timerBaseRegister(timer.timer); + + for (int i = 0; i < MAX_IO_TIMERS; ++i) { + if (io_timers_conf[i].base == timer_base) { + ret.timer_index = i; + break; + } + } + + constexpr_assert(ret.timer_index != 0xff, "Timer not found"); + + return ret; +} + +static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) +{ + io_timers_t ret{}; + + switch (timer) { + case Timer::FTM0: + ret.base = KINETIS_FTM0_BASE; + ret.clock_register = KINETIS_SIM_SCGC6; + ret.clock_bit = SIM_SCGC6_FTM0; + ret.vectorno = KINETIS_IRQ_FTM0; + break; + + case Timer::FTM1: + ret.base = KINETIS_FTM1_BASE; + ret.clock_register = KINETIS_SIM_SCGC6; + ret.clock_bit = SIM_SCGC6_FTM1; + ret.vectorno = KINETIS_IRQ_FTM1; + break; + + case Timer::FTM2: + ret.base = KINETIS_FTM2_BASE; + ret.clock_register = KINETIS_SIM_SCGC3; + ret.clock_bit = SIM_SCGC3_FTM2; + ret.vectorno = KINETIS_IRQ_FTM2; + break; + + case Timer::FTM3: + ret.base = KINETIS_FTM3_BASE; + ret.clock_register = KINETIS_SIM_SCGC3; + ret.clock_bit = SIM_SCGC3_FTM3; + ret.vectorno = KINETIS_IRQ_FTM3; + break; + } + + return ret; +} + + diff --git a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..b6c5ffe772 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/hw_description.h @@ -0,0 +1,277 @@ +/**************************************************************************** + * + * Copyright (C) 2019 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. + * + ****************************************************************************/ + +#pragma once + +#include + +#include +#include +#include + +#include + +/* + * DMA + */ + +struct DMA { + enum Index { Invalid = 0, Index1 = 1, Index2 }; + Index index; + enum Stream { Stream0, Stream1, Stream2, Stream3, Stream4, Stream5, Stream6, Stream7 }; + Stream stream; + enum Channel { Channel0, Channel1, Channel2, Channel3, Channel4, Channel5, Channel6, Channel7 }; + Channel channel; +}; + +static inline constexpr uint32_t getDMABaseRegister(const DMA &dma) +{ + switch (dma.index) { + case DMA::Index1: return STM32_DMA1_BASE; + + case DMA::Index2: return STM32_DMA2_BASE; + + case DMA::Invalid: + constexpr_assert(false, "Trying to get DMA base register for invalid config"); + break; + } + + return 0; +} + + +/* + * Timers + */ + +namespace Timer +{ +enum Timer { + Timer1 = 1, + Timer2, + Timer3, + Timer4, + Timer5, + Timer6, + Timer7, + Timer8, + Timer9, + Timer10, + Timer11, + Timer12, + Timer13, + Timer14, +}; +enum Channel { + Channel1 = 1, + Channel2, + Channel3, + Channel4, +}; +struct TimerChannel { + Timer timer; + Channel channel; +}; +} + +static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer) +{ + switch (timer) { + case Timer::Timer1: return STM32_TIM1_BASE; + + case Timer::Timer2: return STM32_TIM2_BASE; + + case Timer::Timer3: return STM32_TIM3_BASE; + + case Timer::Timer4: return STM32_TIM4_BASE; + + case Timer::Timer5: return STM32_TIM5_BASE; + + case Timer::Timer6: return STM32_TIM6_BASE; + + case Timer::Timer7: return STM32_TIM7_BASE; + + case Timer::Timer8: return STM32_TIM8_BASE; + +#ifdef STM32_TIM9_BASE // STM32F1 only goes up to TIM8 + + case Timer::Timer9: return STM32_TIM9_BASE; +#endif + +#ifdef STM32_TIM10_BASE + + case Timer::Timer10: return STM32_TIM10_BASE; +#endif + +#ifdef STM32_TIM11_BASE + + case Timer::Timer11: return STM32_TIM11_BASE; +#endif + +#ifdef STM32_TIM12_BASE + + case Timer::Timer12: return STM32_TIM12_BASE; +#endif + +#ifdef STM32_TIM13_BASE + + case Timer::Timer13: return STM32_TIM13_BASE; +#endif + +#ifdef STM32_TIM14_BASE + + case Timer::Timer14: return STM32_TIM14_BASE; +#endif + + default: break; + } + + return 0; +} + + +/* + * GPIO + */ + +namespace GPIO +{ +enum Port { + PortA = 0, + PortB, + PortC, + PortD, + PortE, + PortF, + PortG, + PortH, + PortI, +}; +enum Pin { + Pin0 = 0, + Pin1, + Pin2, + Pin3, + Pin4, + Pin5, + Pin6, + Pin7, + Pin8, + Pin9, + Pin10, + Pin11, + Pin12, + Pin13, + Pin14, + Pin15, +}; +struct GPIOPin { + Port port; + Pin pin; +}; +} + +static inline constexpr uint32_t getGPIOPort(GPIO::Port port) +{ + switch (port) { + case GPIO::PortA: return GPIO_PORTA; + + case GPIO::PortB: return GPIO_PORTB; + + case GPIO::PortC: return GPIO_PORTC; + + case GPIO::PortD: return GPIO_PORTD; + + case GPIO::PortE: return GPIO_PORTE; +#ifdef GPIO_PORTF + + case GPIO::PortF: return GPIO_PORTF; +#endif +#ifdef GPIO_PORTG + + case GPIO::PortG: return GPIO_PORTG; +#endif +#ifdef GPIO_PORTH + + case GPIO::PortH: return GPIO_PORTH; +#endif +#ifdef GPIO_PORTI + + case GPIO::PortI: return GPIO_PORTI; +#endif + + default: break; + } + + return 0; +} + +static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin) +{ + switch (pin) { + case GPIO::Pin0: return GPIO_PIN0; + + case GPIO::Pin1: return GPIO_PIN1; + + case GPIO::Pin2: return GPIO_PIN2; + + case GPIO::Pin3: return GPIO_PIN3; + + case GPIO::Pin4: return GPIO_PIN4; + + case GPIO::Pin5: return GPIO_PIN5; + + case GPIO::Pin6: return GPIO_PIN6; + + case GPIO::Pin7: return GPIO_PIN7; + + case GPIO::Pin8: return GPIO_PIN8; + + case GPIO::Pin9: return GPIO_PIN9; + + case GPIO::Pin10: return GPIO_PIN10; + + case GPIO::Pin11: return GPIO_PIN11; + + case GPIO::Pin12: return GPIO_PIN12; + + case GPIO::Pin13: return GPIO_PIN13; + + case GPIO::Pin14: return GPIO_PIN14; + + case GPIO::Pin15: return GPIO_PIN15; + } + + return 0; +} + diff --git a/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..eb63318efc --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,238 @@ +/**************************************************************************** + * + * Copyright (C) 2019 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. + * + ****************************************************************************/ + +#pragma once + + +#include +#include +#include +#include +#include +#include + +static inline constexpr timer_io_channels_t initIOTimerGPIOInOut(Timer::TimerChannel timer, GPIO::GPIOPin pin); + + +static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t io_timers_conf[MAX_IO_TIMERS], + Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret = initIOTimerGPIOInOut(timer, pin); + + // TODO: here we could validate that pin actually maps to the given timer channel + + switch (timer.channel) { + case Timer::Channel1: + ret.ccr_offset = STM32_GTIM_CCR1_OFFSET; + ret.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF; + ret.timer_channel = 1; + break; + + case Timer::Channel2: + ret.ccr_offset = STM32_GTIM_CCR2_OFFSET; + ret.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF; + ret.timer_channel = 2; + break; + + case Timer::Channel3: + ret.ccr_offset = STM32_GTIM_CCR3_OFFSET; + ret.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF; + ret.timer_channel = 3; + break; + + case Timer::Channel4: + ret.ccr_offset = STM32_GTIM_CCR4_OFFSET; + ret.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF; + ret.timer_channel = 4; + break; + } + + // find timer index + ret.timer_index = 0xff; + const uint32_t timer_base = timerBaseRegister(timer.timer); + + for (int i = 0; i < MAX_IO_TIMERS; ++i) { + if (io_timers_conf[i].base == timer_base) { + ret.timer_index = i; + break; + } + } + + constexpr_assert(ret.timer_index != 0xff, "Timer not found"); + + return ret; +} + +static inline constexpr timer_io_channels_t initIOTimerChannelOutputClear(const io_timers_t + io_timers_conf[MAX_IO_TIMERS], Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin); + ret.gpio_out |= GPIO_OUTPUT_CLEAR; + return ret; +} + + +static inline constexpr io_timers_t initIOTimer(Timer::Timer timer, DMA dshot_dma = {}) +{ + io_timers_t ret{}; + + switch (timer) { + case Timer::Timer1: + ret.base = STM32_TIM1_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM1EN; + ret.clock_freq = STM32_APB2_TIM1_CLKIN; + ret.vectorno = STM32_IRQ_TIM1CC; + break; + + case Timer::Timer2: + ret.base = STM32_TIM2_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM2EN; + ret.clock_freq = STM32_APB1_TIM2_CLKIN; + ret.vectorno = STM32_IRQ_TIM2; + break; + + case Timer::Timer3: + ret.base = STM32_TIM3_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM3EN; + ret.clock_freq = STM32_APB1_TIM3_CLKIN; + ret.vectorno = STM32_IRQ_TIM3; + break; + + case Timer::Timer4: + ret.base = STM32_TIM4_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM4EN; + ret.clock_freq = STM32_APB1_TIM4_CLKIN; + ret.vectorno = STM32_IRQ_TIM4; + break; + + case Timer::Timer5: + ret.base = STM32_TIM5_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM5EN; + ret.clock_freq = STM32_APB1_TIM5_CLKIN; + ret.vectorno = STM32_IRQ_TIM5; + break; + + case Timer::Timer6: + ret.base = STM32_TIM6_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM6EN; + ret.clock_freq = STM32_APB1_TIM6_CLKIN; + ret.vectorno = STM32_IRQ_TIM6; + break; + + case Timer::Timer7: + ret.base = STM32_TIM7_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM7EN; + ret.clock_freq = STM32_APB1_TIM7_CLKIN; + ret.vectorno = STM32_IRQ_TIM7; + break; + +#ifdef RCC_APB2ENR_TIM8EN + + case Timer::Timer8: + ret.base = STM32_TIM8_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM8EN; + ret.clock_freq = STM32_APB2_TIM8_CLKIN; + ret.vectorno = STM32_IRQ_TIM8CC; + break; +#endif + +#ifdef STM32_TIM9_BASE + + case Timer::Timer9: + ret.base = STM32_TIM9_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM9EN; + ret.clock_freq = STM32_APB2_TIM9_CLKIN; + ret.vectorno = STM32_IRQ_TIM9; + break; +#endif + +#ifdef STM32_TIM10_BASE + + case Timer::Timer10: + ret.base = STM32_TIM10_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM10EN; + ret.clock_freq = STM32_APB2_TIM10_CLKIN; + ret.vectorno = STM32_IRQ_TIM10; + break; +#endif + +#ifdef STM32_TIM11_BASE + + case Timer::Timer11: + ret.base = STM32_TIM11_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM11EN; + ret.clock_freq = STM32_APB2_TIM11_CLKIN; + ret.vectorno = STM32_IRQ_TIM11; + break; +#endif + +#ifdef STM32_TIM12_BASE + + case Timer::Timer12: + ret.base = STM32_TIM12_BASE; + ret.clock_register = STM32_RCC_APB1ENR; + ret.clock_bit = RCC_APB1ENR_TIM12EN; + ret.clock_freq = STM32_APB1_TIM12_CLKIN; + ret.vectorno = STM32_IRQ_TIM12; + break; +#endif + + case Timer::Timer13: + case Timer::Timer14: + constexpr_assert(false, "Implementation missing"); + break; + + default: break; + } + + // DShot + if (dshot_dma.index != DMA::Invalid) { + ret.dshot.dma_base = getDMABaseRegister(dshot_dma); + ret.dshot.dmamap = getTimerUpdateDMAMap(timer, dshot_dma); + } + + return ret; +} + + diff --git a/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..4296e0490a --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/hw_description.h @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/hw_description.h" + +static inline constexpr uint32_t getTimerUpdateDMAMap(Timer::Timer timer, const DMA &dma) +{ + // not used on STM32F1 + return 0; +} + diff --git a/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..11c51b8d0a --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f1/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,45 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/io_timer_hw_description.h" + +static inline constexpr timer_io_channels_t initIOTimerGPIOInOut(Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret{}; + uint32_t pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin); + ret.gpio_in = (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_MODE_INPUT) | pin_port; + ret.gpio_out = (GPIO_ALT | GPIO_CNF_AFPP | GPIO_MODE_50MHz) | pin_port; + return ret; +} diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..ad3ffb1d5b --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/hw_description.h @@ -0,0 +1,101 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/hw_description.h" + +static inline constexpr uint32_t getTimerUpdateDMAMap(Timer::Timer timer, const DMA &dma) +{ + uint32_t dma_map = 0; + + switch (timer) { + case Timer::Timer1: + if (dma.index == DMA::Index2 && dma.stream == DMA::Stream5 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM1_UP; } + + break; + + case Timer::Timer2: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel3) { dma_map = DMAMAP_TIM2_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream7 && dma.channel == DMA::Channel3) { dma_map = DMAMAP_TIM2_UP_2; } + + break; + + case Timer::Timer3: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream2 && dma.channel == DMA::Channel5) { dma_map = DMAMAP_TIM3_UP; } + + break; + + case Timer::Timer4: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream6 && dma.channel == DMA::Channel2) { dma_map = DMAMAP_TIM4_UP; } + + break; + + case Timer::Timer5: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream0 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM5_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream6 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM5_UP_2; } + + break; + + case Timer::Timer6: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel7) { dma_map = DMAMAP_TIM6_UP; } + + break; + + case Timer::Timer7: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream2 && dma.channel == DMA::Channel1) { dma_map = DMAMAP_TIM7_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream4 && dma.channel == DMA::Channel1) { dma_map = DMAMAP_TIM7_UP_2; } + + break; + + case Timer::Timer8: + if (dma.index == DMA::Index2 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel7) { dma_map = DMAMAP_TIM8_UP; } + + break; + + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + case Timer::Timer12: + case Timer::Timer13: + case Timer::Timer14: + break; + } + + constexpr_assert(dma_map != 0, "Invalid DMA config for given timer"); + return dma_map; +} + diff --git a/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..89da314eae --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/io_timer_hw_description.h" + +static inline constexpr timer_io_channels_t initIOTimerGPIOInOut(Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret{}; + uint32_t gpio_af = 0; + + switch (timer.timer) { + case Timer::Timer1: + case Timer::Timer2: + gpio_af = GPIO_AF1; + break; + + case Timer::Timer3: + case Timer::Timer4: + case Timer::Timer5: + gpio_af = GPIO_AF2; + break; + + case Timer::Timer6: + case Timer::Timer7: + case Timer::Timer8: + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + gpio_af = GPIO_AF3; + break; + + case Timer::Timer12: + case Timer::Timer13: + case Timer::Timer14: + gpio_af = GPIO_AF9; + break; + } + + uint32_t pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin); + ret.gpio_in = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_FLOAT) | pin_port; + ret.gpio_out = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_PUSHPULL) | pin_port; + return ret; +} diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..ad3ffb1d5b --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/hw_description.h @@ -0,0 +1,101 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/hw_description.h" + +static inline constexpr uint32_t getTimerUpdateDMAMap(Timer::Timer timer, const DMA &dma) +{ + uint32_t dma_map = 0; + + switch (timer) { + case Timer::Timer1: + if (dma.index == DMA::Index2 && dma.stream == DMA::Stream5 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM1_UP; } + + break; + + case Timer::Timer2: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel3) { dma_map = DMAMAP_TIM2_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream7 && dma.channel == DMA::Channel3) { dma_map = DMAMAP_TIM2_UP_2; } + + break; + + case Timer::Timer3: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream2 && dma.channel == DMA::Channel5) { dma_map = DMAMAP_TIM3_UP; } + + break; + + case Timer::Timer4: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream6 && dma.channel == DMA::Channel2) { dma_map = DMAMAP_TIM4_UP; } + + break; + + case Timer::Timer5: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream0 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM5_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream6 && dma.channel == DMA::Channel6) { dma_map = DMAMAP_TIM5_UP_2; } + + break; + + case Timer::Timer6: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel7) { dma_map = DMAMAP_TIM6_UP; } + + break; + + case Timer::Timer7: + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream2 && dma.channel == DMA::Channel1) { dma_map = DMAMAP_TIM7_UP_1; } + + if (dma.index == DMA::Index1 && dma.stream == DMA::Stream4 && dma.channel == DMA::Channel1) { dma_map = DMAMAP_TIM7_UP_2; } + + break; + + case Timer::Timer8: + if (dma.index == DMA::Index2 && dma.stream == DMA::Stream1 && dma.channel == DMA::Channel7) { dma_map = DMAMAP_TIM8_UP; } + + break; + + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + case Timer::Timer12: + case Timer::Timer13: + case Timer::Timer14: + break; + } + + constexpr_assert(dma_map != 0, "Invalid DMA config for given timer"); + return dma_map; +} + diff --git a/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..89da314eae --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/io_timer_hw_description.h" + +static inline constexpr timer_io_channels_t initIOTimerGPIOInOut(Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret{}; + uint32_t gpio_af = 0; + + switch (timer.timer) { + case Timer::Timer1: + case Timer::Timer2: + gpio_af = GPIO_AF1; + break; + + case Timer::Timer3: + case Timer::Timer4: + case Timer::Timer5: + gpio_af = GPIO_AF2; + break; + + case Timer::Timer6: + case Timer::Timer7: + case Timer::Timer8: + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + gpio_af = GPIO_AF3; + break; + + case Timer::Timer12: + case Timer::Timer13: + case Timer::Timer14: + gpio_af = GPIO_AF9; + break; + } + + uint32_t pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin); + ret.gpio_in = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_FLOAT) | pin_port; + ret.gpio_out = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_PUSHPULL) | pin_port; + return ret; +} diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/hw_description.h new file mode 100644 index 0000000000..4663a2a50a --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/hw_description.h @@ -0,0 +1,94 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/hw_description.h" + +static inline constexpr uint32_t getTimerUpdateDMAMap(Timer::Timer timer, const DMA &dma) +{ + uint32_t dma_map = 0; + + switch (timer) { + case Timer::Timer1: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM1UP_0 : DMAMAP_DMA12_TIM1UP_1; + break; + + case Timer::Timer2: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM2UP_0 : DMAMAP_DMA12_TIM2UP_1; + + break; + + case Timer::Timer3: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM3UP_0 : DMAMAP_DMA12_TIM3UP_1; + + break; + + case Timer::Timer4: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM4UP_0 : DMAMAP_DMA12_TIM4UP_1; + + break; + + case Timer::Timer5: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM5UP_0 : DMAMAP_DMA12_TIM5UP_1; + + break; + + case Timer::Timer6: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM6UP_0 : DMAMAP_DMA12_TIM6UP_1; + + break; + + case Timer::Timer7: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM7UP_0 : DMAMAP_DMA12_TIM7UP_1; + + break; + + case Timer::Timer8: + dma_map = (dma.index == DMA::Index1) ? DMAMAP_DMA12_TIM8UP_0 : DMAMAP_DMA12_TIM8UP_1; + + break; + + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + case Timer::Timer12: + case Timer::Timer13: + case Timer::Timer14: + break; + } + + constexpr_assert(dma_map != 0, "Invalid DMA config for given timer"); + return dma_map; +} + diff --git a/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer_hw_description.h new file mode 100644 index 0000000000..6711c2fe35 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/io_timer_hw_description.h @@ -0,0 +1,237 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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. + * + ****************************************************************************/ +#pragma once + +#include +#include +#include +#include +#include +#include + +static inline constexpr timer_io_channels_t initIOTimerGPIOInOut(Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret{}; + uint32_t gpio_af = 0; + + switch (timer.timer) { + case Timer::Timer1: + case Timer::Timer2: + gpio_af = GPIO_AF1; + break; + + case Timer::Timer3: + case Timer::Timer4: + case Timer::Timer5: + case Timer::Timer12: + gpio_af = GPIO_AF2; + break; + + case Timer::Timer6: + case Timer::Timer7: + case Timer::Timer8: + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + gpio_af = GPIO_AF3; + break; + + case Timer::Timer13: + case Timer::Timer14: + gpio_af = GPIO_AF9; + break; + } + + uint32_t pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin); + ret.gpio_in = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_FLOAT) | pin_port; + ret.gpio_out = gpio_af | (GPIO_ALT | GPIO_SPEED_50MHz | GPIO_PUSHPULL) | pin_port; + return ret; +} + + + +static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t io_timers_conf[MAX_IO_TIMERS], + Timer::TimerChannel timer, GPIO::GPIOPin pin) +{ + timer_io_channels_t ret = initIOTimerGPIOInOut(timer, pin); + + switch (timer.channel) { + case Timer::Channel1: + ret.ccr_offset = STM32_GTIM_CCR1_OFFSET; + ret.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF; + ret.timer_channel = 1; + break; + + case Timer::Channel2: + ret.ccr_offset = STM32_GTIM_CCR2_OFFSET; + ret.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF; + ret.timer_channel = 2; + break; + + case Timer::Channel3: + ret.ccr_offset = STM32_GTIM_CCR3_OFFSET; + ret.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF; + ret.timer_channel = 3; + break; + + case Timer::Channel4: + ret.ccr_offset = STM32_GTIM_CCR4_OFFSET; + ret.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF; + ret.timer_channel = 4; + break; + } + + // find timer index + ret.timer_index = 0xff; + const uint32_t timer_base = timerBaseRegister(timer.timer); + + for (int i = 0; i < MAX_IO_TIMERS; ++i) { + if (io_timers_conf[i].base == timer_base) { + ret.timer_index = i; + break; + } + } + + constexpr_assert(ret.timer_index != 0xff, "Timer not found"); + + return ret; +} + +static inline constexpr io_timers_t initIOTimer(Timer::Timer timer, DMA dshot_dma = {}) +{ + io_timers_t ret{}; + + switch (timer) { + case Timer::Timer1: + ret.base = STM32_TIM1_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM1EN; + ret.clock_freq = STM32_APB2_TIM1_CLKIN; + ret.vectorno = STM32_IRQ_TIMCC; + break; + + case Timer::Timer2: + ret.base = STM32_TIM2_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM2EN; + ret.clock_freq = STM32_APB1_TIM2_CLKIN; + ret.vectorno = STM32_IRQ_TIM2; + break; + + case Timer::Timer3: + ret.base = STM32_TIM3_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM3EN; + ret.clock_freq = STM32_APB1_TIM3_CLKIN; + ret.vectorno = STM32_IRQ_TIM3; + break; + + case Timer::Timer4: + ret.base = STM32_TIM4_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM4EN; + ret.clock_freq = STM32_APB1_TIM4_CLKIN; + ret.vectorno = STM32_IRQ_TIM4; + break; + + case Timer::Timer5: + ret.base = STM32_TIM5_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM5EN; + ret.clock_freq = STM32_APB1_TIM5_CLKIN; + ret.vectorno = STM32_IRQ_TIM5; + break; + + case Timer::Timer6: + ret.base = STM32_TIM6_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM6EN; + ret.clock_freq = STM32_APB1_TIM6_CLKIN; + ret.vectorno = STM32_IRQ_TIM6; + break; + + case Timer::Timer7: + ret.base = STM32_TIM7_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM7EN; + ret.clock_freq = STM32_APB1_TIM7_CLKIN; + ret.vectorno = STM32_IRQ_TIM7; + break; + + case Timer::Timer8: + ret.base = STM32_TIM8_BASE; + ret.clock_register = STM32_RCC_APB2ENR; + ret.clock_bit = RCC_APB2ENR_TIM8EN; + ret.clock_freq = STM32_APB2_TIM8_CLKIN; + ret.vectorno = STM32_IRQ_TIM8CC; + break; + + case Timer::Timer9: + case Timer::Timer10: + case Timer::Timer11: + constexpr_assert(false, "Invalid Timer"); + break; + + case Timer::Timer12: + ret.base = STM32_TIM12_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM12EN; + ret.clock_freq = STM32_APB1_TIM12_CLKIN; + ret.vectorno = STM32_IRQ_TIM12; + break; + + case Timer::Timer13: + ret.base = STM32_TIM13_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM13EN; + ret.clock_freq = STM32_APB1_TIM13_CLKIN; + ret.vectorno = STM32_IRQ_TIM13; + break; + + case Timer::Timer14: + ret.base = STM32_TIM14_BASE; + ret.clock_register = STM32_RCC_APB1LENR; + ret.clock_bit = RCC_APB1LENR_TIM14EN; + ret.clock_freq = STM32_APB1_TIM14_CLKIN; + ret.vectorno = STM32_IRQ_TIM14; + break; + } + + // DShot + if (dshot_dma.index != DMA::Invalid) { + ret.dshot.dma_base = getDMABaseRegister(dshot_dma); + ret.dshot.dmamap = getTimerUpdateDMAMap(timer, dshot_dma); + } + + return ret; +}