From 54150a8f62d57bd3af5efce1439ba3c29e20f07f Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Mar 2011 01:04:10 +0000 Subject: Incorporate changes from Uros Platise git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3419 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/Make.defs | 3 +- nuttx/arch/arm/src/stm32/chip.h | 2 +- nuttx/arch/arm/src/stm32/stm32.h | 65 ++++ nuttx/arch/arm/src/stm32/stm32_memorymap.h | 2 +- nuttx/arch/arm/src/stm32/stm32_tim.c | 512 +++++++++++++++++++++++++++++ nuttx/arch/arm/src/stm32/stm32_tim.h | 214 +++++++++--- 6 files changed, 741 insertions(+), 57 deletions(-) create mode 100644 nuttx/arch/arm/src/stm32/stm32.h create mode 100644 nuttx/arch/arm/src/stm32/stm32_tim.c (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 7595ff944..34b6458b1 100755 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -47,5 +47,6 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ CHIP_ASRCS = CHIP_CSRCS = stm32_start.c stm32_rcc.c stm32_gpio.c stm32_idle.c \ stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \ - stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c + stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c \ + stm32_tim.c diff --git a/nuttx/arch/arm/src/stm32/chip.h b/nuttx/arch/arm/src/stm32/chip.h index 9d6ed8eb3..28d59c838 100755 --- a/nuttx/arch/arm/src/stm32/chip.h +++ b/nuttx/arch/arm/src/stm32/chip.h @@ -75,7 +75,7 @@ # undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */ # define STM32_NATIM 2 /* Two advanced timers TIM1 and TIM8 */ # define STM32_NGTIM 4 /* General timers TIM2,3,4,5 */ -# define STM32 NBTIM 2 /* Two basic timers TIM6 and TIM7 */ +# define STM32_NBTIM 2 /* Two basic timers TIM6 and TIM7 */ # define STM32_NDMA 2 /* DMA1-2 */ # define STM32_NSPI 3 /* SPI1-3 */ # define STM32_NUSART 5 /* USART1-5 */ diff --git a/nuttx/arch/arm/src/stm32/stm32.h b/nuttx/arch/arm/src/stm32/stm32.h new file mode 100644 index 000000000..92628ab2e --- /dev/null +++ b/nuttx/arch/arm/src/stm32/stm32.h @@ -0,0 +1,65 @@ +/************************************************************************************ + * arch/arm/src/stm32/stm32.h + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Author: Uros Platise + * + * 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 NuttX 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_STM32_H +#define __ARCH_ARM_SRC_STM32_STM32_H + +#include "chip.h" +#include "stm32_adc.h" +#include "stm32_bkp.h" +#include "stm32_can.h" +#include "stm32_dgbmcu.h" +#include "stm32_dma.h" +#include "stm32_exti.h" +#include "stm32_flash.h" +#include "stm32_fsmc.h" +#include "stm32_gpio.h" +#include "stm32_i2c.h" +#include "stm32_pwr.h" +#include "stm32_rcc.h" +#include "stm32_rtc.h" +#include "stm32_sdio.h" +#include "stm32_spi.h" +#include "stm32_tim.h" +#include "stm32_uart.h" +#include "stm32_usbdev.h" +#include "stm32_wdg.h" + +/* TODO: Inconsistency! Code uses GPIO macros from this file instead from gpio.h! + * _internal also includes pinmap.h file. + */ +#include "stm32_internal.h" + +#endif /* __ARCH_ARM_SRC_STM32_STM32_H */ diff --git a/nuttx/arch/arm/src/stm32/stm32_memorymap.h b/nuttx/arch/arm/src/stm32/stm32_memorymap.h index 09b91185f..dea7c49e7 100755 --- a/nuttx/arch/arm/src/stm32/stm32_memorymap.h +++ b/nuttx/arch/arm/src/stm32/stm32_memorymap.h @@ -105,7 +105,7 @@ #define STM32_ADC2_BASE 0x40012800 /* 0x40012800 - 0x40012bff: ADC2 */ #define STM32_TIM1_BASE 0x40012c00 /* 0x40012c00 - 0x40012fff: TIM1 timer */ #define STM32_SPI1_BASE 0x40013000 /* 0x40013000 - 0x400133ff: SPI1 */ -#define STM32_TIM8_BASE 0x40012c00 /* 0x40013400 - 0x400137ff: TIM8 timer */ +#define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */ #define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */ #define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013fff: ADC3 */ /* 0x40014000 - 0x40017fff: Reserved */ diff --git a/nuttx/arch/arm/src/stm32/stm32_tim.c b/nuttx/arch/arm/src/stm32/stm32_tim.c new file mode 100644 index 000000000..e185b1a87 --- /dev/null +++ b/nuttx/arch/arm/src/stm32/stm32_tim.c @@ -0,0 +1,512 @@ +/************************************************************************************ + * arm/arm/src/stm32/stm32_tim.c + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Author: Uros Platise + * + * 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 NuttX 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 + * \author Uros Platise + * \brief STM32 Basic, General and Advanced Timers + */ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include "chip.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "stm32_internal.h" +#include "stm32_gpio.h" +#include "stm32_tim.h" + + +#define getreg16(a) (*(volatile uint16_t *)(a)) +#define putreg16(v,a) (*(volatile uint16_t *)(a) = (v)) + + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/** TIM Device Structure + */ +struct stm32_tim_priv_s { + struct stm32_tim_ops_s *ops; + stm32_tim_mode_t mode; + + uint32_t base; /** TIMn base address */ + uint8_t irqno; /** TIM IRQ number */ +}; + + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + + +/** Get register value by offset */ +static inline uint16_t stm32_tim_getreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset) +{ + return getreg16( ((struct stm32_tim_priv_s *)dev)->base + offset); +} + + +/** Put register value by offset */ +static inline void stm32_tim_putreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset, uint16_t value) +{ + //printf("putreg(%8x)=%4x\n", ((struct stm32_tim_priv_s *)dev)->base + offset, value ); + putreg16(value, ((struct stm32_tim_priv_s *)dev)->base + offset); +} + + +/** Modify register value by offset */ +static inline void stm32_tim_modifyreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset, uint16_t clearbits, uint16_t setbits) +{ + modifyreg16( ((struct stm32_tim_priv_s *)dev)->base + offset, clearbits, setbits); +} + + +static void stm32_tim_reload_counter(FAR struct stm32_tim_dev_s *dev) +{ + uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_EGR_OFFSET); + val |= ATIM_EGR_UG; + stm32_tim_putreg(dev, STM32_BTIM_EGR_OFFSET, val); +} + + +static void stm32_tim_enable(FAR struct stm32_tim_dev_s *dev) +{ + uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_CR1_OFFSET); + val |= ATIM_CR1_CEN; + stm32_tim_reload_counter(dev); + stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val); +} + + +static void stm32_tim_disable(FAR struct stm32_tim_dev_s *dev) +{ + uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_CR1_OFFSET); + val &= ~ATIM_CR1_CEN; + stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val); +} + + +/** Reset timer into system default state, but do not affect output/input pins */ +static void stm32_tim_reset(FAR struct stm32_tim_dev_s *dev) +{ + ((struct stm32_tim_priv_s *)dev)->mode = STM32_TIM_MODE_DISABLED; + stm32_tim_disable(dev); +} + + +/************************************************************************************ + * Basic Functions + ************************************************************************************/ + +static int stm32_tim_setclock(FAR struct stm32_tim_dev_s *dev, uint32_t freq) +{ + int prescaler; + + ASSERT(dev); + + /* Disable Timer? */ + if (freq == 0) { + stm32_tim_disable(dev); + return 0; + } + +#if STM32_NATIM > 0 + if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM1_BASE || + ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM8_BASE) + prescaler = STM32_TIM18_FREQUENCY / freq; + else +#endif + prescaler = STM32_TIM27_FREQUENCY / freq; + + /* we need to decrement value for '1', but only, if we are allowed to + * not to cause underflow. Check for overflow. + */ + if (prescaler > 0) prescaler--; + if (prescaler > 0xFFFF) prescaler = 0xFFFF; + + stm32_tim_putreg(dev, STM32_BTIM_PSC_OFFSET, prescaler); + stm32_tim_enable(dev); + + return prescaler; +} + + +static void stm32_tim_setperiod(FAR struct stm32_tim_dev_s *dev, uint16_t period) +{ + ASSERT(dev); + stm32_tim_putreg(dev, STM32_BTIM_ARR_OFFSET, period); +} + + +static int stm32_tim_setisr(FAR struct stm32_tim_dev_s *dev, int (*handler)(int irq, void *context), int source) +{ + int vectorno; + + ASSERT(dev); + ASSERT(source==0); + + switch( ((struct stm32_tim_priv_s *)dev)->base ) { + case STM32_TIM3_BASE: vectorno = STM32_IRQ_TIM3; break; + +#if STM32_NATIM > 0 + /** \todo add support for multiple sources and callbacks */ + case STM32_TIM1_BASE: vectorno = STM32_IRQ_TIM1UP; break; + case STM32_TIM8_BASE: vectorno = STM32_IRQ_TIM8UP; break; +#endif + default: return ERROR; + } + + /* Disable interrupt when callback is removed */ + + if (!handler) { + up_disable_irq(vectorno); + irq_detach(vectorno); + return OK; + } + + /* Otherwise set callback and enable interrupt */ + + printf("Attaching ISR: %d, %p\n", vectorno, handler); + + irq_attach(vectorno, handler); + up_enable_irq(vectorno); +// up_prioritize_irq(vectorno, NVIC_SYSH_PRIORITY_DEFAULT); + return OK; +} + + +static void stm32_tim_enableint(FAR struct stm32_tim_dev_s *dev, int source) +{ + ASSERT(dev); + stm32_tim_modifyreg(dev, STM32_BTIM_DIER_OFFSET, 0, ATIM_DIER_UIE); +} + + +static void stm32_tim_disableint(FAR struct stm32_tim_dev_s *dev, int source) +{ + ASSERT(dev); + stm32_tim_modifyreg(dev, STM32_BTIM_DIER_OFFSET, ATIM_DIER_UIE, 0); +} + + +static void stm32_tim_ackint(FAR struct stm32_tim_dev_s *dev, int source) +{ + stm32_tim_putreg(dev, STM32_BTIM_SR_OFFSET, ~ATIM_SR_UIF); +} + + + +/************************************************************************************ + * General Functions + ************************************************************************************/ + +static int stm32_tim_setmode(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode) +{ + uint16_t val = ATIM_CR1_CEN | ATIM_CR1_ARPE; + + ASSERT(dev); + + /* This function is not supported on basic timers. To enable or + * disable it, simply set its clock to valid frequency or zero. + */ + +#if STM32_NBTIM > 0 + if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM6_BASE +#endif +#if STM32_NBTIM > 1 + || ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM7_BASE +#endif +#if STM32_NBTIM > 0 + ) return ERROR; +#endif + + /* Decode operational modes */ + + switch(mode & STM32_TIM_MODE_MASK) { + + case STM32_TIM_MODE_DISABLED: + val = 0; + break; + + case STM32_TIM_MODE_DOWN: + val |= ATIM_CR1_DIR; + + case STM32_TIM_MODE_UP: + break; + + case STM32_TIM_MODE_UPDOWN: + val |= ATIM_CR1_CENTER1; + // Our default: Interrupts are generated on compare, when counting down + break; + + case STM32_TIM_MODE_PULSE: + val |= ATIM_CR1_OPM; + break; + + default: return ERROR; + } + + stm32_tim_reload_counter(dev); + stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val); + +#if STM32_NATIM > 0 + /* Advanced registers require Main Output Enable */ + + if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM1_BASE || + ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM8_BASE) { + stm32_tim_modifyreg(dev, STM32_ATIM_BDTR_OFFSET, 0, ATIM_BDTR_MOE); + } +#endif + + return OK; +} + + +static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel, stm32_tim_channel_t mode) +{ + uint16_t ccmr_val = 0; + uint16_t ccer_val = stm32_tim_getreg(dev, STM32_GTIM_CCER_OFFSET); + uint8_t ccmr_offset = STM32_GTIM_CCMR1_OFFSET; + + ASSERT(dev); + + /* Further we use range as 0..3; if channel=0 it will also overflow here */ + + if (--channel > 4) return ERROR; + + /* Assume that channel is disabled and polarity is active high */ + + ccer_val &= ~(3 << (channel << 2)); + + /* This function is not supported on basic timers. To enable or + * disable it, simply set its clock to valid frequency or zero. + */ + +#if STM32_NBTIM > 0 + if ( ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM6_BASE +#endif +#if STM32_NBTIM > 1 + || ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM7_BASE +#endif +#if STM32_NBTIM > 0 + ) return ERROR; +#endif + + /* Decode configuration */ + + switch(mode & STM32_TIM_CH_MODE_MASK) { + + case STM32_TIM_CH_DISABLED: + break; + + case STM32_TIM_CH_OUTPWM: + ccmr_val = (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) + ATIM_CCMR1_OC1PE; + ccer_val |= ATIM_CCER_CC1E << (channel << 2); + break; + + default: + return ERROR; + } + + /* Set polarity */ + + if (mode & STM32_TIM_CH_POLARITY_NEG) + ccer_val |= ATIM_CCER_CC1P << (channel << 2); + + /* define its position (shift) and get register offset */ + + if (channel & 1) ccmr_val <<= 8; + if (channel > 1) ccmr_offset = STM32_GTIM_CCMR2_OFFSET; + + stm32_tim_putreg(dev, ccmr_offset, ccmr_val); + stm32_tim_putreg(dev, STM32_GTIM_CCER_OFFSET, ccer_val); + + return OK; +} + + +static int stm32_tim_setcompare(FAR struct stm32_tim_dev_s *dev, uint8_t channel, uint16_t compare) +{ + ASSERT(dev); + + switch(channel) { + case 1: stm32_tim_putreg(dev, STM32_GTIM_CCR1_OFFSET, compare); break; + case 2: stm32_tim_putreg(dev, STM32_GTIM_CCR2_OFFSET, compare); break; + case 3: stm32_tim_putreg(dev, STM32_GTIM_CCR3_OFFSET, compare); break; + case 4: stm32_tim_putreg(dev, STM32_GTIM_CCR4_OFFSET, compare); break; + default: return ERROR; + } + return OK; +} + + +static int stm32_tim_getcapture(FAR struct stm32_tim_dev_s *dev, uint8_t channel) +{ + ASSERT(dev); + + switch(channel) { + case 1: return stm32_tim_getreg(dev, STM32_GTIM_CCR1_OFFSET); + case 2: return stm32_tim_getreg(dev, STM32_GTIM_CCR2_OFFSET); + case 3: return stm32_tim_getreg(dev, STM32_GTIM_CCR3_OFFSET); + case 4: return stm32_tim_getreg(dev, STM32_GTIM_CCR4_OFFSET); + } + return ERROR; +} + + +/************************************************************************************ + * Advanced Functions + ************************************************************************************/ + +/** \todo Advanced functions for the STM32_ATIM */ + + +/************************************************************************************ + * Device Structures, Instantiation + ************************************************************************************/ + +struct stm32_tim_ops_s stm32_tim_ops = { + .setmode = &stm32_tim_setmode, + .setclock = &stm32_tim_setclock, + .setperiod = &stm32_tim_setperiod, + .setchannel = &stm32_tim_setchannel, + .setcompare = &stm32_tim_setcompare, + .getcapture = &stm32_tim_getcapture, + .setisr = &stm32_tim_setisr, + .enableint = &stm32_tim_enableint, + .disableint = &stm32_tim_disableint, + .ackint = &stm32_tim_ackint +}; + + +struct stm32_tim_priv_s stm32_tim3_priv = { + .ops = &stm32_tim_ops, + .mode = STM32_TIM_MODE_UNUSED, + .base = STM32_TIM3_BASE, +}; + +#if STM32_NATIM > 0 + +struct stm32_tim_priv_s stm32_tim1_priv = { + .ops = &stm32_tim_ops, + .mode = STM32_TIM_MODE_UNUSED, + .base = STM32_TIM1_BASE, +}; + +struct stm32_tim_priv_s stm32_tim8_priv = { + .ops = &stm32_tim_ops, + .mode = STM32_TIM_MODE_UNUSED, + .base = STM32_TIM8_BASE, +}; + +#endif + + +/************************************************************************************ + * Public Function - Initialization + ************************************************************************************/ + +FAR struct stm32_tim_dev_s * stm32_tim_init(int timer) +{ + struct stm32_tim_dev_s * dev = NULL; + + /* Get structure and enable power */ + + switch(timer) { + case 3: + dev = (struct stm32_tim_dev_s *)&stm32_tim3_priv; + modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN); + break; + +#if STM32_NATIM > 0 + case 1: + dev = (struct stm32_tim_dev_s *)&stm32_tim1_priv; + modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); + break; + + case 8: + dev = (struct stm32_tim_dev_s *)&stm32_tim8_priv; + modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM8EN); + break; +#endif + default: return NULL; + } + + /* Is device already allocated */ + + if ( ((struct stm32_tim_priv_s *)dev)->mode != STM32_TIM_MODE_UNUSED) + return NULL; + + stm32_tim_reset(dev); + + return dev; +} + + +int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev) +{ + ASSERT(dev); + + /* Disable power */ + + switch( ((struct stm32_tim_priv_s *)dev)->base ) { + case STM32_TIM3_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM3EN, 0); break; + +#if STM32_NATIM > 0 + case STM32_TIM1_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM1EN, 0); break; + case STM32_TIM8_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM8EN, 0); break; +#endif + default: return ERROR; + } + + /* Mark it as free */ + + ((struct stm32_tim_priv_s *)dev)->mode = STM32_TIM_MODE_UNUSED; + + return OK; +} diff --git a/nuttx/arch/arm/src/stm32/stm32_tim.h b/nuttx/arch/arm/src/stm32/stm32_tim.h index 21b37bb72..60cbec691 100644 --- a/nuttx/arch/arm/src/stm32/stm32_tim.h +++ b/nuttx/arch/arm/src/stm32/stm32_tim.h @@ -2,7 +2,9 @@ * arch/arm/src/stm32/stm32_tim.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2011 Uros Platise. All rights reserved. * Author: Gregory Nutt + * Uros Platise * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,6 +35,11 @@ * ************************************************************************************/ +/** \file + * \author Gregory Nutt, Uros Platise + * \brief STM32 Timers + */ + #ifndef __ARCH_ARM_SRC_STM32_STM32_TIM_H #define __ARCH_ARM_SRC_STM32_STM32_TIM_H @@ -41,7 +48,6 @@ ************************************************************************************/ #include - #include "chip.h" /************************************************************************************ @@ -50,28 +56,16 @@ /* Register Offsets *****************************************************************/ -/* Advanced Timers - TIM1 and TIM8 */ +/* Basic Timers - TIM6 and TIM7 */ -#define STM32_ATIM_CR1_OFFSET 0x0000 /* Control register 1 (16-bit) */ -#define STM32_ATIM_CR2_OFFSET 0x0004 /* Control register 2 *(16-bit) */ -#define STM32_ATIM_SMCR_OFFSET 0x0008 /* Slave mode control register (16-bit) */ -#define STM32_ATIM_DIER_OFFSET 0x000c /* DMA/Interrupt enable register (16-bit) */ -#define STM32_ATIM_SR_OFFSET 0x0010 /* Status register (16-bit) */ -#define STM32_ATIM_EGR_OFFSET 0x0014 /* Event generation register (16-bit) */ -#define STM32_ATIM_CCMR1_OFFSET 0x0018 /* Capture/compare mode register 1 (16-bit) */ -#define STM32_ATIM_CCMR2_OFFSET 0x001c /* Capture/compare mode register 2 (16-bit) */ -#define STM32_ATIM_CCER_OFFSET 0x0020 /* Capture/compare enable register (16-bit) */ -#define STM32_ATIM_CNT_OFFSET 0x0024 /* Counter (16-bit) */ -#define STM32_ATIM_PSC_OFFSET 0x0028 /* Prescaler (16-bit) */ -#define STM32_ATIM_ARR_OFFSET 0x002c /* Auto-reload register (16-bit) */ -#define STM32_ATIM_RCR_OFFSET 0x0030 /* Repetition counter register (16-bit) */ -#define STM32_ATIM_CCR1_OFFSET 0x0034 /* Capture/compare register 1 (16-bit) */ -#define STM32_ATIM_CCR2_OFFSET 0x0038 /* Capture/compare register 2 (16-bit) */ -#define STM32_ATIM_CCR3_OFFSET 0x003c /* Capture/compare register 3 (16-bit) */ -#define STM32_ATIM_CCR4_OFFSET 0x0040 /* Capture/compare register 4 (16-bit) */ -#define STM32_ATIM_BDTR_OFFSET 0x0044 /* Break and dead-time register (16-bit) */ -#define STM32_ATIM_DCR_OFFSET 0x0048 /* DMA control register (16-bit) */ -#define STM32_ATIM_DMAR_OFFSET 0x004c /* DMA address for burst mode (16-bit) */ +#define STM32_BTIM_CR1_OFFSET 0x0000 /* Control register 1 (16-bit) */ +#define STM32_BTIM_CR2_OFFSET 0x0004 /* Control register 2 (16-bit) */ +#define STM32_BTIM_DIER_OFFSET 0x000c /* DMA/Interrupt enable register (16-bit) */ +#define STM32_BTIM_SR_OFFSET 0x0010 /* Status register (16-bit) */ +#define STM32_BTIM_EGR_OFFSET 0x0014 /* Event generation register (16-bit) */ +#define STM32_BTIM_CNT_OFFSET 0x0024 /* Counter (16-bit) */ +#define STM32_BTIM_PSC_OFFSET 0x0028 /* Prescaler (16-bit) */ +#define STM32_BTIM_ARR_OFFSET 0x002c /* Auto-reload register (16-bit) */ /* General Timers - TIM2, TIM3, TIM4, and TIM5 */ @@ -94,16 +88,28 @@ #define STM32_GTIM_DCR_OFFSET 0x0048 /* DMA control register (16-bit) */ #define STM32_GTIM_DMAR_OFFSET 0x004c /* DMA address for burst mode (16-bit) */ -/* Basic Timers - TIM6 and TIM7 */ +/* Advanced Timers - TIM1 and TIM8 */ -#define STM32_BTIM_CR1_OFFSET 0x0000 /* Control register 1 (16-bit) */ -#define STM32_BTIM_CR2_OFFSET 0x0004 /* Control register 2 (16-bit) */ -#define STM32_BTIM_DIER_OFFSET 0x000c /* DMA/Interrupt enable register (16-bit) */ -#define STM32_BTIM_SR_OFFSET 0x0010 /* Status register (16-bit) */ -#define STM32_BTIM_EGR_OFFSET 0x0014 /* Event generation register (16-bit) */ -#define STM32_BTIM_CNT_OFFSET 0x0024 /* Counter (16-bit) */ -#define STM32_BTIM_PSC_OFFSET 0x0028 /* Prescaler (16-bit) */ -#define STM32_BTIM_ARR_OFFSET 0x002c /* Auto-reload register (16-bit) */ +#define STM32_ATIM_CR1_OFFSET 0x0000 /* Control register 1 (16-bit) */ +#define STM32_ATIM_CR2_OFFSET 0x0004 /* Control register 2 *(16-bit) */ +#define STM32_ATIM_SMCR_OFFSET 0x0008 /* Slave mode control register (16-bit) */ +#define STM32_ATIM_DIER_OFFSET 0x000c /* DMA/Interrupt enable register (16-bit) */ +#define STM32_ATIM_SR_OFFSET 0x0010 /* Status register (16-bit) */ +#define STM32_ATIM_EGR_OFFSET 0x0014 /* Event generation register (16-bit) */ +#define STM32_ATIM_CCMR1_OFFSET 0x0018 /* Capture/compare mode register 1 (16-bit) */ +#define STM32_ATIM_CCMR2_OFFSET 0x001c /* Capture/compare mode register 2 (16-bit) */ +#define STM32_ATIM_CCER_OFFSET 0x0020 /* Capture/compare enable register (16-bit) */ +#define STM32_ATIM_CNT_OFFSET 0x0024 /* Counter (16-bit) */ +#define STM32_ATIM_PSC_OFFSET 0x0028 /* Prescaler (16-bit) */ +#define STM32_ATIM_ARR_OFFSET 0x002c /* Auto-reload register (16-bit) */ +#define STM32_ATIM_RCR_OFFSET 0x0030 /* Repetition counter register (16-bit) */ +#define STM32_ATIM_CCR1_OFFSET 0x0034 /* Capture/compare register 1 (16-bit) */ +#define STM32_ATIM_CCR2_OFFSET 0x0038 /* Capture/compare register 2 (16-bit) */ +#define STM32_ATIM_CCR3_OFFSET 0x003c /* Capture/compare register 3 (16-bit) */ +#define STM32_ATIM_CCR4_OFFSET 0x0040 /* Capture/compare register 4 (16-bit) */ +#define STM32_ATIM_BDTR_OFFSET 0x0044 /* Break and dead-time register (16-bit) */ +#define STM32_ATIM_DCR_OFFSET 0x0048 /* DMA control register (16-bit) */ +#define STM32_ATIM_DMAR_OFFSET 0x004c /* DMA address for burst mode (16-bit) */ /* Register Addresses ***************************************************************/ @@ -269,23 +275,23 @@ /* Control register 1 */ -#define ATIM_SR_CEN (1 << 0) /* Bit 0: Counter enable */ -#define ATIM_SR_UDIS (1 << 1) /* Bit 1: Update disable */ -#define ATIM_SR_URS (1 << 2) /* Bit 2: Update request source */ -#define ATIM_SR_OPM (1 << 3) /* Bit 3: One pulse mode */ -#define ATIM_SR_DIR (1 << 4) /* Bit 4: Direction */ -#define ATIM_SR_CMS_SHIFT (5) /* Bits 6-5: Center-aligned mode selection */ -#define ATIM_SR_CMS_MASK (3 << ATIM_SR_CMS_SHIFT) -# define ATIM_SR_EDGE (0 << ATIM_SR_CMS_SHIFT) /* 00: Edge-aligned mode */ -# define ATIM_SR_CENTER1 (1 << ATIM_SR_CMS_SHIFT) /* 01: Center-aligned mode 1 */ -# define ATIM_SR_CENTER2 (2 << ATIM_SR_CMS_SHIFT) /* 10: Center-aligned mode 2 */ -# define ATIM_SR_CENTER3 (3 << ATIM_SR_CMS_SHIFT) /* 11: Center-aligned mode 3 */ -#define ATIM_SR_ARPE (1 << 7) /* Bit 7: Auto-reload preload enable */ -#define ATIM_SR_CKD_SHIFT (8) /* Bits 9-8: Clock division */ -#define ATIM_SR_CKD_MASK (3 << ATIM_SR_CKD_SHIFT) -# define ATIM_SR_TCKINT (0 << ATIM_SR_CKD_SHIFT) /* 00: tDTS=tCK_INT */ -# define ATIM_SR_2TCKINT (1 << ATIM_SR_CKD_SHIFT) /* 01: tDTS=2*tCK_INT */ -# define ATIM_SR_4TCKINT (2 << ATIM_SR_CKD_SHIFT) /* 10: tDTS=4*tCK_INT */ +#define ATIM_CR1_CEN (1 << 0) /* Bit 0: Counter enable */ +#define ATIM_CR1_UDIS (1 << 1) /* Bit 1: Update disable */ +#define ATIM_CR1_URS (1 << 2) /* Bit 2: Update request source */ +#define ATIM_CR1_OPM (1 << 3) /* Bit 3: One pulse mode */ +#define ATIM_CR1_DIR (1 << 4) /* Bit 4: Direction */ +#define ATIM_CR1_CMS_SHIFT (5) /* Bits 6-5: Center-aligned mode selection */ +#define ATIM_CR1_CMS_MASK (3 << ATIM_CR1_CMS_SHIFT) +# define ATIM_CR1_EDGE (0 << ATIM_CR1_CMS_SHIFT) /* 00: Edge-aligned mode */ +# define ATIM_CR1_CENTER1 (1 << ATIM_CR1_CMS_SHIFT) /* 01: Center-aligned mode 1 */ +# define ATIM_CR1_CENTER2 (2 << ATIM_CR1_CMS_SHIFT) /* 10: Center-aligned mode 2 */ +# define ATIM_CR1_CENTER3 (3 << ATIM_CR1_CMS_SHIFT) /* 11: Center-aligned mode 3 */ +#define ATIM_CR1_ARPE (1 << 7) /* Bit 7: Auto-reload preload enable */ +#define ATIM_CR1_CKD_SHIFT (8) /* Bits 9-8: Clock division */ +#define ATIM_CR1_CKD_MASK (3 << ATIM_CR1_CKD_SHIFT) +# define ATIM_CR1_TCKINT (0 << ATIM_CR1_CKD_SHIFT) /* 00: tDTS=tCK_INT */ +# define ATIM_CR1_2TCKINT (1 << ATIM_CR1_CKD_SHIFT) /* 01: tDTS=2*tCK_INT */ +# define ATIM_CR1_4TCKINT (2 << ATIM_CR1_CKD_SHIFT) /* 10: tDTS=4*tCK_INT */ /* Control register 2 */ @@ -508,7 +514,7 @@ /* Bits 1-0:(same as output compare mode) */ #define ATIM_CCMR2_IC3PSC_SHIFT (2) /* Bits 3-2: Input Capture 3 Prescaler */ -#define ATIM_CCMR1_IC1PSC_MASK (3 << ATIM_CCMR2_IC3PSC_SHIFT) +#define ATIM_CCMR1_IC3PSC_MASK (3 << ATIM_CCMR2_IC3PSC_SHIFT) /* (See common (unshifted) bit field definitions above) */ #define ATIM_CCMR2_IC3F_SHIFT (4) /* Bits 7-4: Input Capture 3 Filter */ #define ATIM_CCMR2_IC3F_MASK (0x0f << ATIM_CCMR2_IC3F_SHIFT) @@ -589,7 +595,7 @@ /* Control register 2 */ -#define GTIM_CR2_CCDS (1 << 3) /* Bit 3: Capture/Compare DMA Selection. +#define GTIM_CR2_CCDS (1 << 3) /* Bit 3: Capture/Compare DMA Selection. */ #define GTIM_CR2_MMS_SHIFT (4) /* Bits 6-4: Master Mode Selection */ #define GTIM_CR2_MMS_MASK (7 << GTIM_CR2_MMS_SHIFT) # define GTIM_CR2_RESET (0 << GTIM_CR2_MMS_SHIFT) /* 000: Reset */ @@ -609,7 +615,7 @@ # define GTIM_SMCR_DISAB (0 << GTIM_SMCR_SMS_SHIFT) /* 000: Slave mode disabled */ # define GTIM_SMCR_ENCMD1 (1 << GTIM_SMCR_SMS_SHIFT) /* 001: Encoder mode 1 */ # define GTIM_SMCR_ENCMD2 (2 << GTIM_SMCR_SMS_SHIFT) /* 010: Encoder mode 2 */ -# define GTIM_SMCR_ENCMD2 (3 << GTIM_SMCR_SMS_SHIFT) /* 011: Encoder mode 3 */ +# define GTIM_SMCR_ENCMD3 (3 << GTIM_SMCR_SMS_SHIFT) /* 011: Encoder mode 3 */ # define GTIM_SMCR_RESET (4 << GTIM_SMCR_SMS_SHIFT) /* 100: Reset Mode */ # define GTIM_SMCR_GATED (5 << GTIM_SMCR_SMS_SHIFT) /* 101: Gated Mode */ # define GTIM_SMCR_TRIGGER (6 << GTIM_SMCR_SMS_SHIFT) /* 110: Trigger Mode */ @@ -856,17 +862,117 @@ #define BTIM_EGR_UG (1 << 0) /* Bit 0: Update generation */ + /************************************************************************************ * Public Types ************************************************************************************/ -/************************************************************************************ - * Public Data - ************************************************************************************/ +/** TIM Device Structure + */ +struct stm32_tim_dev_s { + struct stm32_tim_ops_s *ops; +}; + + +/** TIM Modes of Operation + */ +typedef enum { + STM32_TIM_MODE_UNUSED = -1, + + /* One of the following */ + STM32_TIM_MODE_MASK = 0x0300, + STM32_TIM_MODE_DISABLED = 0x0000, + STM32_TIM_MODE_UP = 0x0100, + STM32_TIM_MODE_DOWN = 0x0110, + STM32_TIM_MODE_UPDOWN = 0x0200, + STM32_TIM_MODE_PULSE = 0x0300, + + /* One of the following */ + STM32_TIM_MODE_CK_INT = 0x0000, +// STM32_TIM_MODE_CK_INT_TRIG = 0x0400, +// STM32_TIM_MODE_CK_EXT = 0x0800, +// STM32_TIM_MODE_CK_EXT_TRIG = 0x0C00, + + /* Clock sources, OR'ed with CK_EXT */ +// STM32_TIM_MODE_CK_CHINVALID = 0x0000, +// STM32_TIM_MODE_CK_CH1 = 0x0001, +// STM32_TIM_MODE_CK_CH2 = 0x0002, +// STM32_TIM_MODE_CK_CH3 = 0x0003, +// STM32_TIM_MODE_CK_CH4 = 0x0004 + + /* Todo: external trigger block */ + +} stm32_tim_mode_t; + + +/** TIM Channel Modes + */ +typedef enum { + STM32_TIM_CH_DISABLED = 0x00, + + /* Common configuration */ + STM32_TIM_CH_POLARITY_POS = 0x00, + STM32_TIM_CH_POLARITY_NEG = 0x01, + + /* MODES: */ + STM32_TIM_CH_MODE_MASK = 0x06, + + /* Output Compare Modes */ + STM32_TIM_CH_OUTPWM = 0x04, /** Enable standard PWM mode, active high when counter < compare */ +// STM32_TIM_CH_OUTCOMPARE = 0x06, + + // TODO other modes ... as PWM capture, ENCODER and Hall Sensor +// STM32_TIM_CH_INCAPTURE = 0x10, +// STM32_TIM_CH_INPWM = 0x20 + +} stm32_tim_channel_t; + + +/** TIM Operations + */ +struct stm32_tim_ops_s { + + /* Basic Timers */ + + int (*setmode)(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode); + int (*setclock)(FAR struct stm32_tim_dev_s *dev, uint32_t freq); + void (*setperiod)(FAR struct stm32_tim_dev_s *dev, uint16_t period); + + /* General and Advanced Timers Adds */ + + int (*setchannel)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, stm32_tim_channel_t mode); + int (*setcompare)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, uint16_t compare); + int (*getcapture)(FAR struct stm32_tim_dev_s *dev, uint8_t channel); + + int (*setisr)(FAR struct stm32_tim_dev_s *dev, int (*handler)(int irq, void *context), int source); + void (*enableint)(FAR struct stm32_tim_dev_s *dev, int source); + void (*disableint)(FAR struct stm32_tim_dev_s *dev, int source); + void (*ackint)(FAR struct stm32_tim_dev_s *dev, int source); +}; + + +/* Helpers */ + +#define STM32_TIM_SETMODE(d,mode) ((d)->ops->setmode(d,mode)) +#define STM32_TIM_SETCLOCK(d,freq) ((d)->ops->setclock(d,freq)) +#define STM32_TIM_SETPERIOD(d,period) ((d)->ops->setperiod(d,period)) +#define STM32_TIM_SETCHANNEL(d,ch,mode) ((d)->ops->setchannel(d,ch,mode)) +#define STM32_TIM_SETCOMPARE(d,ch,comp) ((d)->ops->setcompare(d,ch,comp)) +#define STM32_TIM_GETCAPTURE(d,ch) ((d)->ops->getcapture(d,ch)) +#define STM32_TIM_SETISR(d,hnd,s) ((d)->ops->setisr(d,hnd,s)) +#define STM32_TIM_ENABLEINT(d,s) ((d)->ops->enableint(d,s)) +#define STM32_TIM_DISABLEINT(d,s) ((d)->ops->disableint(d,s)) +#define STM32_TIM_ACKINT(d,s) ((d)->ops->ackint(d,s)) /************************************************************************************ * Public Functions ************************************************************************************/ +/** Power-up timer and get its structure */ +FAR struct stm32_tim_dev_s * stm32_tim_init(int timer); + +/** Power-down timer, mark it as unused */ +int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev); + #endif /* __ARCH_ARM_SRC_STM32_STM32_TIM_H */ -- cgit v1.2.3