summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-28 15:01:43 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-28 15:01:43 +0000
commit82fb23b2cc78fade702316d00510efcf9d65954f (patch)
treea997a6f40b080a1e31890359dde9fc466e726221 /nuttx/arch/arm
parentb197eb1609652b2b766bb79caf00b23ef07eed40 (diff)
downloadpx4-nuttx-82fb23b2cc78fade702316d00510efcf9d65954f.tar.gz
px4-nuttx-82fb23b2cc78fade702316d00510efcf9d65954f.tar.bz2
px4-nuttx-82fb23b2cc78fade702316d00510efcf9d65954f.zip
More changes from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3431 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f103re_pinmap.h15
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h52
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c302
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_i2c.h2
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_rcc.c30
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_tim.c177
6 files changed, 456 insertions, 122 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103re_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103re_pinmap.h
index 3e238ece1..a41001525 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f103re_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f103re_pinmap.h
@@ -295,24 +295,17 @@
/* CAN */
-#if defined(CONFIG_STM32_CAN1_FULL_REMAP)
-# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
-# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
-#elif defined(CONFIG_STM32_CAN1_PARTIAL_REMAP)
+#if defined(CONFIG_STM32_CAN1_REMAP1)
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
+#elif defined(CONFIG_STM32_CAN1_REMAP2)
+# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
+# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
#else
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
#endif
-#if defined(CONFIG_STM32_CAN2_REMAP)
-# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
-# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
-#else
-# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
-# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
-#endif
/* SDIO */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
index 80ba6c329..3caf54279 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
@@ -48,6 +48,8 @@
/* Alternate Pin Functions: */
+/* TIMERS */
+
#if defined(CONFIG_STM32_TIM1_FULL_REMAP)
# define GPIO_TIM1_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN7)
# define GPIO_TIM1_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTE|GPIO_PIN9)
@@ -183,9 +185,31 @@
# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
#endif
+#define GPIO_TIM5_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM5_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM5_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_TIM5_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_TIM5_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_TIM5_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
#define GPIO_TIM5_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_TIM8_ETR (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM8_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN6)
+#define GPIO_TIM8_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN6)
+#define GPIO_TIM8_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN7)
+#define GPIO_TIM8_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN7)
+#define GPIO_TIM8_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TIM8_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TIM8_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9)
+#define GPIO_TIM8_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9)
+#define GPIO_TIM8_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_TIM8_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_TIM8_CH2N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_TIM8_CH3N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
+
+/* USART */
+
#if defined(CONFIG_STM32_USART1_REMAP)
# define GPIO_USART1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN9)
# define GPIO_USART1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
@@ -228,6 +252,8 @@
# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
#endif
+/* SPI */
+
#if defined(CONFIG_STM32_SPI1_REMAP)
# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
@@ -252,6 +278,8 @@
# define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
#endif
+/* I2C */
+
#if defined(CONFIG_STM32_I2C1_REMAP)
# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
@@ -260,25 +288,25 @@
# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
#endif
-#if defined(CONFIG_STM32_CAN1_FULL_REMAP)
-# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
-# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
-#elif defined(CONFIG_STM32_CAN1_PARTIAL_REMAP)
+#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+
+#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+
+/* CAN */
+
+#if defined(CONFIG_STM32_CAN1_REMAP1)
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
+#elif defined(CONFIG_STM32_CAN1_REMAP2)
+# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTD|GPIO_PIN0)
+# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1)
#else
# define GPIO_CAN1_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN11)
# define GPIO_CAN1_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
#endif
-#if defined(CONFIG_STM32_CAN2_REMAP)
-# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
-# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN6)
-#else
-# define GPIO_CAN2_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
-# define GPIO_CAN2_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
-#endif
-
/* FSMC: CF */
#define GPIO_CF_A0 (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTF|GPIO_PIN0)
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index 583541e59..05afd5a7b 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -79,7 +79,7 @@
#include "stm32_rcc.h"
#include "stm32_i2c.h"
-#if defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C1)
+#if defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2)
/************************************************************************************
* Private Types
@@ -92,6 +92,9 @@ struct stm32_i2c_priv_s {
uint32_t base;
int refs;
sem_t sem;
+
+ uint8_t msgc;
+ FAR struct i2c_msg_s *msgv;
};
@@ -103,8 +106,27 @@ struct stm32_i2c_inst_s {
uint32_t frequency;
int address;
+ uint16_t flags;
+};
+
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+#if CONFIG_STM32_I2C1
+struct stm32_i2c_priv_s stm32_i2c1_priv = {
+ .base = STM32_I2C1_BASE,
+ .refs = 0
};
+#endif
+#if CONFIG_STM32_I2C2
+struct stm32_i2c_priv_s stm32_i2c2_priv = {
+ .base = STM32_I2C2_BASE,
+ .refs = 0
+};
+#endif
/************************************************************************************
@@ -159,7 +181,7 @@ void inline stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev)
}
-static void stm32_i2c_setclock(FAR struct i2c_dev_s *inst)
+static void stm32_i2c_setclock(FAR struct i2c_dev_s *inst, uint32_t frequency)
{
/* Disable Peripheral if rising time is to be changed,
* and restore state on return. */
@@ -171,13 +193,13 @@ static void stm32_i2c_setclock(FAR struct i2c_dev_s *inst)
/* Update timing and control registers */
- if (((struct stm32_i2c_inst_s *)inst)->frequency < 400e3) {
+ if (frequency < 400e3) {
/* Speed: 100 kHz
* Risetime: 1000 ns
* Duty: t_low / t_high = 1
*/
- stm32_i2c_putreg(inst, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK / 200000);
+ stm32_i2c_putreg(inst, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK/200000);
stm32_i2c_putreg(inst, STM32_I2C_TRISE_OFFSET, 1 + STM32_BOARD_HCLK/1000000);
}
else {
@@ -186,7 +208,7 @@ static void stm32_i2c_setclock(FAR struct i2c_dev_s *inst)
* Risetime: 1000 ns ??? \todo check rise time for 400 kHz devices
* Duty: t_low / t_high = 2
*/
- stm32_i2c_putreg(inst, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK / 1200000);
+ stm32_i2c_putreg(inst, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK/1200000);
stm32_i2c_putreg(inst, STM32_I2C_TRISE_OFFSET, 1 + STM32_BOARD_HCLK/1000000);
}
@@ -197,23 +219,103 @@ static void stm32_i2c_setclock(FAR struct i2c_dev_s *inst)
}
+static inline void stm32_i2c_sendstart(FAR struct i2c_dev_s *inst)
+{
+ stm32_i2c_modifyreg(inst, STM32_I2C_CR1_OFFSET, 0, I2C_CR1_START);
+}
+
+
+static inline void stm32_i2c_sendstop(FAR struct i2c_dev_s *inst)
+{
+ stm32_i2c_modifyreg(inst, STM32_I2C_CR1_OFFSET, 0, I2C_CR1_STOP);
+}
+
+
+/************************************************************************************
+ * Interrupt Service Routines
+ ************************************************************************************/
+
+static int stm32_i2c_event_isr(struct stm32_i2c_priv_s * priv)
+{
+ return OK;
+}
+
+
+static int stm32_i2c_error_isr(struct stm32_i2c_priv_s * priv)
+{
+ return OK;
+}
+
+
+/* Decode ***************************************************************************/
+
+#if CONFIG_STM32_I2C1
+static int stm32_i2c1_event_isr(int irq, void *context)
+{
+ return stm32_i2c_event_isr(&stm32_i2c1_priv);
+}
+
+static int stm32_i2c1_error_isr(int irq, void *context)
+{
+ return stm32_i2c_error_isr(&stm32_i2c1_priv);
+}
+#endif
+
+#if CONFIG_STM32_I2C2
+static int stm32_i2c2_event_isr(int irq, void *context)
+{
+ return stm32_i2c_event_isr(&stm32_i2c2_priv);
+}
+
+static int stm32_i2c2_error_isr(int irq, void *context)
+{
+ return stm32_i2c_error_isr(&stm32_i2c1_priv);
+}
+#endif
+
+
+/************************************************************************************
+ * Private Initialization and Deinitialization
+ ************************************************************************************/
+
/** Setup the I2C hardware, ready for operation with defaults */
static int stm32_i2c_init(FAR struct i2c_dev_s *inst)
{
/* Power-up and configure GPIOs */
switch( ((struct stm32_i2c_inst_s *)inst)->priv->base ) {
+
+#if CONFIG_STM32_I2C1
case STM32_I2C1_BASE:
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
- stm32_configgpio(GPIO_I2C1_SCL);
- stm32_configgpio(GPIO_I2C1_SDA);
- break;
+ if (stm32_configgpio(GPIO_I2C1_SCL)==ERROR) return ERROR;
+ if (stm32_configgpio(GPIO_I2C1_SDA)==ERROR) {
+ stm32_unconfiggpio(GPIO_I2C1_SCL);
+ return ERROR;
+ }
+ irq_attach(STM32_IRQ_I2C1EV, stm32_i2c1_event_isr);
+ irq_attach(STM32_IRQ_I2C1ER, stm32_i2c1_error_isr);
+ up_enable_irq(STM32_IRQ_I2C1EV);
+ up_enable_irq(STM32_IRQ_I2C1ER);
+ break;
+#endif
+
+#if CONFIG_STM32_I2C2
case STM32_I2C2_BASE:
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C2EN);
- stm32_configgpio(GPIO_I2C2_SCL);
- stm32_configgpio(GPIO_I2C2_SDA);
+
+ if (stm32_configgpio(GPIO_I2C2_SCL)==ERROR) return ERROR;
+ if (stm32_configgpio(GPIO_I2C2_SDA)==ERROR) {
+ stm32_unconfiggpio(GPIO_I2C2_SCL);
+ return ERROR;
+ }
+ irq_attach(STM32_IRQ_I2C2EV, stm32_i2c2_event_isr);
+ irq_attach(STM32_IRQ_I2C2ER, stm32_i2c2_error_isr);
+ up_enable_irq(STM32_IRQ_I2C2EV);
+ up_enable_irq(STM32_IRQ_I2C2ER);
break;
+#endif
default: return ERROR;
}
@@ -221,18 +323,14 @@ static int stm32_i2c_init(FAR struct i2c_dev_s *inst)
/* Set peripheral frequency, where it must be at least 2 MHz
* for 100 kHz or 4 MHz for 400 kHz. Enable interrupt generation.
*/
-
-#if STM32_BOARD_HCLK < 4000000
-# error STM32_I2C_INIT: Peripheral clock must be at least 4 MHz to support 100/400 kHz operation.
-#endif
-
+
stm32_i2c_putreg(inst, STM32_I2C_CR2_OFFSET,
I2C_CR2_ITERREN | I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN |
(STM32_BOARD_HCLK / 1000000)
);
- stm32_i2c_setclock(inst);
-
+ stm32_i2c_setclock(inst, 100000);
+
/* Enable I2C */
stm32_i2c_putreg(inst, STM32_I2C_CR1_OFFSET, I2C_CR1_PE);
@@ -249,17 +347,34 @@ static int stm32_i2c_deinit(FAR struct i2c_dev_s *inst)
stm32_i2c_putreg(inst, STM32_I2C_CR1_OFFSET, 0);
switch( ((struct stm32_i2c_inst_s *)inst)->priv->base ) {
+
+#if CONFIG_STM32_I2C1
case STM32_I2C1_BASE:
stm32_unconfiggpio(GPIO_I2C1_SCL);
stm32_unconfiggpio(GPIO_I2C1_SDA);
+
+ up_disable_irq(STM32_IRQ_I2C1EV);
+ up_disable_irq(STM32_IRQ_I2C1ER);
+ irq_detach(STM32_IRQ_I2C1EV);
+ irq_detach(STM32_IRQ_I2C1ER);
+
modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C1EN, 0);
break;
-
+#endif
+
+#if CONFIG_STM32_I2C2
case STM32_I2C2_BASE:
stm32_unconfiggpio(GPIO_I2C2_SCL);
stm32_unconfiggpio(GPIO_I2C2_SDA);
+
+ up_disable_irq(STM32_IRQ_I2C1EV);
+ up_disable_irq(STM32_IRQ_I2C1ER);
+ irq_detach(STM32_IRQ_I2C1EV);
+ irq_detach(STM32_IRQ_I2C1ER);
+
modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C2EN, 0);
break;
+#endif
default: return ERROR;
}
@@ -269,24 +384,6 @@ static int stm32_i2c_deinit(FAR struct i2c_dev_s *inst)
/************************************************************************************
- * Interrupt Service Routines
- ************************************************************************************/
-
-static int stm32_i2c1_isr(int irq, void *context)
-{
- // ACK before return!
- return OK;
-}
-
-
-static int stm32_i2c2_isr(int irq, void *context)
-{
- // ACK before return!
- return OK;
-}
-
-
-/************************************************************************************
* Device Driver OPS - Blocking Type
************************************************************************************/
@@ -294,8 +391,12 @@ uint32_t stm32_i2c_setfrequency(FAR struct i2c_dev_s *inst, uint32_t frequency)
{
stm32_i2c_sem_wait(inst);
+#if STM32_BOARD_HCLK < 4000000
+ ((struct stm32_i2c_inst_s *)inst)->frequency = 100000;
+#else
((struct stm32_i2c_inst_s *)inst)->frequency = frequency;
-
+#endif
+
stm32_i2c_sem_post(inst);
return ((struct stm32_i2c_inst_s *)inst)->frequency;
}
@@ -306,42 +407,96 @@ int stm32_i2c_setaddress(FAR struct i2c_dev_s *inst, int addr, int nbits)
stm32_i2c_sem_wait(inst);
((struct stm32_i2c_inst_s *)inst)->address = addr;
+ ((struct stm32_i2c_inst_s *)inst)->flags = (nbits == 10) ? I2C_M_TEN : 0;
stm32_i2c_sem_post(inst);
return OK;
}
+
+int stm32_i2c_process(FAR struct i2c_dev_s *inst, FAR struct i2c_msg_s *msgs, int count)
+{
+ /* The semaphore already ensures that I2C is ours, since we do not yet support
+ * non-blocking operation.
+ */
+
+ ((struct stm32_i2c_inst_s *)inst)->priv->msgv = msgs;
+ ((struct stm32_i2c_inst_s *)inst)->priv->msgc = count;
+
+ stm32_i2c_setclock(inst, ((struct stm32_i2c_inst_s *)inst)->frequency);
+ stm32_i2c_sendstart(inst);
+
+ /* Trigger start condition, then the process moves into the ISR,
+ * until semaphore is posted.
+ */
+
+ stm32_i2c_sem_wait(inst); /* wait again for the semaphore and */
+ stm32_i2c_sem_post(inst); /* release it immediately. */
+ return OK;
+}
+
int stm32_i2c_write(FAR struct i2c_dev_s *inst, const uint8_t *buffer, int buflen)
{
- stm32_i2c_sem_wait(inst);
+ stm32_i2c_sem_wait(inst); /* ensure that address or flags don't change meanwhile */
- stm32_i2c_setclock(inst);
+ struct i2c_msg_s msgv = {
+ .addr = ((struct stm32_i2c_inst_s *)inst)->address,
+ .flags = ((struct stm32_i2c_inst_s *)inst)->flags,
+ .buffer = (uint8_t *)buffer,
+ .length = buflen
+ };
- stm32_i2c_sem_post(inst);
- return OK;
+ return stm32_i2c_process(inst, &msgv, 1);
}
int stm32_i2c_read(FAR struct i2c_dev_s *inst, uint8_t *buffer, int buflen)
{
- stm32_i2c_sem_wait(inst);
+ stm32_i2c_sem_wait(inst); /* ensure that address or flags don't change meanwhile */
- stm32_i2c_setclock(inst);
+ struct i2c_msg_s msgv = {
+ .addr = ((struct stm32_i2c_inst_s *)inst)->address,
+ .flags = ((struct stm32_i2c_inst_s *)inst)->flags | I2C_M_READ,
+ .buffer = buffer,
+ .length = buflen
+ };
- stm32_i2c_sem_post(inst);
- return OK;
+ return stm32_i2c_process(inst, &msgv, 1);
}
+#ifdef CONFIG_I2C_WRITEREAD
+int stm32_i2c_writeread(FAR struct i2c_dev_s *inst, const uint8_t *wbuffer, int wbuflen,
+ uint8_t *rbuffer, int rbuflen)
+{
+ stm32_i2c_sem_wait(inst); /* ensure that address or flags don't change meanwhile */
+
+ struct i2c_msg_s msgv[2] = {
+ {
+ .addr = ((struct stm32_i2c_inst_s *)inst)->address,
+ .flags = ((struct stm32_i2c_inst_s *)inst)->flags,
+ .buffer = (uint8_t *)wbuffer, /* this is really ugly, sorry const ... */
+ .length = wbuflen
+ },
+ {
+ .addr = ((struct stm32_i2c_inst_s *)inst)->address,
+ .flags = ((struct stm32_i2c_inst_s *)inst)->flags | I2C_M_READ,
+ .buffer = rbuffer,
+ .length = rbuflen
+ }
+ };
+
+ return stm32_i2c_process(inst, msgv, 2);
+}
+#endif
+
+
#ifdef CONFIG_I2C_TRANSFER
int stm32_i2c_transfer(FAR struct i2c_dev_s *inst, FAR struct i2c_msg_s *msgs, int count)
{
- stm32_i2c_sem_wait(inst);
-
-
- stm32_i2c_sem_post(inst);
- return OK;
+ stm32_i2c_sem_wait(inst); /* ensure that address or flags don't change meanwhile */
+ return stm32_i2c_process(inst, msgs, count);
}
#endif
@@ -351,29 +506,23 @@ int stm32_i2c_transfer(FAR struct i2c_dev_s *inst, FAR struct i2c_msg_s *msgs, i
************************************************************************************/
struct i2c_ops_s stm32_i2c_ops = {
- .setfrequency = stm32_i2c_setfrequency,
- .setaddress = stm32_i2c_setaddress,
- .write = stm32_i2c_write,
- .read = stm32_i2c_read
+ .setfrequency = stm32_i2c_setfrequency,
+ .setaddress = stm32_i2c_setaddress,
+ .write = stm32_i2c_write,
+ .read = stm32_i2c_read,
+#ifdef CONFIG_I2C_WRITEREAD
+ .writeread = stm32_i2c_writeread
+#endif
#ifdef CONFIG_I2C_TRANSFER
- , .transfer = stm32_i2c_transfer
+ , .transfer = stm32_i2c_transfer
+#endif
+#ifdef CONFIG_I2C_SLAVE
+ , .setownaddress = stm32_i2c_setownaddress,
+ .registercallback = stm32_i2c_registercallback
#endif
};
-struct stm32_i2c_priv_s stm32_i2c1_priv = {
- .base = STM32_I2C1_BASE,
- .refs = 0
-};
-
-
-struct stm32_i2c_priv_s stm32_i2c2_priv = {
- .base = STM32_I2C2_BASE,
- .refs = 0
-};
-
-
-
/************************************************************************************
* Public Function - Initialization
************************************************************************************/
@@ -383,12 +532,25 @@ FAR struct i2c_dev_s * up_i2cinitialize(int port)
struct stm32_i2c_priv_s * priv = NULL; /* private data of device with multiple instances */
struct stm32_i2c_inst_s * inst = NULL; /* device, single instance */
int irqs;
+
+#if STM32_BOARD_HCLK < 4000000
+# warning STM32_I2C_INIT: Peripheral clock must be at least 4 MHz to support 400 kHz operation.
+#endif
+
+#if STM32_BOARD_HCLK < 2000000
+# warning STM32_I2C_INIT: Peripheral clock must be at least 2 MHz to support 100 kHz operation.
+ return NULL;
+#endif
/* Get structure and enable power */
switch(port) {
+#if CONFIG_STM32_I2C1
case 1: priv = (struct stm32_i2c_priv_s *)&stm32_i2c1_priv; break;
+#endif
+#if CONFIG_STM32_I2C2
case 2: priv = (struct stm32_i2c_priv_s *)&stm32_i2c2_priv; break;
+#endif
default: return NULL;
}
@@ -402,6 +564,7 @@ FAR struct i2c_dev_s * up_i2cinitialize(int port)
inst->priv = priv;
inst->frequency = 100e3;
inst->address = 0;
+ inst->flags = 0;
/* Init private data for the first time, increment refs count,
* power-up hardware and configure GPIOs.
@@ -453,5 +616,4 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * inst)
return OK;
}
-#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C1 */
-
+#endif /* defined(CONFIG_STM32_I2C1) && defined(CONFIG_STM32_I2C2) */
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.h b/nuttx/arch/arm/src/stm32/stm32_i2c.h
index c9116d942..23a06bc05 100755
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.h
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_i2c.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.c b/nuttx/arch/arm/src/stm32/stm32_rcc.c
index 1b998d858..52e1ac0ae 100755
--- a/nuttx/arch/arm/src/stm32/stm32_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rcc.c
@@ -164,39 +164,45 @@ static inline void rcc_enableapb1(void)
regval = getreg32(STM32_RCC_APB1ENR);
#if CONFIG_STM32_TIM2
/* Timer 2 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM2EN;
#endif
+#endif
#if CONFIG_STM32_TIM3
/* Timer 3 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM3EN;
#endif
+#endif
#if CONFIG_STM32_TIM4
/* Timer 4 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
+#endif
#if CONFIG_STM32_TIM5
/* Timer 5 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM5EN;
#endif
+#endif
#if CONFIG_STM32_TIM6
/* Timer 6 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM6EN;
#endif
+#endif
#if CONFIG_STM32_TIM7
/* Timer 7 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM7EN;
#endif
+#endif
#if CONFIG_STM32_WWDG
/* Window Watchdog clock enable */
@@ -242,15 +248,17 @@ static inline void rcc_enableapb1(void)
#if CONFIG_STM32_I2C1
/* I2C 1 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C1EN;
#endif
+#endif
#if CONFIG_STM32_I2C2
/* I2C 2 clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C2EN;
#endif
+#endif
#if CONFIG_STM32_USB
/* USB clock enable */
@@ -333,9 +341,10 @@ static inline void rcc_enableapb2(void)
#if CONFIG_STM32_TIM1
/* TIM1 Timer clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM1EN;
#endif
+#endif
#if CONFIG_STM32_SPI1
/* SPI 1 clock enable */
@@ -345,9 +354,10 @@ static inline void rcc_enableapb2(void)
#if CONFIG_STM32_TIM8
/* TIM8 Timer clock enable */
-
+#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM8EN;
#endif
+#endif
#if CONFIG_STM32_USART1
/* USART1 clock enable */
diff --git a/nuttx/arch/arm/src/stm32/stm32_tim.c b/nuttx/arch/arm/src/stm32/stm32_tim.c
index 433269bac..d996a7af1 100644
--- a/nuttx/arch/arm/src/stm32/stm32_tim.c
+++ b/nuttx/arch/arm/src/stm32/stm32_tim.c
@@ -59,11 +59,9 @@
#include "stm32_gpio.h"
#include "stm32_tim.h"
-
-#define getreg16(a) (*(volatile uint16_t *)(a))
-#define putreg16(v,a) (*(volatile uint16_t *)(a) = (v))
-
-#if defined(CONFIG_STM32_TIM5) && defined(CONFIG_STM32_TIM8)
+#if defined(CONFIG_STM32_TIM1) || defined(CONFIG_STM32_TIM2) || defined(CONFIG_STM32_TIM3) || \
+ defined(CONFIG_STM32_TIM4) || defined(CONFIG_STM32_TIM5) || defined(CONFIG_STM32_TIM6) || \
+ defined(CONFIG_STM32_TIM7) || defined(CONFIG_STM32_TIM8)
/************************************************************************************
* Private Types
@@ -74,9 +72,7 @@
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 */
+ uint32_t base; /** TIMn base address */
};
@@ -205,13 +201,37 @@ static int stm32_tim_setisr(FAR struct stm32_tim_dev_s *dev, int (*handler)(int
ASSERT(source==0);
switch( ((struct stm32_tim_priv_s *)dev)->base ) {
+#if CONFIG_STM32_TIM2
+ case STM32_TIM2_BASE: vectorno = STM32_IRQ_TIM2; break;
+#endif
+#if CONFIG_STM32_TIM3
case STM32_TIM3_BASE: vectorno = STM32_IRQ_TIM3; break;
-
+#endif
+#if CONFIG_STM32_TIM4
+ case STM32_TIM4_BASE: vectorno = STM32_IRQ_TIM4; break;
+#endif
+#if CONFIG_STM32_TIM5
+ case STM32_TIM5_BASE: vectorno = STM32_IRQ_TIM5; break;
+#endif
+#if STM32_NBTIM > 0
+#if CONFIG_STM32_TIM6
+ case STM32_TIM6_BASE: vectorno = STM32_IRQ_TIM6; break;
+#endif
+#endif
+#if STM32_NBTIM > 1
+#if CONFIG_STM32_TIM7
+ case STM32_TIM7_BASE: vectorno = STM32_IRQ_TIM7; break;
+#endif
+#endif
#if STM32_NATIM > 0
/** \todo add support for multiple sources and callbacks */
+#if CONFIG_STM32_TIM1
case STM32_TIM1_BASE: vectorno = STM32_IRQ_TIM1UP; break;
+#endif
+#if CONFIG_STM32_TIM8
case STM32_TIM8_BASE: vectorno = STM32_IRQ_TIM8UP; break;
#endif
+#endif
default: return ERROR;
}
@@ -381,7 +401,7 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
/* set GPIO */
switch( ((struct stm32_tim_priv_s *)dev)->base ) {
-
+#if CONFIG_STM32_TIM2
case STM32_TIM2_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM2_CH1OUT, mode); break;
@@ -390,7 +410,8 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
case 3: stm32_tim_gpioconfig(GPIO_TIM2_CH4OUT, mode); break;
}
break;
-
+#endif
+#if CONFIG_STM32_TIM3
case STM32_TIM3_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM3_CH1OUT, mode); break;
@@ -399,7 +420,8 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
case 3: stm32_tim_gpioconfig(GPIO_TIM3_CH4OUT, mode); break;
}
break;
-
+#endif
+#if CONFIG_STM32_TIM4
case STM32_TIM4_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM4_CH1OUT, mode); break;
@@ -408,7 +430,8 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
case 3: stm32_tim_gpioconfig(GPIO_TIM4_CH4OUT, mode); break;
}
break;
-
+#endif
+#if CONFIG_STM32_TIM5
case STM32_TIM5_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM5_CH1OUT, mode); break;
@@ -417,8 +440,10 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
case 3: stm32_tim_gpioconfig(GPIO_TIM5_CH4OUT, mode); break;
}
break;
+#endif
#if STM32_NATIM > 0
+#if CONFIG_STM32_TIM1
case STM32_TIM1_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM1_CH1OUT, mode); break;
@@ -427,7 +452,8 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
case 3: stm32_tim_gpioconfig(GPIO_TIM1_CH4OUT, mode); break;
}
break;
-
+#endif
+#if CONFIG_STM32_TIM8
case STM32_TIM8_BASE:
switch(channel) {
case 0: stm32_tim_gpioconfig(GPIO_TIM8_CH1OUT, mode); break;
@@ -437,6 +463,7 @@ static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel
}
break;
#endif
+#endif
default: return ERROR;
}
@@ -497,26 +524,75 @@ struct stm32_tim_ops_s stm32_tim_ops = {
.ackint = &stm32_tim_ackint
};
+#if CONFIG_STM32_TIM2
+struct stm32_tim_priv_s stm32_tim2_priv = {
+ .ops = &stm32_tim_ops,
+ .mode = STM32_TIM_MODE_UNUSED,
+ .base = STM32_TIM2_BASE,
+};
+#endif
+#if CONFIG_STM32_TIM3
struct stm32_tim_priv_s stm32_tim3_priv = {
.ops = &stm32_tim_ops,
.mode = STM32_TIM_MODE_UNUSED,
.base = STM32_TIM3_BASE,
};
+#endif
+
+#if CONFIG_STM32_TIM4
+struct stm32_tim_priv_s stm32_tim4_priv = {
+ .ops = &stm32_tim_ops,
+ .mode = STM32_TIM_MODE_UNUSED,
+ .base = STM32_TIM4_BASE,
+};
+#endif
+
+#if CONFIG_STM32_TIM5
+struct stm32_tim_priv_s stm32_tim5_priv = {
+ .ops = &stm32_tim_ops,
+ .mode = STM32_TIM_MODE_UNUSED,
+ .base = STM32_TIM5_BASE,
+};
+#endif
+
+#if STM32_NBTIM > 0
+#if CONFIG_STM32_TIM6
+struct stm32_tim_priv_s stm32_tim6_priv = {
+ .ops = &stm32_tim_ops,
+ .mode = STM32_TIM_MODE_UNUSED,
+ .base = STM32_TIM6_BASE,
+};
+#endif
+#endif
+
+#if STM32_NBTIM > 1
+#if CONFIG_STM32_TIM7
+struct stm32_tim_priv_s stm32_tim7_priv = {
+ .ops = &stm32_tim_ops,
+ .mode = STM32_TIM_MODE_UNUSED,
+ .base = STM32_TIM7_BASE,
+};
+#endif
+#endif
#if STM32_NATIM > 0
+#if CONFIG_STM32_TIM7
struct stm32_tim_priv_s stm32_tim1_priv = {
.ops = &stm32_tim_ops,
.mode = STM32_TIM_MODE_UNUSED,
.base = STM32_TIM1_BASE,
};
+#endif
+#if CONFIG_STM32_TIM8
struct stm32_tim_priv_s stm32_tim8_priv = {
.ops = &stm32_tim_ops,
.mode = STM32_TIM_MODE_UNUSED,
.base = STM32_TIM8_BASE,
};
+#endif
#endif
@@ -532,22 +608,62 @@ FAR struct stm32_tim_dev_s * stm32_tim_init(int timer)
/* Get structure and enable power */
switch(timer) {
+#if CONFIG_STM32_TIM2
+ case 2:
+ dev = (struct stm32_tim_dev_s *)&stm32_tim2_priv;
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM2EN);
+ break;
+#endif
+#if CONFIG_STM32_TIM3
case 3:
dev = (struct stm32_tim_dev_s *)&stm32_tim3_priv;
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN);
break;
-
+#endif
+#if CONFIG_STM32_TIM4
+ case 4:
+ dev = (struct stm32_tim_dev_s *)&stm32_tim4_priv;
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM4EN);
+ break;
+#endif
+#if CONFIG_STM32_TIM5
+ case 5:
+ dev = (struct stm32_tim_dev_s *)&stm32_tim5_priv;
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM5EN);
+ break;
+#endif
+
+#if STM32_NBTIM > 0
+#if CONFIG_STM32_TIM6
+ case 6:
+ dev = (struct stm32_tim_dev_s *)&stm32_tim6_priv;
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM6EN);
+ break;
+#endif
+#endif
+#if STM32_NBTIM > 1
+#if CONFIG_STM32_TIM7
+ case 7:
+ dev = (struct stm32_tim_dev_s *)&stm32_tim7_priv;
+ modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM7EN);
+ break;
+#endif
+#endif
+
#if STM32_NATIM > 0
+#if CONFIG_STM32_TIM1
case 1:
dev = (struct stm32_tim_dev_s *)&stm32_tim1_priv;
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
break;
-
+#endif
+#if CONFIG_STM32_TIM8
case 8:
dev = (struct stm32_tim_dev_s *)&stm32_tim8_priv;
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM8EN);
break;
#endif
+#endif
default: return NULL;
}
@@ -562,6 +678,7 @@ FAR struct stm32_tim_dev_s * stm32_tim_init(int timer)
}
+/** \todo Detach interrupts, and close down all TIM Channels */
int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev)
{
ASSERT(dev);
@@ -569,12 +686,37 @@ int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev)
/* Disable power */
switch( ((struct stm32_tim_priv_s *)dev)->base ) {
+#if CONFIG_STM32_TIM2
+ case STM32_TIM2_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM2EN, 0); break;
+#endif
+#if CONFIG_STM32_TIM3
case STM32_TIM3_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM3EN, 0); break;
+#endif
+#if CONFIG_STM32_TIM4
+ case STM32_TIM4_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM4EN, 0); break;
+#endif
+#if CONFIG_STM32_TIM5
+ case STM32_TIM5_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM5EN, 0); break;
+#endif
+#if STM32_NBTIM > 0
+#if CONFIG_STM32_TIM6
+ case STM32_TIM6_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM6EN, 0); break;
+#endif
+#endif
+#if STM32_NBTIM > 1
+#if CONFIG_STM32_TIM7
+ case STM32_TIM7_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM7EN, 0); break;
+#endif
+#endif
#if STM32_NATIM > 0
+#if CONFIG_STM32_TIM1
case STM32_TIM1_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM1EN, 0); break;
+#endif
+#if CONFIG_STM32_TIM8
case STM32_TIM8_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM8EN, 0); break;
#endif
+#endif
default: return ERROR;
}
@@ -585,5 +727,4 @@ int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev)
return OK;
}
-#endif /* CONFIG_STM32_TIM5 && CONFIG_STM32_TIM8 */
-
+#endif /* defined(CONFIG_STM32_TIM1 || ... || TIM8) */