summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_adc.h58
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_can.h7
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_dac.h20
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_dbgmcu.h20
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_exti.h64
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_pwr.h9
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_tim.h507
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_wdg.h117
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f30xxx_adc.h543
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.h7
-rw-r--r--nuttx/libc/spawn/lib_psfa_dump.c4
12 files changed, 1165 insertions, 203 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_adc.h b/nuttx/arch/arm/src/stm32/chip/stm32_adc.h
index 218b11aa5..c5d24bb34 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_adc.h
@@ -203,12 +203,12 @@
#define ADC_CR1_AWDEN (1 << 23) /* Bit 23: Analog watchdog enable on regular channels */
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define ACD_CR1_RES_SHIFT (24) /* Bits 24-25: Resolution */
-# define ACD_CR1_RES_MASK (3 << ACD_CR1_RES_SHIFT)
-# define ACD_CR1_RES_12BIT (0 << ACD_CR1_RES_SHIFT) /* 15 ADCCLK clyes */
-# define ACD_CR1_RES_10BIT (1 << ACD_CR1_RES_SHIFT) /* 13 ADCCLK clyes */
-# define ACD_CR1_RES_8BIT (2 << ACD_CR1_RES_SHIFT) /* 11 ADCCLK clyes */
-# define ACD_CR1_RES_6BIT (3 << ACD_CR1_RES_SHIFT) /* 9 ADCCLK clyes */
+# define ADC_CR1_RES_SHIFT (24) /* Bits 24-25: Resolution */
+# define ADC_CR1_RES_MASK (3 << ADC_CR1_RES_SHIFT)
+# define ADC_CR1_RES_12BIT (0 << ADC_CR1_RES_SHIFT) /* 15 ADCCLK clyes */
+# define ADC_CR1_RES_10BIT (1 << ADC_CR1_RES_SHIFT) /* 13 ADCCLK clyes */
+# define ADC_CR1_RES_8BIT (2 << ADC_CR1_RES_SHIFT) /* 11 ADCCLK clyes */
+# define ADC_CR1_RES_6BIT (3 << ADC_CR1_RES_SHIFT) /* 9 ADCCLK clyes */
# define ADC_CR1_OVRIE (1 << 26) /* Bit 26: Overrun interrupt enable */
#endif
@@ -252,12 +252,12 @@
# define ADC_CR2_JEXTSEL_T8CC4 (14 << ADC_CR2_JEXTSEL_SHIFT) /* 1110: Timer 8 CC4 event */
# define ADC_CR2_JEXTSEL_EXTI (15 << ADC_CR2_JEXTSEL_SHIFT) /* 1111: EXTI line15 */
-# define ACD_CR2_JEXTEN_SHIFT (20) /* Bits 20-21: External trigger enable for injected channels */
-# define ACD_CR2_JEXTEN_MASK (3 << ACD_CR2_JEXTEN_SHIFT)
-# define ACD_CR2_JEXTEN_NONE (0 << ACD_CR2_JEXTEN_SHIFT) /* 00: Trigger detection disabled */
-# define ACD_CR2_JEXTEN_RISING (1 << ACD_CR2_JEXTEN_SHIFT) /* 01: Trigger detection on the rising edge */
-# define ACD_CR2_JEXTEN_FALLING (2 << ACD_CR2_JEXTEN_SHIFT) /* 10: Trigger detection on the falling edge */
-# define ACD_CR2_JEXTEN_BOTH (3 << ACD_CR2_JEXTEN_SHIFT) /* 11: Trigger detection on both the rising and falling edges */
+# define ADC_CR2_JEXTEN_SHIFT (20) /* Bits 20-21: External trigger enable for injected channels */
+# define ADC_CR2_JEXTEN_MASK (3 << ADC_CR2_JEXTEN_SHIFT)
+# define ADC_CR2_JEXTEN_NONE (0 << ADC_CR2_JEXTEN_SHIFT) /* 00: Trigger detection disabled */
+# define ADC_CR2_JEXTEN_RISING (1 << ADC_CR2_JEXTEN_SHIFT) /* 01: Trigger detection on the rising edge */
+# define ADC_CR2_JEXTEN_FALLING (2 << ADC_CR2_JEXTEN_SHIFT) /* 10: Trigger detection on the falling edge */
+# define ADC_CR2_JEXTEN_BOTH (3 << ADC_CR2_JEXTEN_SHIFT) /* 11: Trigger detection on both the rising and falling edges */
# define ADC_CR2_JSWSTART (1 << 22) /* Bit 22: Start Conversion of injected channels */
/* Bit 23: Reserved, must be kept at reset value. */
@@ -280,12 +280,12 @@
# define ADC_CR2_EXTSEL_T8TRGO (14 << ADC_CR2_EXTSEL_SHIFT) /* 1110: Timer 8 TRGO event */
# define ADC_CR2_EXTSEL_EXTI (15 << ADC_CR2_EXTSEL_SHIFT) /* 1111: EXTI line11 */
-# define ACD_CR2_EXTEN_SHIFT (28) /* Bits 28-29: External trigger enable for regular channels */
-# define ACD_CR2_EXTEN_MASK (3 << ACD_CR2_EXTEN_SHIFT)
-# define ACD_CR2_EXTEN_NONE (0 << ACD_CR2_EXTEN_SHIFT) /* 00: Trigger detection disabled */
-# define ACD_CR2_EXTEN_RISING (1 << ACD_CR2_EXTEN_SHIFT) /* 01: Trigger detection on the rising edge */
-# define ACD_CR2_EXTEN_FALLING (2 << ACD_CR2_EXTEN_SHIFT) /* 10: Trigger detection on the falling edge */
-# define ACD_CR2_EXTEN_BOTH (3 << ACD_CR2_EXTEN_SHIFT) /* 11: Trigger detection on both the rising and falling edges */
+# define ADC_CR2_EXTEN_SHIFT (28) /* Bits 28-29: External trigger enable for regular channels */
+# define ADC_CR2_EXTEN_MASK (3 << ADC_CR2_EXTEN_SHIFT)
+# define ADC_CR2_EXTEN_NONE (0 << ADC_CR2_EXTEN_SHIFT) /* 00: Trigger detection disabled */
+# define ADC_CR2_EXTEN_RISING (1 << ADC_CR2_EXTEN_SHIFT) /* 01: Trigger detection on the rising edge */
+# define ADC_CR2_EXTEN_FALLING (2 << ADC_CR2_EXTEN_SHIFT) /* 10: Trigger detection on the falling edge */
+# define ADC_CR2_EXTEN_BOTH (3 << ADC_CR2_EXTEN_SHIFT) /* 11: Trigger detection on both the rising and falling edges */
# define ADC_CR2_SWSTART (1 << 30) /* Bit 30: Start Conversion of regular channels */
@@ -369,25 +369,25 @@
/* ADC sample time register 2 */
#define ADC_SMPR2_SMP0_SHIFT (0) /* Bits 2-0: Channel 0 Sample time selection */
-#define ADC_SMPR2_SMP0_MASK (7 << ADC_SMPR1_SMP0_SHIFT)
+#define ADC_SMPR2_SMP0_MASK (7 << ADC_SMPR2_SMP0_SHIFT)
#define ADC_SMPR2_SMP1_SHIFT (3) /* Bits 5-3: Channel 1 Sample time selection */
-#define ADC_SMPR2_SMP1_MASK (7 << ADC_SMPR1_SMP1_SHIFT)
+#define ADC_SMPR2_SMP1_MASK (7 << ADC_SMPR2_SMP1_SHIFT)
#define ADC_SMPR2_SMP2_SHIFT (6) /* Bits 8-6: Channel 2 Sample time selection */
-#define ADC_SMPR2_SMP2_MASK (7 << ADC_SMPR1_SMP2_SHIFT)
+#define ADC_SMPR2_SMP2_MASK (7 << ADC_SMPR2_SMP2_SHIFT)
#define ADC_SMPR2_SMP3_SHIFT (9) /* Bits 11-9: Channel 3 Sample time selection */
-#define ADC_SMPR2_SMP3_MASK (7 << ADC_SMPR1_SMP3_SHIFT)
+#define ADC_SMPR2_SMP3_MASK (7 << ADC_SMPR2_SMP3_SHIFT)
#define ADC_SMPR2_SMP4_SHIFT (12) /* Bits 14-12: Channel 4 Sample time selection */
-#define ADC_SMPR2_SMP4_MASK (7 << ADC_SMPR1_SMP4_SHIFT)
+#define ADC_SMPR2_SMP4_MASK (7 << ADC_SMPR2_SMP4_SHIFT)
#define ADC_SMPR2_SMP5_SHIFT (15) /* Bits 17-15: Channel 5 Sample time selection */
-#define ADC_SMPR2_SMP5_MASK (7 << ADC_SMPR1_SMP5_SHIFT)
+#define ADC_SMPR2_SMP5_MASK (7 << ADC_SMPR2_SMP5_SHIFT)
#define ADC_SMPR2_SMP6_SHIFT (18) /* Bits 20-18: Channel 6 Sample time selection */
-#define ADC_SMPR2_SMP6_MASK (7 << ADC_SMPR1_SMP6_SHIFT)
+#define ADC_SMPR2_SMP6_MASK (7 << ADC_SMPR2_SMP6_SHIFT)
#define ADC_SMPR2_SMP7_SHIFT (21) /* Bits 23-21: Channel 7 Sample time selection */
-#define ADC_SMPR2_SMP7_MASK (7 << ADC_SMPR1_SMP7_SHIFT)
+#define ADC_SMPR2_SMP7_MASK (7 << ADC_SMPR2_SMP7_SHIFT)
#define ADC_SMPR2_SMP8_SHIFT (24) /* Bits 26-24: Channel 8 Sample time selection */
-#define ADC_SMPR2_SMP8_MASK (7 << ADC_SMPR1_SMP8_SHIFT)
+#define ADC_SMPR2_SMP8_MASK (7 << ADC_SMPR2_SMP8_SHIFT)
#define ADC_SMPR2_SMP9_SHIFT (27) /* Bits 29-27: Channel 9 Sample time selection */
-#define ADC_SMPR2_SMP9_MASK (7 << ADC_SMPR1_SMP9_SHIFT)
+#define ADC_SMPR2_SMP9_MASK (7 << ADC_SMPR2_SMP9_SHIFT)
/* ADC injected channel data offset register 1-4 */
@@ -455,7 +455,7 @@
#define ADC_JSQR_JSQ1_SHIFT (0) /* Bits 4-0: 1st conversion in injected sequence */
#define ADC_JSQR_JSQ1_MASK (0x1f << ADC_JSQR_JSQ1_SHIFT)
#define ADC_JSQR_JSQ2_SHIFT (5) /* Bits 9-5: 2nd conversion in injected sequence */
-#define ADC_JSQR_JSQ2_MASK (0x1f << ADC_JSQR_JSQ2_MASK)
+#define ADC_JSQR_JSQ2_MASK (0x1f << ADC_JSQR_JSQ2_SHIFT)
#define ADC_JSQR_JSQ3_SHIFT (10) /* Bits 14-10: 3rd conversion in injected sequence */
#define ADC_JSQR_JSQ3_MASK (0x1f << ADC_JSQR_JSQ3_SHIFT)
#define ADC_JSQR_JSQ4_SHIFT (15) /* Bits 19-15: 4th conversion in injected sequence */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_can.h b/nuttx/arch/arm/src/stm32/chip/stm32_can.h
index 253bf68fc..ba3042309 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_can.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_can.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_can.h
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -61,7 +61,8 @@
/* Number of filters depends on silicon */
-#if defined(CONFIG_STM32_CONNECTIVITYLINE) || defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+#if defined(CONFIG_STM32_CONNECTIVITYLINE) || defined(CONFIG_STM32_STM32F20XX) || \
+ defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F40XX)
# define CAN_NFILTERS 28
#else
# define CAN_NFILTERS 14
@@ -271,7 +272,7 @@
#define CAN_MSR_SLAKI (1 << 4) /* Bit 4: Sleep acknowledge interrupt */
#define CAN_MSR_TXM (1 << 8) /* Bit 8: Transmit Mode */
#define CAN_MSR_RXM (1 << 9) /* Bit 9: Receive Mode */
-#define CAN_MSR_SAMP (1 << 20) /* Bit 10: Last Sample Point */
+#define CAN_MSR_SAMP (1 << 10) /* Bit 10: Last Sample Point */
#define CAN_MSR_RX (1 << 11) /* Bit 11: CAN Rx Signal */
/* CAN transmit status register */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_dac.h b/nuttx/arch/arm/src/stm32/chip/stm32_dac.h
index 1498c8c93..7b6069b8b 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_dac.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_dac.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_dac.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -86,9 +86,10 @@
/* DAC control register */
/* These definitions may be used for 16-bit values of either channel */
-#define DAC_CR_EN (1 << 0) /* Bit 0: DAC channel1 enable */
-#define DAC_CR_BOFF (1 << 1) /* Bit 1: DAC channel1 output buffer disable */
-#define DAC_CR_TSEL_SHIFT (3) /* Bits 3-5: DAC channel1 trigger selection */
+#define DAC_CR_EN (1 << 0) /* Bit 0: DAC channel enable */
+#define DAC_CR_BOFF (1 << 1) /* Bit 1: DAC channel output buffer disable */
+#define DAC_CR_TEN (1 << 2) /* Bit 2: DAC channel trigger enable */
+#define DAC_CR_TSEL_SHIFT (3) /* Bits 3-5: DAC channel trigger selection */
#define DAC_CR_TSEL_MASK (7 << DAC_CR_TSEL_SHIFT)
# define DAC_CR_TSEL_TIM6 (0 << DAC_CR_TSEL_SHIFT) /* Timer 6 TRGO event */
#ifdef CONFIG_STM32_CONNECTIVITYLINE
@@ -102,14 +103,14 @@
# define DAC_CR_TSEL_TIM4 (5 << DAC_CR_TSEL_SHIFT) /* Timer 4 TRGO event */
# define DAC_CR_TSEL_EXT9 (6 << DAC_CR_TSEL_SHIFT) /* External line9 */
# define DAC_CR_TSEL_SW (7 << DAC_CR_TSEL_SHIFT) /* Software trigger */
-#define DAC_CR_WAVE_SHIFT (6) /* Bits 6-7: DAC channel1 noise/triangle wave generation */enable
+#define DAC_CR_WAVE_SHIFT (6) /* Bits 6-7: DAC channel noise/triangle wave generation */enable
#define DAC_CR_WAVE_MASK (3 << DAC_CR_WAVE_SHIFT)
# define DAC_CR_WAVE_DISABLED (0 << DAC_CR_WAVE_SHIFT) /* Wave generation disabled */
# define DAC_CR_WAVE_NOISE (1 << DAC_CR_WAVE_SHIFT) /* Noise wave generation enabled */
# define DAC_CR_WAVE_TRIANGLE (2 << DAC_CR_WAVE_SHIFT) /* Triangle wave generation enabled */
-#define DAC_CR_MAMP_SHIFT (8) /* Bits 8-11: DAC channel1 mask/amplitude selector */
+#define DAC_CR_MAMP_SHIFT (8) /* Bits 8-11: DAC channel mask/amplitude selector */
#define DAC_CR_MAMP_MASK (15 << DAC_CR_MAMP_SHIFT)
-# define DAC_CR_MAMP_AMP1 (0 << DAC_CR_MAMP1_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */
+# define DAC_CR_MAMP_AMP1 (0 << DAC_CR_MAMP1_SHIFT) /* Unmask bit0 of LFSR/triangle amplitude=1 */
# define DAC_CR_MAMP_AMP3 (1 << DAC_CR_MAMP_SHIFT) /* Unmask bits[1:0] of LFSR/triangle amplitude=3 */
# define DAC_CR_MAMP_AMP7 (2 << DAC_CR_MAMP_SHIFT) /* Unmask bits[2:0] of LFSR/triangle amplitude=7 */
# define DAC_CR_MAMP_AMP15 (3 << DAC_CR_MAMP_SHIFT) /* Unmask bits[3:0] of LFSR/triangle amplitude=15 */
@@ -121,13 +122,14 @@
# define DAC_CR_MAMP_AMP1023 (9 << DAC_CR_MAMP_SHIFT) /* Unmask bits[9:0] of LFSR/triangle amplitude=1023 */
# define DAC_CR_MAMP_AMP2047 (10 << DAC_CR_MAMP_SHIFT) /* Unmask bits[10:0] of LFSR/triangle amplitude=2047 */
# define DAC_CR_MAMP_AMP4095 (11 << DAC_CR_MAMP_SHIFT) /* Unmask bits[11:0] of LFSR/triangle amplitude=4095 */
-#define DAC_CR_DMAEN (1 << 12) /* Bit 12: DAC channel1 DMA enable */
-#define DAC_CR_DMAUDRIE (1 << 13) /* Bit 13: DAC channel1 DMA Underrun Interrupt enable */
+#define DAC_CR_DMAEN (1 << 12) /* Bit 12: DAC channel DMA enable */
+#define DAC_CR_DMAUDRIE (1 << 13) /* Bit 13: DAC channel DMA Underrun Interrupt enable */
/* These definitions may be used with the full, 32-bit register */
#define DAC_CR_EN1 (1 << 0) /* Bit 0: DAC channel1 enable */
#define DAC_CR_BOFF1 (1 << 1) /* Bit 1: DAC channel1 output buffer disable */
+#define DAC_CR_TEN1 (1 << 2) /* Bit 2: DAC channel1 trigger enable */
#define DAC_CR_TSEL1_SHIFT (3) /* Bits 3-5: DAC channel1 trigger selection */
#define DAC_CR_TSEL1_MASK (7 << DAC_CR_TSEL1_SHIFT)
# define DAC_CR_TSEL1_TIM6 (0 << DAC_CR_TSEL1_SHIFT) /* Timer 6 TRGO event */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_dbgmcu.h b/nuttx/arch/arm/src/stm32/chip/stm32_dbgmcu.h
index ff1661313..2f3c55816 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_dbgmcu.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_dbgmcu.h
@@ -1,7 +1,7 @@
/****************************************************************************************************
* arch/arm/src/stm32/chip/stm32_dbgmcu.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -117,6 +117,18 @@
# define DBGMCU_APB1_I2C3STOP (1 << 23) /* Bit 23: SMBUS timeout mode stopped when Core is halted */
# define DBGMCU_APB1_CAN1STOP (1 << 25) /* Bit 25: CAN1 stopped when core is halted */
# define DBGMCU_APB1_CAN2STOP (1 << 26) /* Bit 26: CAN2 stopped when core is halted */
+#elif defined(CONFIG_STM32_STM32F30XX)
+# define DBGMCU_APB1_TIM2STOP (1 << 0) /* Bit 0: TIM2 stopped when core is halted */
+# define DBGMCU_APB1_TIM3STOP (1 << 1) /* Bit 1: TIM3 stopped when core is halted */
+# define DBGMCU_APB1_TIM4STOP (1 << 2) /* Bit 2: TIM4 stopped when core is halted */
+# define DBGMCU_APB1_TIM6STOP (1 << 4) /* Bit 4: TIM6 stopped when core is halted */
+# define DBGMCU_APB1_TIM7STOP (1 << 5) /* Bit 5: TIM7 stopped when core is halted */
+# define DBGMCU_CR_RTCSTOP (1 << 10) /* Bit 11: RTC stopped when Core is halted */
+# define DBGMCU_CR_WWDGSTOP (1 << 11) /* Bit 11: Window Watchdog stopped when core is halted */
+# define DBGMCU_CR_IWDGSTOP (1 << 12) /* Bit 12: Independent Watchdog stopped when core is halted */
+# define DBGMCU_APB1_I2C1STOP (1 << 21) /* Bit 21: SMBUS timeout mode stopped when Core is halted */
+# define DBGMCU_APB1_I2C2STOP (1 << 22) /* Bit 22: SMBUS timeout mode stopped when Core is halted */
+# define DBGMCU_APB1_CAN1STOP (1 << 25) /* Bit 25: CAN1 stopped when core is halted */
#endif
/* Debug MCU APB2 freeze register */
@@ -127,6 +139,12 @@
# define DBGMCU_APB2_TIM9STOP (1 << 16) /* Bit 16: TIM9 stopped when core is halted */
# define DBGMCU_APB2_TIM10STOP (1 << 17) /* Bit 17: TIM10 stopped when core is halted */
# define DBGMCU_APB2_TIM11STOP (1 << 18) /* Bit 18: TIM11 stopped when core is halted */
+#elif defined(CONFIG_STM32_STM32F30XX)
+# define DBGMCU_APB2_TIM1STOP (1 << 0) /* Bit 0: TIM1 stopped when core is halted */
+# define DBGMCU_APB2_TIM8STOP (1 << 1) /* Bit 1: TIM8 stopped when core is halted */
+# define DBGMCU_APB2_TIM15STOP (1 << 2) /* Bit 2: TIM15 stopped when core is halted */
+# define DBGMCU_APB2_TIM16STOP (1 << 3) /* Bit 3: TIM16 stopped when core is halted */
+# define DBGMCU_APB2_TIM17STOP (1 << 4) /* Bit 4: TIM17 stopped when core is halted */
#endif
/****************************************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_exti.h b/nuttx/arch/arm/src/stm32/chip/stm32_exti.h
index 5386a260f..b9b27e347 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_exti.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_exti.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_exti.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,6 +55,11 @@
# define STM32_NEXTI 19
# define STM32_EXTI_MASK 0x0007ffff
# endif
+#eif defined(CONFIG_STM32_STM32F30XX)
+# define STM32_NEXTI1 31
+# define STM32_EXTI1_MASK 0xffffffff
+# define STM32_NEXTI2 4
+# define STM32_EXTI2_MASK 0x0000000f
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define STM32_NEXTI 23
# define STM32_EXTI_MASK 0x007fffff
@@ -64,6 +69,11 @@
/* Register Offsets *****************************************************************/
+#if defined(CONFIG_STM32_STM32F30XX)
+# define STM32_EXTI1_OFFSET 0x0000 /* Offset to EXTI1 registers */
+# define STM32_EXTI2_OFFSET 0x0018 /* Offset to EXTI2 registers */
+#endif
+
#define STM32_EXTI_IMR_OFFSET 0x0000 /* Interrupt mask register */
#define STM32_EXTI_EMR_OFFSET 0x0004 /* Event mask register */
#define STM32_EXTI_RTSR_OFFSET 0x0008 /* Rising Trigger selection register */
@@ -73,12 +83,39 @@
/* Register Addresses ***************************************************************/
-#define STM32_EXTI_IMR (STM32_EXTI_BASE+STM32_EXTI_IMR_OFFSET)
-#define STM32_EXTI_EMR (STM32_EXTI_BASE+STM32_EXTI_EMR_OFFSET)
-#define STM32_EXTI_RTSR (STM32_EXTI_BASE+STM32_EXTI_RTSR_OFFSET)
-#define STM32_EXTI_FTSR (STM32_EXTI_BASE+STM32_EXTI_FTSR_OFFSET)
-#define STM32_EXTI_SWIER (STM32_EXTI_BASE+STM32_EXTI_SWIER_OFFSET)
-#define STM32_EXTI_PR (STM32_EXTI_BASE+STM32_EXTI_PR_OFFSET)
+#if defined(CONFIG_STM32_STM32F30XX)
+# define STM32_EXTI1_BASE (STM32_EXTI_BASE+STM32_EXTI1_OFFSET)
+# define STM32_EXTI2_BASE (STM32_EXTI_BASE+STM32_EXTI2_OFFSET)
+
+# define STM32_EXTI1_IMR (STM32_EXTI1_BASE+STM32_EXTI_IMR_OFFSET)
+# define STM32_EXTI1_EMR (STM32_EXTI1_BASE+STM32_EXTI_EMR_OFFSET)
+# define STM32_EXTI1_RTSR (STM32_EXTI1_BASE+STM32_EXTI_RTSR_OFFSET)
+# define STM32_EXTI1_FTSR (STM32_EXTI1_BASE+STM32_EXTI_FTSR_OFFSET)
+# define STM32_EXTI1_SWIER (STM32_EXTI1_BASE+STM32_EXTI_SWIER_OFFSET)
+# define STM32_EXTI1_PR (STM32_EXTI1_BASE+STM32_EXTI_PR_OFFSET)
+
+# define STM32_EXTI2_IMR (STM32_EXTI2_BASE+STM32_EXTI_IMR_OFFSET)
+# define STM32_EXTI2_EMR (STM32_EXTI2_BASE+STM32_EXTI_EMR_OFFSET)
+# define STM32_EXTI2_RTSR (STM32_EXTI2_BASE+STM32_EXTI_RTSR_OFFSET)
+# define STM32_EXTI2_FTSR (STM32_EXTI2_BASE+STM32_EXTI_FTSR_OFFSET)
+# define STM32_EXTI2_SWIER (STM32_EXTI2_BASE+STM32_EXTI_SWIER_OFFSET)
+# define STM32_EXTI2_PR (STM32_EXTI2_BASE+STM32_EXTI_PR_OFFSET)
+
+# define STM32_EXTI_IMR STM32_EXTI1_IMR
+# define STM32_EXTI_EMR STM32_EXTI1_EMR
+# define STM32_EXTI_RTSR STM32_EXTI1_RTSR
+# define STM32_EXTI_FTSR STM32_EXTI1_FTSR
+# define STM32_EXTI_SWIER STM32_EXTI1_SWIER
+# define STM32_EXTI_PR STM32_EXTI1_PR
+
+#else
+# define STM32_EXTI_IMR (STM32_EXTI_BASE+STM32_EXTI_IMR_OFFSET)
+# define STM32_EXTI_EMR (STM32_EXTI_BASE+STM32_EXTI_EMR_OFFSET)
+# define STM32_EXTI_RTSR (STM32_EXTI_BASE+STM32_EXTI_RTSR_OFFSET)
+# define STM32_EXTI_FTSR (STM32_EXTI_BASE+STM32_EXTI_FTSR_OFFSET)
+# define STM32_EXTI_SWIER (STM32_EXTI_BASE+STM32_EXTI_SWIER_OFFSET)
+# define STM32_EXTI_PR (STM32_EXTI_BASE+STM32_EXTI_PR_OFFSET)
+#endif
/* Register Bitfield Definitions ****************************************************/
@@ -138,4 +175,17 @@
#define EXTI_IMR_SHIFT (0) /* Bits 0-X: Pending bit for all lines */
#define EXTI_IMR_MASK STM32_EXTI_MASK
+/* Compatibility Definitions ********************************************************/
+
+#if defined(CONFIG_STM32_STM32F30XX)
+# define STM32_NEXTI STM32_NEXTI1
+# define STM32_EXTI_MASK STM32_EXTI1_MASK
+# define STM32_EXTI_IMR STM32_EXTI1_IMR
+# define STM32_EXTI_EMR STM32_EXTI1_EMR
+# define STM32_EXTI_RTSR STM32_EXTI1_RTSR
+# define STM32_EXTI_FTSR STM32_EXTI1_FTSR
+# define STM32_EXTI_SWIER STM32_EXTI1_SWIER
+# define STM32_EXTI_PR STM32_EXTI1_PR
+#endif
+
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_EXTI_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
index 2ece6a357..4e817a2c1 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_pwr.h
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -93,7 +93,12 @@
# define PWR_CSR_BRR (1 << 3) /* Bit 3: Backup regulator ready */
#endif
-#define PWR_CSR_EWUP (1 << 8) /* Bit 8: Enable WKUP pin */
+#if defined(CONFIG_STM32_STM32F30XX)
+# define PWR_CSR_EWUP1 (1 << 8) /* Bit 8: Enable WKUP1 pin */
+# define PWR_CSR_EWUP2 (1 << 9) /* Bit 9: Enable WKUP2 pin */
+#else
+# define PWR_CSR_EWUP (1 << 8) /* Bit 8: Enable WKUP pin */
+#endif
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define PWR_CSR_BRE (1 << 9) /* Bit 9: Backup regulator enable */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_tim.h b/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
index 3713f8b79..d31a7704e 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
@@ -57,6 +57,8 @@
* 16-bit General Timers without DMA: TIM9, TIM10, TIM11, TIM12, TIM13, and TIM14
* For the STM32F10xx all timers are 16-bit.
* For the STM32F20xx and STM32F40xx, TIM2 and 5 are 32-bit
+ * The STM32 F1 Value Line and the STM32 F3 have variant general purpose registers
+ * that are not yet fully covered in this header file.
*/
#define STM32_GTIM_CR1_OFFSET 0x0000 /* Control register 1 (16-bit) */
@@ -68,31 +70,42 @@
#define STM32_GTIM_CCMR1_OFFSET 0x0018 /* Capture/compare mode register 1 (16-bit) */
#define STM32_GTIM_CCMR2_OFFSET 0x001c /* Capture/compare mode register 2 (16-bit, TIM2-5 only) */
#define STM32_GTIM_CCER_OFFSET 0x0020 /* Capture/compare enable register (16-bit) */
-#define STM32_GTIM_CNT_OFFSET 0x0024 /* Counter (16-bit or 32-bit STM3240 TIM2 and 5 only) */
+#define STM32_GTIM_CNT_OFFSET 0x0024 /* Counter (16-bit* or 32-bit STM3240 TIM2 and 5 only) */
#define STM32_GTIM_PSC_OFFSET 0x0028 /* Prescaler (16-bit) */
#define STM32_GTIM_ARR_OFFSET 0x002c /* Auto-reload register (16-bit) */
#define STM32_GTIM_CCR1_OFFSET 0x0034 /* Capture/compare register 1 (16-bit or 32-bit STM3240 TIM2/5 only) */
-#define STM32_GTIM_CCR2_OFFSET 0x0038 /* Capture/compare register 2 (16-bit TIM2-5 only or 32-bit STM3240 TIM2/5 only) */
-#define STM32_GTIM_CCR3_OFFSET 0x003c /* Capture/compare register 3 (16-bit TIM2-5 only or 32-bit STM3240 TIM2/5 only) */
-#define STM32_GTIM_CCR4_OFFSET 0x0040 /* Capture/compare register 4 (16-bit TIM2-5 only or 32-bit STM3240 TIM2/5 only) */
+#define STM32_GTIM_CCR2_OFFSET 0x0038 /* Capture/compare register 2 (16-bit TIM2-5 only or 32-bit STM32 F4 TIM2/5 or STM2 F3 TIM15 only) */
+#define STM32_GTIM_CCR3_OFFSET 0x003c /* Capture/compare register 3 (16-bit TIM2-5 only or 32-bit STM32 F4 TIM2/5 only) */
+#define STM32_GTIM_CCR4_OFFSET 0x0040 /* Capture/compare register 4 (16-bit TIM2-5 only or 32-bit STM32 F4 TIM2/5 only) */
#define STM32_GTIM_DCR_OFFSET 0x0048 /* DMA control register (16-bit, TIM2-5 only) */
#define STM32_GTIM_DMAR_OFFSET 0x004c /* DMA address for burst mode (16-bit, TIM2-5 only) */
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define STM32_GTIM_OR_OFFSET 0x0050 /* Timer 2/5/11 option register */
-#endif
+/* The Option register is available on in the
+ *
+ * STM32 F1 value line, F2 and F4: TIM2, TIM5, and TIM11
+ * STM32 F3 (and possibly the F1 value line): TIM16
+ */
+
+#define STM32_GTIM_OR_OFFSET 0x0050 /* Timer 2/5/11/16 option register */
+
+/* TIM16, and 17 only.
+ * Only available in the STM32 F1 Value Line and the STM32 F3 family.
+ */
+
+#define STM32_GTIM_RCR_OFFSET 0x002c /* Repetition counter register (TIM16/TIM17) */
+#define STM32_GTIM_BDTR_OFFSET 0x0044 /* Break and dead-time register (TIM16/TIM17) */
/* Advanced Timers - TIM1 and TIM8 */
#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_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_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_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) */
@@ -101,10 +114,18 @@
#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_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) */
+/* *Note that many of the above registers are 32-bits wide on the F3 */
+
+#ifdef CONFIG_STM32_STM32F30XX
+# define STM32_ATIM_CCMR3_OFFSET 0x0054 /* Capture/compare mode register 3 (32-bit) */
+# define STM32_ATIM_CCR5_OFFSET 0x0058 /* Capture/compare register 4 (16-bit) */
+# define STM32_ATIM_CCR6_OFFSET 0x005c /* Capture/compare register 4 (32-bit) */
+#endif
+
/* Register Addresses *******************************************************************************/
/* Advanced Timers - TIM1 and TIM8 */
@@ -130,6 +151,11 @@
# define STM32_TIM1_BDTR (STM32_TIM1_BASE+STM32_ATIM_BDTR_OFFSET)
# define STM32_TIM1_DCR (STM32_TIM1_BASE+STM32_ATIM_DCR_OFFSET)
# define STM32_TIM1_DMAR (STM32_TIM1_BASE+STM32_ATIM_DMAR_OFFSET)
+# ifdef CONFIG_STM32_STM32F30XX
+# define STM32_TIM1_CCMR3 (STM32_TIM1_BASE+STM32_ATIM_CCMR3_OFFSET)
+# define STM32_TIM1_CCR5 (STM32_TIM1_BASE+STM32_ATIM_CCR5_OFFSET)
+# define STM32_TIM1_CCR6 (STM32_TIM1_BASE+STM32_ATIM_CCR6_OFFSET)
+# endif
#endif
#if STM32_NATIM > 1
@@ -153,6 +179,11 @@
# define STM32_TIM8_BDTR (STM32_TIM8_BASE+STM32_ATIM_BDTR_OFFSET)
# define STM32_TIM8_DCR (STM32_TIM8_BASE+STM32_ATIM_DCR_OFFSET)
# define STM32_TIM8_DMAR (STM32_TIM8_BASE+STM32_ATIM_DMAR_OFFSET)
+# ifdef CONFIG_STM32_STM32F30XX
+# define STM32_TIM8_CCMR3 (STM32_TIM8_BASE+STM32_ATIM_CCMR3_OFFSET)
+# define STM32_TIM8_CCR5 (STM32_TIM8_BASE+STM32_ATIM_CCR5_OFFSET)
+# define STM32_TIM8_CCR6 (STM32_TIM8_BASE+STM32_ATIM_CCR6_OFFSET)
+# endif
#endif
/* 16-/32-bit General Timers - TIM2, TIM3, TIM4, and TIM5 with DMA.
@@ -250,6 +281,59 @@
# endif
#endif
+#define STM32_TIM15_CR1 (STM32_TIM15_BASE+STM32_GTIM_CR1_OFFSET)
+#define STM32_TIM15_CR2 (STM32_TIM15_BASE+STM32_GTIM_CR2_OFFSET)
+#define STM32_TIM15_SMCR (STM32_TIM15_BASE+STM32_GTIM_SMCR_OFFSET)
+#define STM32_TIM15_DIER (STM32_TIM15_BASE+STM32_GTIM_DIER_OFFSET)
+#define STM32_TIM15_SR (STM32_TIM15_BASE+STM32_GTIM_SR_OFFSET)
+#define STM32_TIM15_EGR (STM32_TIM15_BASE+STM32_GTIM_EGR_OFFSET)
+#define STM32_TIM15_CCMR1 (STM32_TIM15_BASE+STM32_GTIM_CCMR1_OFFSET)
+#define STM32_TIM15_CCER (STM32_TIM15_BASE+STM32_GTIM_CCER_OFFSET)
+#define STM32_TIM15_CNT (STM32_TIM15_BASE+STM32_GTIM_CNT_OFFSET)
+#define STM32_TIM15_PSC (STM32_TIM15_BASE+STM32_GTIM_PSC_OFFSET)
+#define STM32_TIM15_ARR (STM32_TIM15_BASE+STM32_GTIM_ARR_OFFSET)
+#define STM32_TIM15_RCR (STM32_TIM15_BASE+STM32_GTIM_RCR_OFFSET)
+#define STM32_TIM15_CCR1 (STM32_TIM15_BASE+STM32_GTIM_CCR1_OFFSET)
+#define STM32_TIM15_CCR2 (STM32_TIM15_BASE+STM32_GTIM_CCR2_OFFSET)
+#define STM32_TIM15_BDTR (STM32_TIM15_BASE+STM32_GTIM_BDTR_OFFSET)
+#define STM32_TIM15_DCR (STM32_TIM15_BASE+STM32_GTIM_DCR_OFFSET)
+#define STM32_TIM15_DMAR (STM32_TIM15_BASE+STM32_GTIM_DMAR_OFFSET)
+
+#define STM32_TIM16_CR1 (STM32_TIM16_BASE+STM32_GTIM_CR1_OFFSET)
+#define STM32_TIM16_CR2 (STM32_TIM16_BASE+STM32_GTIM_CR2_OFFSET)
+#define STM32_TIM16_DIER (STM32_TIM16_BASE+STM32_GTIM_DIER_OFFSET)
+#define STM32_TIM16_SR (STM32_TIM16_BASE+STM32_GTIM_SR_OFFSET)
+#define STM32_TIM16_EGR (STM32_TIM16_BASE+STM32_GTIM_EGR_OFFSET)
+#define STM32_TIM16_CCMR1 (STM32_TIM16_BASE+STM32_GTIM_CCMR1_OFFSET)
+#define STM32_TIM16_CCMR2 (STM32_TIM16_BASE+STM32_GTIM_CCMR2_OFFSET)
+#define STM32_TIM16_CCER (STM32_TIM16_BASE+STM32_GTIM_CCER_OFFSET)
+#define STM32_TIM16_CNT (STM32_TIM16_BASE+STM32_GTIM_CNT_OFFSET)
+#define STM32_TIM16_PSC (STM32_TIM16_BASE+STM32_GTIM_PSC_OFFSET)
+#define STM32_TIM16_ARR (STM32_TIM16_BASE+STM32_GTIM_ARR_OFFSET)
+#define STM32_TIM16_RCR (STM32_TIM16_BASE+STM32_GTIM_RCR_OFFSET)
+#define STM32_TIM16_CCR1 (STM32_TIM16_BASE+STM32_GTIM_CCR1_OFFSET)
+#define STM32_TIM16_BDTR (STM32_TIM16_BASE+STM32_GTIM_BDTR_OFFSET)
+#define STM32_TIM16_DCR (STM32_TIM16_BASE+STM32_GTIM_DCR_OFFSET)
+#define STM32_TIM16_DMAR (STM32_TIM16_BASE+STM32_GTIM_DMAR_OFFSET)
+#define STM32_TIM16_OR (STM32_TIM16_BASE+STM32_GTIM_OR_OFFSET)
+
+#define STM32_TIM17_CR1 (STM32_TIM17_BASE+STM32_GTIM_CR1_OFFSET)
+#define STM32_TIM17_CR2 (STM32_TIM17_BASE+STM32_GTIM_CR2_OFFSET)
+#define STM32_TIM17_DIER (STM32_TIM17_BASE+STM32_GTIM_DIER_OFFSET)
+#define STM32_TIM17_SR (STM32_TIM17_BASE+STM32_GTIM_SR_OFFSET)
+#define STM32_TIM17_EGR (STM32_TIM17_BASE+STM32_GTIM_EGR_OFFSET)
+#define STM32_TIM17_CCMR1 (STM32_TIM17_BASE+STM32_GTIM_CCMR1_OFFSET)
+#define STM32_TIM17_CCMR2 (STM32_TIM17_BASE+STM32_GTIM_CCMR2_OFFSET)
+#define STM32_TIM17_CCER (STM32_TIM17_BASE+STM32_GTIM_CCER_OFFSET)
+#define STM32_TIM17_CNT (STM32_TIM17_BASE+STM32_GTIM_CNT_OFFSET)
+#define STM32_TIM17_PSC (STM32_TIM17_BASE+STM32_GTIM_PSC_OFFSET)
+#define STM32_TIM17_ARR (STM32_TIM17_BASE+STM32_GTIM_ARR_OFFSET)
+#define STM32_TIM17_RCR (STM32_TIM17_BASE+STM32_GTIM_RCR_OFFSET)
+#define STM32_TIM17_CCR1 (STM32_TIM17_BASE+STM32_GTIM_CCR1_OFFSET)
+#define STM32_TIM17_BDTR (STM32_TIM17_BASE+STM32_GTIM_BDTR_OFFSET)
+#define STM32_TIM17_DCR (STM32_TIM17_BASE+STM32_GTIM_DCR_OFFSET)
+#define STM32_TIM17_DMAR (STM32_TIM17_BASE+STM32_GTIM_DMAR_OFFSET)
+
/* 16-bit General Timers - TIM9-14 without DMA. Note that (1) these timers
* support only a subset of the general timer registers are supported, and
* (2) TIM9 and TIM12 differ from the others.
@@ -384,6 +468,10 @@
# 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 */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CR1_UIFREMAP (1 << 11) /* Bit 11: UIF status bit remapping */
+#endif
+
/* Control register 2 */
#define ATIM_CR2_CCPC (1 << 0) /* Bit 0: Capture/Compare Preloaded Control */
@@ -391,10 +479,16 @@
#define ATIM_CR2_CCDS (1 << 3) /* Bit 3: Capture/Compare DMA Selection */
#define ATIM_CR2_MMS_SHIFT (4) /* Bits 6-4: Master Mode Selection */
#define ATIM_CR2_MMS_MASK (7 << ATIM_CR2_MMS_SHIFT)
-#define ATIM_CR2_OC1REF (4 << ATIM_CR2_MMS_SHIFT) /* 100: Compare OC1REF is TRGO */
-#define ATIM_CR2_OC2REF (5 << ATIM_CR2_MMS_SHIFT) /* 101: Compare OC2REF is TRGO */
-#define ATIM_CR2_OC3REF (6 << ATIM_CR2_MMS_SHIFT) /* 110: Compare OC3REF is TRGO */
-#define ATIM_CR2_OC4REF (7 << ATIM_CR2_MMS_SHIFT) /* 111: Compare OC4REF is TRGO */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CR2_MMS_RESET (0 << ATIM_CR2_MMS_SHIFT) /* 000: Reset - TIMx_EGR UG bit is TRG9 */
+# define ATIM_CR2_MMS_ENABLE (1 << ATIM_CR2_MMS_SHIFT) /* 001: Enable - CNT_EN is TRGO */
+# define ATIM_CR2_MMS_UPDATE (2 << ATIM_CR2_MMS_SHIFT) /* 010: Update event is TRGH0*/
+# define ATIM_CR2_MMS_COMPP (3 << ATIM_CR2_MMS_SHIFT) /* 010: Compare Pulse - CC1IF flag */
+#endif
+# define ATIM_CR2_MMS_OC1REF (4 << ATIM_CR2_MMS_SHIFT) /* 100: Compare OC1REF is TRGO */
+# define ATIM_CR2_MMS_OC2REF (5 << ATIM_CR2_MMS_SHIFT) /* 101: Compare OC2REF is TRGO */
+# define ATIM_CR2_MMS_OC3REF (6 << ATIM_CR2_MMS_SHIFT) /* 110: Compare OC3REF is TRGO */
+# define ATIM_CR2_MMS_OC4REF (7 << ATIM_CR2_MMS_SHIFT) /* 111: Compare OC4REF is TRGO */
#define ATIM_CR2_TI1S (1 << 7) /* Bit 7: TI1 Selection */
#define ATIM_CR2_OIS1 (1 << 8) /* Bit 8: Output Idle state 1 (OC1 output) */
#define ATIM_CR2_OIS1N (1 << 9) /* Bit 9: Output Idle state 1 (OC1N output) */
@@ -404,6 +498,29 @@
#define ATIM_CR2_OIS3N (1 << 13) /* Bit 13: Output Idle state 3 (OC3N output) */
#define ATIM_CR2_OIS4 (1 << 14) /* Bit 14: Output Idle state 4 (OC4 output) */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CR2_OIS5 (1 << 16) /* Bit 16: OOutput Idle state 5 (OC5 output) */
+# define ATIM_CR2_OIS6 (1 << 18) /* Bit 18: Output Idle state 6 (OC6 output) */
+# define ATIM_CR2_MMS2_SHIFT (20) /* Bits 20-23: Master Mode Selection 2 */
+# define ATIM_CR2_MMS2_MASK (15 << ATIM_CR2_MMS2_SHIFT)
+# define ATIM_CR2_MMS2_RESET (0 << ATIM_CR2_MMS2_SHIFT) /* 0000: Reset - TIMx_EGR UG bit is TRG9 */
+# define ATIM_CR2_MMS2_ENABLE (1 << ATIM_CR2_MMS2_SHIFT) /* 0001: Enable - CNT_EN is TRGO2 */
+# define ATIM_CR2_MMS2_UPDATE (2 << ATIM_CR2_MMS2_SHIFT) /* 0010: Update event is TRGH0*/
+# define ATIM_CR2_MMS2_COMPP (3 << ATIM_CR2_MMS2_SHIFT) /* 0010: Compare Pulse - CC1IF flag */
+# define ATIM_CR2_MMS2_OC1REF (4 << ATIM_CR2_MMS2_SHIFT) /* 0100: Compare OC1REF is TRGO2 */
+# define ATIM_CR2_MMS2_OC2REF (5 << ATIM_CR2_MMS2_SHIFT) /* 0101: Compare OC2REF is TRGO2 */
+# define ATIM_CR2_MMS2_OC3REF (6 << ATIM_CR2_MMS2_SHIFT) /* 0110: Compare OC3REF is TRGO2 */
+# define ATIM_CR2_MMS2_OC4REF (7 << ATIM_CR2_MMS2_SHIFT) /* 0111: Compare OC4REF is TRGO2 */
+# define ATIM_CR2_MMS2_OC5REF (8 << ATIM_CR2_MMS2_SHIFT) /* 1000: Compare OC5REF is TRGO2 */
+# define ATIM_CR2_MMS2_OC6REF (9 << ATIM_CR2_MMS2_SHIFT) /* 1001: Compare OC6REF is TRGO2 */
+# define ATIM_CR2_MMS2_CMPOC4 (10 << ATIM_CR2_MMS2_SHIFT) /* 1010: Compare pulse - OC4REF edge is TRGO2 */
+# define ATIM_CR2_MMS2_CMPOC6 (11 << ATIM_CR2_MMS2_SHIFT) /* 1011: Compare pulse - OC6REF edge is TRGO2 */
+# define ATIM_CR2_MMS2_CMPOC4R6R (12 << ATIM_CR2_MMS2_SHIFT) /* 1100: Compare pulse - OC4REF/OC6REF rising */
+# define ATIM_CR2_MMS2_CMPOC4R6F (13 << ATIM_CR2_MMS2_SHIFT) /* 1101: Compare pulse - OC4REF rising/OC6REF falling */
+# define ATIM_CR2_MMS2_CMPOC5R6R (14 << ATIM_CR2_MMS2_SHIFT) /* 1110: Compare pulse - OC5REF/OC6REF rising */
+# define ATIM_CR2_MMS2_CMPOC5R6F (15 << ATIM_CR2_MMS2_SHIFT) /* 1111: Compare pulse - OC5REF rising/OC6REF falling */
+#endif
+
/* Slave mode control register */
#define ATIM_SMCR_SMS_SHIFT (0) /* Bits 0-2: Slave mode selection */
@@ -416,6 +533,9 @@
# define ATIM_SMCR_GATED (5 << ATIM_SMCR_SMS_SHIFT) /* 101: Gated Mode */
# define ATIM_SMCR_TRIGGER (6 << ATIM_SMCR_SMS_SHIFT) /* 110: Trigger Mode */
# define ATIM_SMCR_EXTCLK1 (7 << ATIM_SMCR_SMS_SHIFT) /* 111: External Clock Mode 1 */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_SMCR_OCCS (1 << 3) /* Bit 3: OCREF clear selection */
+#endif
#define ATIM_SMCR_TS_SHIFT (4) /* Bits 4-6: Trigger selection */
#define ATIM_SMCR_TS_MASK (7 << ATIM_SMCR_TS_SHIFT)
# define ATIM_SMCR_ITR0 (0 << ATIM_SMCR_TS_SHIFT) /* 000: Internal trigger 0 (ITR0) */
@@ -453,6 +573,9 @@
# define ATIM_SMCR_ETRPd8 (3 << ATIM_SMCR_ETPS_SHIFT) /* 11: ETRP frequency divided by 8 */
#define ATIM_SMCR_ECE (1 << 14) /* Bit 14: External clock enable */
#define ATIM_SMCR_ETP (1 << 15) /* Bit 15: External trigger polarity */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_SMCR_SMS (1 << 16) /* Bit 16: Slave mode selection - bit 3 */
+#endif
/* DMA/Interrupt enable register */
@@ -462,13 +585,13 @@
#define ATIM_DIER_CC3IE (1 << 3) /* Bit 3: Capture/Compare 3 interrupt enable */
#define ATIM_DIER_CC4IE (1 << 4) /* Bit 4: Capture/Compare 4 interrupt enable */
-#ifdef CONFIG_STM32_STM32F10XX
+#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
# define ATIM_DIER_COMIE (1 << 5) /* Bit 5: COM interrupt enable */
#endif
#define ATIM_DIER_TIE (1 << 6) /* Bit 6: Trigger interrupt enable */
-#ifdef CONFIG_STM32_STM32F10XX
+#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
# define ATIM_DIER_BIE (1 << 7) /* Bit 7: Break interrupt enable */
#endif
@@ -478,7 +601,7 @@
#define ATIM_DIER_CC3DE (1 << 11) /* Bit 11: Capture/Compare 3 DMA request enable */
#define ATIM_DIER_CC4DE (1 << 12) /* Bit 12: Capture/Compare 4 DMA request enable */
-#ifdef CONFIG_STM32_STM32F10XX
+#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
# define ATIM_DIER_COMDE (1 << 13) /* Bit 13: COM DMA request enable */
#endif
@@ -486,23 +609,31 @@
/* Status register */
-#define ATIM_SR_UIF (1 << 0) /* Bit 0: Update interrupt Flag */
-#define ATIM_SR_CC1IF (1 << 1) /* Bit 1: Capture/Compare 1 interrupt Flag */
-#define ATIM_SR_CC2IF (1 << 2) /* Bit 2: Capture/Compare 2 interrupt Flag */
-#define ATIM_SR_CC3IF (1 << 3) /* Bit 3: Capture/Compare 3 interrupt Flag */
-#define ATIM_SR_CC4IF (1 << 4) /* Bit 4: Capture/Compare 4 interrupt Flag */
-#define ATIM_SR_COMIF (1 << 5) /* Bit 5: COM interrupt Flag */
-#define ATIM_SR_TIF (1 << 6) /* Bit 6: Trigger interrupt Flag */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_SR_BIF (1 << 7) /* Bit 7: Break interrupt Flag */
+#define ATIM_SR_UIF (1 << 0) /* Bit 0: Update interrupt Flag */
+#define ATIM_SR_CC1IF (1 << 1) /* Bit 1: Capture/Compare 1 interrupt Flag */
+#define ATIM_SR_CC2IF (1 << 2) /* Bit 2: Capture/Compare 2 interrupt Flag */
+#define ATIM_SR_CC3IF (1 << 3) /* Bit 3: Capture/Compare 3 interrupt Flag */
+#define ATIM_SR_CC4IF (1 << 4) /* Bit 4: Capture/Compare 4 interrupt Flag */
+#define ATIM_SR_COMIF (1 << 5) /* Bit 5: COM interrupt Flag */
+#define ATIM_SR_TIF (1 << 6) /* Bit 6: Trigger interrupt Flag */
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define ATIM_SR_BIF (1 << 7) /* Bit 7: Break interrupt Flag */
+#elif defined(CONFIG_STM32_STM32F30XX)
+# define ATIM_SR_BIF (1 << 7) /* Bit 7: Break interrupt Flag */
+# define ATIM_SR_B2IF (1 << 8) /* Bit 8: Break 2 interrupt Flag */
#endif
-#define ATIM_SR_CC1OF (1 << 9) /* Bit 9: Capture/Compare 1 Overcapture Flag */
+#define ATIM_SR_CC1OF (1 << 9) /* Bit 9: Capture/Compare 1 Overcapture Flag */
#define ATIM_SR_CC2OF (1 << 10) /* Bit 10: Capture/Compare 2 Overcapture Flag */
#define ATIM_SR_CC3OF (1 << 11) /* Bit 11: Capture/Compare 3 Overcapture Flag */
#define ATIM_SR_CC4OF (1 << 12) /* Bit 12: Capture/Compare 4 Overcapture Flag */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_SR_CC5IF (1 << 16) /* Bit 16: Compare 5 interrupt flag */
+# define ATIM_SR_CC6IF (1 << 17) /* Bit 17: Compare 6 interrupt flag */
+#endif
+
/* Event generation register */
#define ATIM_EGR_UG (1 << 0) /* Bit 0: Update Generation */
@@ -511,14 +642,17 @@
#define ATIM_EGR_CC3G (1 << 3) /* Bit 3: Capture/Compare 3 Generation */
#define ATIM_EGR_CC4G (1 << 4) /* Bit 4: Capture/Compare 4 Generation */
-#ifdef CONFIG_STM32_STM32F10XX
+#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F30XX)
# define ATIM_EGR_COMG (1 << 5) /* Bit 5: Capture/Compare Control Update Generation */
#endif
#define ATIM_EGR_TG (1 << 6) /* Bit 6: Trigger Generation */
-#ifdef CONFIG_STM32_STM32F10XX
+#if defined(CONFIG_STM32_STM32F10XX)
+# define ATIM_EGR_BG (1 << 7) /* Bit 7: Break Generation */
+#elif defined(CONFIG_STM32_STM32F30XX)
# define ATIM_EGR_BG (1 << 7) /* Bit 7: Break Generation */
+# define ATIM_EGR_B2G (1 << 8) /* Bit 8: Break 2 Generation */
#endif
/* Capture/compare mode register 1 -- Output compare mode */
@@ -542,6 +676,11 @@
/* (See common (unshifted) bit field definitions below) */
#define ATIM_CCMR1_OC2CE (1 << 15) /* Bit 15: Output Compare 2 Clear Enable */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CCMR1_OC1M (1 << 16) /* Bit 16: Output Compare 1 mode - bit 3 */
+# define ATIM_CCMR1_OC2M (1 << 24) /* Bit 24: Output Compare 2 mode - bit 3 */
+#endif
+
/* Common CCMR (unshifted) Capture/Compare Selection bit-field definitions */
#define ATIM_CCMR_CCS_CCOUT (0) /* 00: CCx channel output */
@@ -624,6 +763,11 @@
/* (See common (unshifted) bit field definitions above) */
#define ATIM_CCMR2_OC4CE (1 << 15) /* Bit 15: Output Compare 4 Clear Enable */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CCMR1_OC3M (1 << 16) /* Bit 16: Output Compare 3 mode - bit 3 */
+# define ATIM_CCMR1_OC4M (1 << 24) /* Bit 24: Output Compare 4 mode - bit 3 */
+#endif
+
/* Capture/compare mode register 2 - Input Capture Mode */
/* Bits 1-0:(same as output compare mode) */
@@ -641,33 +785,85 @@
#define ATIM_CCMR2_IC4F_MASK (0x0f << ATIM_CCMR2_IC4F_SHIFT)
/* (See common (unshifted) bit field definitions above) */
+/* Capture/compare mode register 3 -- Output compare mode */
+
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CCMR3_OC5FE (1 << 2) /* Bit 2: Output Compare 5 Fast enable */
+# define ATIM_CCMR3_OC5PE (1 << 3) /* Bit 3: Output Compare 5 Preload enable */
+# define ATIM_CCMR3_OC5M_SHIFT (4) /* Bits 6-4: Output Compare 5 Mode */
+# define ATIM_CCMR3_OC5M_MASK (7 << ATIM_CCMR3_OC5M_SHIFT)
+ /* (See common (unshifted) bit field definitions below) */
+# define ATIM_CCMR3_OC5CE (1 << 7) /* Bit 7: Output Compare 5 Clear Enable */
+# define ATIM_CCMR3_OC6FE (1 << 10) /* Bit 10: Output Compare 6 Fast enable */
+# define ATIM_CCMR3_OC6PE (1 << 11) /* Bit 11: Output Compare 6 Preload enable */
+# define ATIM_CCMR3_OC6M_SHIFT (12) /* Bits 14-12: Output Compare 7 Mode */
+# define ATIM_CCMR3_OC6M_MASK (7 << ATIM_CCMR3_OC6M_SHIFT)
+ /* (See common (unshifted) bit field definitions below) */
+# define ATIM_CCMR3_OC6CE (1 << 15) /* Bit 15: Output Compare 7 Clear Enable */
+
+# define ATIM_CCMR3_OC5M (1 << 16) /* Bit 16: Output Compare 5 mode - bit 3 */
+# define ATIM_CCMR3_OC6M (1 << 24) /* Bit 24: Output Compare 6 mode - bit 3 */
+#endif
+
/* Capture/compare enable register */
#define ATIM_CCER_CC1E (1 << 0) /* Bit 0: Capture/Compare 1 output enable */
#define ATIM_CCER_CC1P (1 << 1) /* Bit 1: Capture/Compare 1 output Polarity */
#define ATIM_CCER_CC1NE (1 << 2) /* Bit 2: Capture/Compare 1 Complementary output enable */
-#define ATIM_CCER_CC1NP (1 << 3) /* Bit 3: Capture/Compare 1 Complementary output Polarity */
+#define ATIM_CCER_CC1NP (1 << 3) /* Bit 3: Capture/Compare 1 Complementary output polarity */
#define ATIM_CCER_CC2E (1 << 4) /* Bit 4: Capture/Compare 2 output enable */
#define ATIM_CCER_CC2P (1 << 5) /* Bit 5: Capture/Compare 2 output Polarity */
#define ATIM_CCER_CC2NE (1 << 6) /* Bit 6: Capture/Compare 2 Complementary output enable */
-#define ATIM_CCER_CC2NP (1 << 7) /* Bit 7: Capture/Compare 2 Complementary output Polarity */
+#define ATIM_CCER_CC2NP (1 << 7) /* Bit 7: Capture/Compare 2 Complementary output polarity */
#define ATIM_CCER_CC3E (1 << 8) /* Bit 8: Capture/Compare 3 output enable */
#define ATIM_CCER_CC3P (1 << 9) /* Bit 9: Capture/Compare 3 output Polarity */
#define ATIM_CCER_CC3NE (1 << 10) /* Bit 10: Capture/Compare 3 Complementary output enable */
-#define ATIM_CCER_CC3NP (1 << 11) /* Bit 11: Capture/Compare 3 Complementary output Polarity */
+#define ATIM_CCER_CC3NP (1 << 11) /* Bit 11: Capture/Compare 3 Complementary output polarity */
#define ATIM_CCER_CC4E (1 << 12) /* Bit 12: Capture/Compare 4 output enable */
#define ATIM_CCER_CC4P (1 << 13) /* Bit 13: Capture/Compare 4 output Polarity */
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define ATIM_CCER_CC4NP (1 << 15) /* Bit 15: Capture/Compare 4 output Polarity */
+# define ATIM_CCER_CC4NP (1 << 15) /* Bit 15: Capture/Compare 4 Complementary output polarity */
+#elif defined(CONFIG_STM32_STM32F30XX)
+# define ATIM_CCER_CC4NP (1 << 15) /* Bit 15: Capture/Compare 4 Complementary output polarity */
+# define ATIM_CCER_CC5E (1 << 16) /* Bit 16: Capture/Compare 5 output enable */
+# define ATIM_CCER_CC5P (1 << 17) /* Bit 17: Capture/Compare 5 output Polarity */
+# define ATIM_CCER_CC6E (1 << 20) /* Bit 20: Capture/Compare 6 output enable */
+# define ATIM_CCER_CC7P (1 << 21) /* Bit 21: Capture/Compare 6 output Polarity */
+#endif
+
+/* 16-bit counter register */
+
+#define ATIM_CNT_SHIFT (0) /* Bits 0-15: Timer counter value */
+#define ATIM_CNT_MASK (0xffff << ATIM_CNT_SHIFT)
+
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CCER_UIFCPY (1 << 31) /* Bit 31: UIF copy */
#endif
/* Repetition counter register */
-#define ATIM_RCR_REP_SHIFT (0) /* Bits 7-0: Repetition Counter Value */
-#define ATIM_RCR_REP_MASK (0xff << ATIM_RCR_REP_SHIFT)
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_RCR_REP_SHIFT (0) /* Bits 0-15: Repetition Counter Value */
+# define ATIM_RCR_REP_MASK (0xffff << ATIM_RCR_REP_SHIFT)
+
+# define ATIM_RCR_REP_MAX 32768 /* REVISIT */
+#else
+# define ATIM_RCR_REP_SHIFT (0) /* Bits 0-7: Repetition Counter Value */
+# define ATIM_RCR_REP_MASK (0xff << ATIM_RCR_REP_SHIFT)
+
+# define ATIM_RCR_REP_MAX 128
+#endif
+
+/* Capture/compare registers (CCR) */
-#define ATIM_RCR_REP_MAX 128
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_CCR5_GC5C1 (1 << 29) /* Bit 29: Group Channel 5 and Channel 1 */
+# define ATIM_CCR5_GC5C2 (1 << 30) /* Bit 30: Group Channel 5 and Channel 2 */
+# define ATIM_CCR5_GC5C3 (1 << 31) /* Bit 31: Group Channel 5 and Channel 3 */
+#endif
+
+#define ATIM_CCR_MASK (0xffff)
/* Break and dead-time register */
@@ -686,13 +882,54 @@
#define ATIM_BDTR_AOE (1 << 14) /* Bit 14: Automatic Output enable */
#define ATIM_BDTR_MOE (1 << 15) /* Bit 15: Main Output enable */
+#ifdef CONFIG_STM32_STM32F30XX
+# define ATIM_BDTR_BKF_SHIFT (16) /* Bits 16-19: Break filter */
+# define ATIM_BDTR_BKF_MASK (15 << ATIM_BDTR_BKF_SHIFT)
+# define ATIM_BDTR_BKF_NOFILT (0 << ATIM_BDTR_BKF_SHIFT) /* 0000: No filter, BRK acts asynchronously */
+# define ATIM_BDTR_BKF_FCKINT2 (1 << ATIM_BDTR_BKF_SHIFT) /* 0001: fSAMPLING=fCK_INT, N=2 */
+# define ATIM_BDTR_BKF_FCKINT4 (2 << ATIM_BDTR_BKF_SHIFT) /* 0010: fSAMPLING=fCK_INT, N=4 */
+# define ATIM_BDTR_BKF_FCKINT8 (3 << ATIM_BDTR_BKF_SHIFT) /* 0011: fSAMPLING=fCK_INT, N=8 */
+# define ATIM_BDTR_BKF_FDTSd26 (4 << ATIM_BDTR_BKF_SHIFT) /* 0100: fSAMPLING=fDTS/2, N=6 */
+# define ATIM_BDTR_BKF_FDTSd28 (5 << ATIM_BDTR_BKF_SHIFT) /* 0101: fSAMPLING=fDTS/2, N=8 */
+# define ATIM_BDTR_BKF_FDTSd36 (6 << ATIM_BDTR_BKF_SHIFT) /* 0110: fSAMPLING=fDTS/4, N=6 */
+# define ATIM_BDTR_BKF_FDTSd38 (7 << ATIM_BDTR_BKF_SHIFT) /* 0111: fSAMPLING=fDTS/4, N=8 */
+# define ATIM_BDTR_BKF_FDTSd86 (8 << ATIM_BDTR_BKF_SHIFT) /* 1000: fSAMPLING=fDTS/8, N=6 */
+# define ATIM_BDTR_BKF_FDTSd88 (9 << ATIM_BDTR_BKF_SHIFT) /* 1001: fSAMPLING=fDTS/8, N=8 */
+# define ATIM_BDTR_BKF_FDTSd165 (10 << ATIM_BDTR_BKF_SHIFT) /* 1010: fSAMPLING=fDTS/16, N=5 */
+# define ATIM_BDTR_BKF_FDTSd166 (11 << ATIM_BDTR_BKF_SHIFT) /* 1011: fSAMPLING=fDTS/16, N=6 */
+# define ATIM_BDTR_BKF_FDTSd168 (12 << ATIM_BDTR_BKF_SHIFT) /* 1100: fSAMPLING=fDTS/16, N=8 */
+# define ATIM_BDTR_BKF_FDTSd325 (13 << ATIM_BDTR_BKF_SHIFT) /* 1101: fSAMPLING=fDTS/32, N=5 */
+# define ATIM_BDTR_BKF_FDTSd326 (14 << ATIM_BDTR_BKF_SHIFT) /* 1110: fSAMPLING=fDTS/32, N=6 */
+# define ATIM_BDTR_BKF_FDTSd328 (15 << ATIM_BDTR_BKF_SHIFT) /* 1111: fSAMPLING=fDTS/32, N=8 */
+# define ATIM_BDTR_BK2F_SHIFT (20) /* Bits 20-23: Break 2 filter */
+# define ATIM_BDTR_BK2F_MASK (15 << ATIM_BDTR_BK2F_SHIFT)
+# define ATIM_BDTR_BK2F_NOFILT (0 << ATIM_BDTR_BK2F_SHIFT) /* 0000: No filter, BRK 2 acts asynchronously */
+# define ATIM_BDTR_BK2F_FCKINT2 (1 << ATIM_BDTR_BK2F_SHIFT) /* 0001: fSAMPLING=fCK_INT, N=2 */
+# define ATIM_BDTR_BK2F_FCKINT4 (2 << ATIM_BDTR_BK2F_SHIFT) /* 0010: fSAMPLING=fCK_INT, N=4 */
+# define ATIM_BDTR_BK2F_FCKINT8 (3 << ATIM_BDTR_BK2F_SHIFT) /* 0011: fSAMPLING=fCK_INT, N=8 */
+# define ATIM_BDTR_BK2F_FDTSd26 (4 << ATIM_BDTR_BK2F_SHIFT) /* 0100: fSAMPLING=fDTS/2, N=6 */
+# define ATIM_BDTR_BK2F_FDTSd28 (5 << ATIM_BDTR_BK2F_SHIFT) /* 0101: fSAMPLING=fDTS/2, N=8 */
+# define ATIM_BDTR_BK2F_FDTSd36 (6 << ATIM_BDTR_BK2F_SHIFT) /* 0110: fSAMPLING=fDTS/4, N=6 */
+# define ATIM_BDTR_BK2F_FDTSd38 (7 << ATIM_BDTR_BK2F_SHIFT) /* 0111: fSAMPLING=fDTS/4, N=8 */
+# define ATIM_BDTR_BK2F_FDTSd86 (8 << ATIM_BDTR_BK2F_SHIFT) /* 1000: fSAMPLING=fDTS/8, N=6 */
+# define ATIM_BDTR_BK2F_FDTSd88 (9 << ATIM_BDTR_BK2F_SHIFT) /* 1001: fSAMPLING=fDTS/8, N=8 */
+# define ATIM_BDTR_BK2F_FDTSd165 (10 << ATIM_BDTR_BK2F_SHIFT) /* 1010: fSAMPLING=fDTS/16, N=5 */
+# define ATIM_BDTR_BK2F_FDTSd166 (11 << ATIM_BDTR_BK2F_SHIFT) /* 1011: fSAMPLING=fDTS/16, N=6 */
+# define ATIM_BDTR_BK2F_FDTSd168 (12 << ATIM_BDTR_BK2F_SHIFT) /* 1100: fSAMPLING=fDTS/16, N=8 */
+# define ATIM_BDTR_BK2F_FDTSd325 (13 << ATIM_BDTR_BK2F_SHIFT) /* 1101: fSAMPLING=fDTS/32, N=5 */
+# define ATIM_BDTR_BK2F_FDTSd326 (14 << ATIM_BDTR_BK2F_SHIFT) /* 1110: fSAMPLING=fDTS/32, N=6 */
+# define ATIM_BDTR_BK2F_FDTSd328 (15 << ATIM_BDTR_BK2F_SHIFT) /* 1111: fSAMPLING=fDTS/32, N=8 */
+# define ATIM_BDTR_BK2E (1 << 24) /* Bit 24: Break 2 enable */
+# define ATIM_BDTR_BK2P (1 << 1525 /* Bit 25:Break 2 polarity */
+#endif
+
/* DMA control register */
+#define ATIM_DCR_DBA_SHIFT (0) /* Bits 4-0: DMA Base Address */
+#define ATIM_DCR_DBA_MASK (0x1f << ATIM_DCR_DBA_SHIFT)
#define ATIM_DCR_DBL_SHIFT (8) /* Bits 12-8: DMA Burst Length */
#define ATIM_DCR_DBL_MASK (0x1f << ATIM_DCR_DBL_SHIFT)
# define ATIM_DCR_DBL(n) (((n)-1) << ATIM_DCR_DBL_SHIFT) /* n transfers, n = 1..18 */
-#define ATIM_DCR_DBA_SHIFT (0) /* Bits 4-0: DMA Base Address */
-#define ATIM_DCR_DBA_MASK (0x1f << ATIM_DCR_DBA_SHIFT)
/* Control register 1 (TIM2-5 and TIM9-14) */
@@ -714,10 +951,16 @@
# define GTIM_CR1_2TCKINT (1 << GTIM_CR1_CKD_SHIFT) /* 01: tDTS = 2 x tCK_INT */
# define GTIM_CR1_4TCKINT (2 << GTIM_CR1_CKD_SHIFT) /* 10: tDTS = 4 x tCK_INT */
-/* Control register 2 (TIM2-5 and TIM9/12 only) */
+#ifdef CONFIG_STM32_STM32F30XX
+# define GTIM_CR1_UIFREMAP (1 << 11) /* Bit 11: UIF status bit remapping */
+#endif
+
+/* Control register 2 (TIM2-5, TIM9-12, and TIM15-17 only) */
-#define GTIM_CR2_CCDS (1 << 3) /* Bit 3: Capture/Compare DMA Selection (TIM2-5 only) */
-#define GTIM_CR2_MMS_SHIFT (4) /* Bits 6-4: Master Mode Selection */
+#define GTIM_CR2_CCPC (1 << 0) /* Bit 0: Capture/compare preloaded control (TIM15-17 only) */
+#define GTIM_CR2_CCUS (1 << 2) /* Bit 2: Capture/compare control update selection (TIM15-17 only) */
+#define GTIM_CR2_CCDS (1 << 3) /* Bit 3: Capture/Compare DMA Selection (TIM2-5,1,&16 only) */
+#define GTIM_CR2_MMS_SHIFT (4) /* Bits 6-4: Master Mode Selection (not TIM16) */
#define GTIM_CR2_MMS_MASK (7 << GTIM_CR2_MMS_SHIFT)
# define GTIM_CR2_RESET (0 << GTIM_CR2_MMS_SHIFT) /* 000: Reset */
# define GTIM_CR2_ENAB (1 << GTIM_CR2_MMS_SHIFT) /* 001: Enable */
@@ -725,11 +968,14 @@
# define GTIM_CR2_CMPP (3 << GTIM_CR2_MMS_SHIFT) /* 011: Compare Pulse */
# define GTIM_CR2_CMP1 (4 << GTIM_CR2_MMS_SHIFT) /* 100: Compare - OC1REF signal is used as trigger output (TRGO) */
# define GTIM_CR2_CMP2 (5 << GTIM_CR2_MMS_SHIFT) /* 101: Compare - OC2REF signal is used as trigger output (TRGO) */
-# define GTIM_CR2_CMP3 (6 << GTIM_CR2_MMS_SHIFT) /* 110: Compare - OC3REF signal is used as trigger output (TRGO, TIM2-5 only) */
-# define GTIM_CR2_CMP4 (7 << GTIM_CR2_MMS_SHIFT) /* 111: Compare - OC4REF signal is used as trigger output (TRGO, TIM2-5 only) */
-#define GTIM_CR2_TI1S (1 << 7) /* Bit 7: TI1 Selection */
+# define GTIM_CR2_CMP3 (6 << GTIM_CR2_MMS_SHIFT) /* 110: Compare - OC3REF signal is used as trigger output (TRGO, TIM2-5 and TIM15 only) */
+# define GTIM_CR2_CMP4 (7 << GTIM_CR2_MMS_SHIFT) /* 111: Compare - OC4REF signal is used as trigger output (TRGO, TIM2-5 and TIM15 only) */
+#define GTIM_CR2_TI1S (1 << 7) /* Bit 7: TI1 Selection (not TIM16) */
+#define GTIM_CR2_OIS1 (1 << 8) /* Bit 8: COutput Idle state 1 (OC1 output) (TIM15-17 only) */
+#define GTIM_CR2_OIS1N (1 << 9) /* Bit 9: Output Idle state 1 (OC1N output) (TIM15-17 only) */
+#define GTIM_CR2_OIS2 (1 << 10) /* Bit 10: Output idle state 2 (OC2 output) (TIM15 only) */
-/* Slave mode control register (TIM2-5 only) */
+/* Slave mode control register (TIM2-5 and TIM15 only) */
#define GTIM_SMCR_SMS_SHIFT (0) /* Bits 2-0: Slave Mode Selection */
#define GTIM_SMCR_SMS_MASK (7 << GTIM_SMCR_SMS_SHIFT)
@@ -752,25 +998,25 @@
# define GTIM_SMCR_TI2FP2 (6 << GTIM_SMCR_TS_SHIFT) /* 110: Filtered Timer Input 2 (TI2FP2) */
# define GTIM_SMCR_ETRF (7 << GTIM_SMCR_TS_SHIFT) /* 111: External Trigger input (ETRF) */
#define GTIM_SMCR_MSM (1 << 7) /* Bit 7: Master/Slave mode */
-#define GTIM_SMCR_ETF_SHIFT (8) /* Bits 11-8: External Trigger Filter */
+#define GTIM_SMCR_ETF_SHIFT (8) /* Bits 11-8: External Trigger Filter (not TIM15) */
#define GTIM_SMCR_ETF_MASK (0x0f << GTIM_SMCR_ETF_SHIFT)
-# define GTIM_SMCR_NOFILT (0 << GTIM_SMCR_ETF_SHIFT) /* 0000: No filter, sampling is done at fDTS */
-# define GTIM_SMCR_FCKINT2 (1 << GTIM_SMCR_ETF_SHIFT) /* 0001: fSAMPLING=fCK_INT, N=2 */
-# define GTIM_SMCR_FCKINT4 (2 << GTIM_SMCR_ETF_SHIFT) /* 0010: fSAMPLING=fCK_INT, N=4 */
-# define GTIM_SMCR_FCKINT8 (3 << GTIM_SMCR_ETF_SHIFT) /* 0011: fSAMPLING=fCK_INT, N=8 */
-# define GTIM_SMCR_FDTSd26 (4 << GTIM_SMCR_ETF_SHIFT) /* 0100: fSAMPLING=fDTS/2, N=6 */
-# define GTIM_SMCR_FDTSd28 (5 << GTIM_SMCR_ETF_SHIFT) /* 0101: fSAMPLING=fDTS/2, N=8 */
-# define GTIM_SMCR_FDTSd36 (6 << GTIM_SMCR_ETF_SHIFT) /* 0110: fSAMPLING=fDTS/4, N=6 */
-# define GTIM_SMCR_FDTSd38 (7 << GTIM_SMCR_ETF_SHIFT) /* 0111: fSAMPLING=fDTS/4, N=8 */
-# define GTIM_SMCR_FDTSd86 (8 << GTIM_SMCR_ETF_SHIFT) /* 1000: fSAMPLING=fDTS/8, N=6 */
-# define GTIM_SMCR_FDTSd88 (9 << GTIM_SMCR_ETF_SHIFT) /* 1001: fSAMPLING=fDTS/8, N=8 */
+# define GTIM_SMCR_NOFILT (0 << GTIM_SMCR_ETF_SHIFT) /* 0000: No filter, sampling is done at fDTS */
+# define GTIM_SMCR_FCKINT2 (1 << GTIM_SMCR_ETF_SHIFT) /* 0001: fSAMPLING=fCK_INT, N=2 */
+# define GTIM_SMCR_FCKINT4 (2 << GTIM_SMCR_ETF_SHIFT) /* 0010: fSAMPLING=fCK_INT, N=4 */
+# define GTIM_SMCR_FCKINT8 (3 << GTIM_SMCR_ETF_SHIFT) /* 0011: fSAMPLING=fCK_INT, N=8 */
+# define GTIM_SMCR_FDTSd26 (4 << GTIM_SMCR_ETF_SHIFT) /* 0100: fSAMPLING=fDTS/2, N=6 */
+# define GTIM_SMCR_FDTSd28 (5 << GTIM_SMCR_ETF_SHIFT) /* 0101: fSAMPLING=fDTS/2, N=8 */
+# define GTIM_SMCR_FDTSd36 (6 << GTIM_SMCR_ETF_SHIFT) /* 0110: fSAMPLING=fDTS/4, N=6 */
+# define GTIM_SMCR_FDTSd38 (7 << GTIM_SMCR_ETF_SHIFT) /* 0111: fSAMPLING=fDTS/4, N=8 */
+# define GTIM_SMCR_FDTSd86 (8 << GTIM_SMCR_ETF_SHIFT) /* 1000: fSAMPLING=fDTS/8, N=6 */
+# define GTIM_SMCR_FDTSd88 (9 << GTIM_SMCR_ETF_SHIFT) /* 1001: fSAMPLING=fDTS/8, N=8 */
# define GTIM_SMCR_FDTSd165 (10 << GTIM_SMCR_ETF_SHIFT) /* 1010: fSAMPLING=fDTS/16, N=5 */
# define GTIM_SMCR_FDTSd166 (11 << GTIM_SMCR_ETF_SHIFT) /* 1011: fSAMPLING=fDTS/16, N=6 */
# define GTIM_SMCR_FDTSd168 (12 << GTIM_SMCR_ETF_SHIFT) /* 1100: fSAMPLING=fDTS/16, N=8 */
# define GTIM_SMCR_FDTSd325 (13 << GTIM_SMCR_ETF_SHIFT) /* 1101: fSAMPLING=fDTS/32, N=5 */
# define GTIM_SMCR_FDTSd326 (14 << GTIM_SMCR_ETF_SHIFT) /* 1110: fSAMPLING=fDTS/32, N=6 */
# define GTIM_SMCR_FDTSd328 (15 << GTIM_SMCR_ETF_SHIFT) /* 1111: fSAMPLING=fDTS/32, N=8 */
-#define GTIM_SMCR_ETPS_SHIFT (12) /* Bits 13-12: External Trigger Prescaler */
+#define GTIM_SMCR_ETPS_SHIFT (12) /* Bits 13-12: External Trigger Prescaler (not TIM15) */
#define GTIM_SMCR_ETPS_MASK (3 << GTIM_SMCR_ETPS_SHIFT)
# define GTIM_SMCR_PSCOFF (0 << GTIM_SMCR_ETPS_SHIFT) /* 00: Prescaler OFF */
# define GTIM_SMCR_ETRPd2 (1 << GTIM_SMCR_ETPS_SHIFT) /* 01: ETRP frequency divided by 2 */
@@ -779,42 +1025,53 @@
#define GTIM_SMCR_ECE (1 << 14) /* Bit 14: External Clock enable */
#define GTIM_SMCR_ETP (1 << 15) /* Bit 15: External Trigger Polarity */
+#ifdef CONFIG_STM32_STM32F30XX
+# define GTIM_CR1_SMS (1 << 16) /* Bit 16: Slave mode selection - bit 3 */
+#endif
+
/* DMA/Interrupt enable register (TIM2-5 and TIM9-14) */
#define GTIM_DIER_UIE (1 << 0) /* Bit 0: Update interrupt enable */
#define GTIM_DIER_CC1IE (1 << 1) /* Bit 1: Capture/Compare 1 interrupt enable */
-#define GTIM_DIER_CC2IE (1 << 2) /* Bit 2: Capture/Compare 2 interrupt enable (TIM2-5,9,&12 only) */
+#define GTIM_DIER_CC2IE (1 << 2) /* Bit 2: Capture/Compare 2 interrupt enable (TIM2-5,9,12,&15 only) */
#define GTIM_DIER_CC3IE (1 << 3) /* Bit 3: Capture/Compare 3 interrupt enable (TIM2-5 only) */
#define GTIM_DIER_CC4IE (1 << 4) /* Bit 4: Capture/Compare 4 interrupt enable (TIM2-5 only) */
+#define GTIM_DIER_COMIE (1 << 5) /* Bit 5: COM interrupt enable (TIM15-17 only) */
#define GTIM_DIER_TIE (1 << 6) /* Bit 6: Trigger interrupt enable (TIM2-5,9,&12 only) */
-#define GTIM_DIER_UDE (1 << 8) /* Bit 8: Update DMA request enable (TIM2-5 only) */
-#define GTIM_DIER_CC1DE (1 << 9) /* Bit 9: Capture/Compare 1 DMA request enable (TIM2-5 only) */
-#define GTIM_DIER_CC2DE (1 << 10) /* Bit 10: Capture/Compare 2 DMA request enable (TIM2-5 only) */
+#define GTIM_DIER_BIE (1 << 7) /* Bit 7: Break interrupt enable (TIM15-17 only) */
+#define GTIM_DIER_UDE (1 << 8) /* Bit 8: Update DMA request enable (TIM2-5&15-17 only) */
+#define GTIM_DIER_CC1DE (1 << 9) /* Bit 9: Capture/Compare 1 DMA request enable (TIM2-5&15-17 only) */
+#define GTIM_DIER_CC2DE (1 << 10) /* Bit 10: Capture/Compare 2 DMA request enable (TIM2-5&15 only) */
#define GTIM_DIER_CC3DE (1 << 11) /* Bit 11: Capture/Compare 3 DMA request enable (TIM2-5 only) */
#define GTIM_DIER_CC4DE (1 << 12) /* Bit 12: Capture/Compare 4 DMA request enable (TIM2-5 only) */
-#define GTIM_DIER_TDE (1 << 14) /* Bit 14: Trigger DMA request enable (TIM2-5 only) */
+#define GTIM_DIER_COMDE (1 << 13) /* Bit 13: COM DMA request enable (TIM15-17 only) */
+#define GTIM_DIER_TDE (1 << 14) /* Bit 14: Trigger DMA request enable (TIM2-5&15-17 only) */
/* Status register */
#define GTIM_SR_UIF (1 << 0) /* Bit 0: Update interrupt flag */
-#define GTIM_SR_CC1IF (1 << 1) /* Bit 1: Capture/compare 1 interrupt Flag */
-#define GTIM_SR_CC2IF (1 << 2) /* Bit 2: Capture/Compare 2 interrupt Flag (TIM2-5,9,&12 only) */
-#define GTIM_SR_CC3IF (1 << 3) /* Bit 3: Capture/Compare 3 interrupt Flag (TIM2-5 only) */
-#define GTIM_SR_CC4IF (1 << 4) /* Bit 4: Capture/Compare 4 interrupt Flag (TIM2-5 only) */
-#define GTIM_SR_TIF (1 << 6) /* Bit 6: Trigger interrupt Flag (TIM2-5,9,&12 only) */
-#define GTIM_SR_CC1OF (1 << 9) /* Bit 9: Capture/Compare 1 Overcapture Flag */
-#define GTIM_SR_CC2OF (1 << 10) /* Bit 10: Capture/Compare 2 Overcapture Flag (TIM2-5,9,&12 only) */
-#define GTIM_SR_CC3OF (1 << 11) /* Bit 11: Capture/Compare 3 Overcapture Flag (TIM2-5 only) */
-#define GTIM_SR_CC4OF (1 << 12) /* Bit 12: Capture/Compare 4 Overcapture Flag (TIM2-5 only) */
+#define GTIM_SR_CC1IF (1 << 1) /* Bit 1: Capture/compare 1 interrupt flag */
+#define GTIM_SR_CC2IF (1 << 2) /* Bit 2: Capture/Compare 2 interrupt flag (TIM2-5,9,12,&15 only) */
+#define GTIM_SR_CC3IF (1 << 3) /* Bit 3: Capture/Compare 3 interrupt flag (TIM2-5 only) */
+#define GTIM_SR_CC4IF (1 << 4) /* Bit 4: Capture/Compare 4 interrupt flag (TIM2-5 only) */
+#define GTIM_SR_COMIF (1 << 5) /* Bit 5: COM interrupt flag (TIM15-17 only) */
+#define GTIM_SR_TIF (1 << 6) /* Bit 6: Trigger interrupt Flag (TIM2-5,9,12&15-17 only) */
+#define GTIM_SR_BIF (1 << 7) /* Bit 7: Break interrupt flag (TIM15-17 only) */
+#define GTIM_SR_CC1OF (1 << 9) /* Bit 9: Capture/Compare 1 Overcapture flag */
+#define GTIM_SR_CC2OF (1 << 10) /* Bit 10: Capture/Compare 2 Overcapture flag (TIM2-5,9,12&15 only) */
+#define GTIM_SR_CC3OF (1 << 11) /* Bit 11: Capture/Compare 3 Overcapture flag (TIM2-5 only) */
+#define GTIM_SR_CC4OF (1 << 12) /* Bit 12: Capture/Compare 4 Overcapture flag (TIM2-5 only) */
/* Event generation register (TIM2-5 and TIM9-14) */
#define GTIM_EGR_UG (1 << 0) /* Bit 0: Update generation */
#define GTIM_EGR_CC1G (1 << 1) /* Bit 1: Capture/compare 1 generation */
-#define GTIM_EGR_CC2G (1 << 2) /* Bit 2: Capture/compare 2 generation (TIM2-5,9,&12 only) */
+#define GTIM_EGR_CC2G (1 << 2) /* Bit 2: Capture/compare 2 generation (TIM2-5,9,12,&15 only) */
#define GTIM_EGR_CC3G (1 << 3) /* Bit 3: Capture/compare 3 generation (TIM2-5 only) */
#define GTIM_EGR_CC4G (1 << 4) /* Bit 4: Capture/compare 4 generation (TIM2-5 only) */
-#define GTIM_EGR_TG (1 << 6) /* Bit 6: Trigger generation (TIM2-5,9,&12 only) */
+#define GTIM_EGR_COMIG (1 << 5) /* Bit 5: Capture/Compare control update generation (TIM15-17 only) */
+#define GTIM_EGR_TG (1 << 6) /* Bit 6: Trigger generation (TIM2-5,9,12&16-17 only) */
+#define GTIM_EGR_BG (1 << 7) /* Bit 7: Break generation (TIM15-17 only) */
/* Capture/compare mode register 1 - Output compare mode (TIM2-5 and TIM9-14) */
@@ -837,6 +1094,11 @@
/* (See common CCMR Output Compare Mode definitions below) */
#define GTIM_CCMR1_OC2CE (1 << 15) /* Bit 15: Output Compare 2 Clear Enable */
+#ifdef CONFIG_STM32_STM32F30XX
+# define GTIM_CCMR1_OC1M (1 << 16) /* Bit 16: Output Compare 1 mode - bit 3 */
+# define GTIM_CCMR1_OC2M (1 << 24) /* Bit 24: Output Compare 2 mode - bit 3 */
+#endif
+
/* Common CCMR (unshifted) Capture/Compare Selection bit-field definitions */
#define GTIM_CCMR_CCS_CCOUT (0) /* 00: CCx channel output */
@@ -939,39 +1201,77 @@
/* Capture/compare enable register (TIM2-5 and TIM9-14) */
#define GTIM_CCER_CC1E (1 << 0) /* Bit 0: Capture/Compare 1 output enable */
-#define GTIM_CCER_CC1P (1 << 1) /* Bit 1: Capture/Compare 1 output Polarity */
-
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define GTIM_CCER_CC1NP (1 << 3) /* Bit 3: Capture/Compare 1 output Polarity */
-#endif
-
+#define GTIM_CCER_CC1P (1 << 1) /* Bit 1: Capture/Compare 1 output polarity */
+#define GTIM_CCER_CC1NE (1 << 2) /* Bit 2: Capture/Compare 1 complementary output enable (TIM15-17) */
+#define GTIM_CCER_CC1NP (1 << 3) /* Bit 3: Capture/Compare 1 output Polarity (F2,F3,F4 and TIM15-17) */
#define GTIM_CCER_CC2E (1 << 4) /* Bit 4: Capture/Compare 2 output enable (TIM2-5,9&12 only) */
-#define GTIM_CCER_CC2P (1 << 5) /* Bit 5: Capture/Compare 2 output Polarity (TIM2-5,9&12 only) */
-
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define GTIM_CCER_CC2NP (1 << 7) /* Bit 7: Capture/Compare 2 output Polarity (TIM2-5,9&12 only) */
-#endif
-
+#define GTIM_CCER_CC2P (1 << 5) /* Bit 5: Capture/Compare 2 output polarity (TIM2-5,9&12 only) */
+#define GTIM_CCER_CC2NE (1 << 6) /* Bit 6: CC2NE: Capture/Compare 2 complementary output enable (TIM15) */
+#define GTIM_CCER_CC2NP (1 << 7) /* Bit 7: Capture/Compare 2 output Polarity (F2,F3,F4 and TIM2-5,9,12&15 only) */
#define GTIM_CCER_CC3E (1 << 8) /* Bit 8: Capture/Compare 3 output enable (TIM2-5 only) */
#define GTIM_CCER_CC3P (1 << 9) /* Bit 9: Capture/Compare 3 output Polarity (TIM2-5 only) */
-
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define GTIM_CCER_CC3NP (1 << 11) /* Bit 11: Capture/Compare 3 output Polarity (TIM2-5 only) */
-#endif
-
+#define GTIM_CCER_CC3NP (1 << 11) /* Bit 11: Capture/Compare 3 output Polarity (F2,F4 and TIM2-5 only) */
#define GTIM_CCER_CC4E (1 << 12) /* Bit 12: Capture/Compare 4 output enable (TIM2-5 only) */
#define GTIM_CCER_CC4P (1 << 13) /* Bit 13: Capture/Compare 4 output Polarity (TIM2-5 only) */
+#define GTIM_CCER_CC4NP (1 << 15) /* Bit 15: Capture/Compare 4 output Polarity (F2,F4 and TIM2-5 only) */
-#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-# define GTIM_CCER_CC4NP (1 << 15) /* Bit 15: Capture/Compare 4 output Polarity (TIM2-5 only) */
+/* 16-bit counter register */
+
+#define GTIM_CNT_SHIFT (0) /* Bits 0-15: Timer counter value */
+#define GTIM_CNT_MASK (0xffff << ATIM_CNT_SHIFT)
+
+#ifdef CONFIG_STM32_STM32F30XX
+# define GTIM_CCER_UIFCPY (1 << 31) /* Bit 31: UIF copy */
#endif
+/* Repitition counter (TIM15-17 only) */
+
+#define GTIM_RCR_REP_SHIFT (0) /* Bits 0-7: Repetition Counter Value */
+#define GTIM_RCR_REP_MASK (0xff << GTIM_RCR_REP_SHIFT)
+
+#define GTIM_RCR_REP_MAX 128
+
+/* Break and dead-time register (TIM15-17 only */
+
+#define GTIM_BDTR_DTG_SHIFT (0) /* Bits 7:0 [7:0]: Dead-Time Generator set-up */
+#define GTIM_BDTR_DTG_MASK (0xff << GTIM_BDTR_DTG_SHIFT)
+#define GTIM_BDTR_LOCK_SHIFT (8) /* Bits 9:8 [1:0]: Lock Configuration */
+#define GTIM_BDTR_LOCK_MASK (3 << GTIM_BDTR_LOCK_SHIFT)
+# define GTIM_BDTR_LOCKOFF (0 << GTIM_BDTR_LOCK_SHIFT) /* 00: LOCK OFF - No bit is write protected */
+# define GTIM_BDTR_LOCK1 (1 << GTIM_BDTR_LOCK_SHIFT) /* 01: LOCK Level 1 protection */
+# define GTIM_BDTR_LOCK2 (2 << GTIM_BDTR_LOCK_SHIFT) /* 10: LOCK Level 2 protection */
+# define GTIM_BDTR_LOCK3 (3 << GTIM_BDTR_LOCK_SHIFT) /* 11: LOCK Level 3 protection */ */
+#define GTIM_BDTR_OSSI (1 << 10) /* Bit 10: Off-State Selection for Idle mode */
+#define GTIM_BDTR_OSSR (1 << 11) /* Bit 11: Off-State Selection for Run mode */
+#define GTIM_BDTR_BKE (1 << 12) /* Bit 12: Break enable */
+#define GTIM_BDTR_BKP (1 << 13) /* Bit 13: Break Polarity */
+#define GTIM_BDTR_AOE (1 << 14) /* Bit 14: Automatic Output enable */
+#define GTIM_BDTR_MOE (1 << 15) /* Bit 15: Main Output enable */
+#define GTIM_BDTR_BKF_SHIFT (16) /* Bits 16-19: Break filter */
+#define GTIM_BDTR_BKF_MASK (15 << GTIM_BDTR_BKF_SHIFT)
+# define GTIM_BDTR_BKF_NOFILT (0 << GTIM_BDTR_BKF_SHIFT) /* 0000: No filter, BRK acts asynchronously */
+# define GTIM_BDTR_BKF_FCKINT2 (1 << GTIM_BDTR_BKF_SHIFT) /* 0001: fSAMPLING=fCK_INT, N=2 */
+# define GTIM_BDTR_BKF_FCKINT4 (2 << GTIM_BDTR_BKF_SHIFT) /* 0010: fSAMPLING=fCK_INT, N=4 */
+# define GTIM_BDTR_BKF_FCKINT8 (3 << GTIM_BDTR_BKF_SHIFT) /* 0011: fSAMPLING=fCK_INT, N=8 */
+# define GTIM_BDTR_BKF_FDTSd26 (4 << GTIM_BDTR_BKF_SHIFT) /* 0100: fSAMPLING=fDTS/2, N=6 */
+# define GTIM_BDTR_BKF_FDTSd28 (5 << GTIM_BDTR_BKF_SHIFT) /* 0101: fSAMPLING=fDTS/2, N=8 */
+# define GTIM_BDTR_BKF_FDTSd36 (6 << GTIM_BDTR_BKF_SHIFT) /* 0110: fSAMPLING=fDTS/4, N=6 */
+# define GTIM_BDTR_BKF_FDTSd38 (7 << GTIM_BDTR_BKF_SHIFT) /* 0111: fSAMPLING=fDTS/4, N=8 */
+# define GTIM_BDTR_BKF_FDTSd86 (8 << GTIM_BDTR_BKF_SHIFT) /* 1000: fSAMPLING=fDTS/8, N=6 */
+# define GTIM_BDTR_BKF_FDTSd88 (9 << GTIM_BDTR_BKF_SHIFT) /* 1001: fSAMPLING=fDTS/8, N=8 */
+# define GTIM_BDTR_BKF_FDTSd165 (10 << GTIM_BDTR_BKF_SHIFT) /* 1010: fSAMPLING=fDTS/16, N=5 */
+# define GTIM_BDTR_BKF_FDTSd166 (11 << GTIM_BDTR_BKF_SHIFT) /* 1011: fSAMPLING=fDTS/16, N=6 */
+# define GTIM_BDTR_BKF_FDTSd168 (12 << GTIM_BDTR_BKF_SHIFT) /* 1100: fSAMPLING=fDTS/16, N=8 */
+# define GTIM_BDTR_BKF_FDTSd325 (13 << GTIM_BDTR_BKF_SHIFT) /* 1101: fSAMPLING=fDTS/32, N=5 */
+# define GTIM_BDTR_BKF_FDTSd326 (14 << GTIM_BDTR_BKF_SHIFT) /* 1110: fSAMPLING=fDTS/32, N=6 */
+# define GTIM_BDTR_BKF_FDTSd328 (15 << GTIM_BDTR_BKF_SHIFT) /* 1111: fSAMPLING=fDTS/32, N=8 */
+
/* DMA control register */
-#define GTIM_DCR_DBL_SHIFT (8) /* Bits 12-8: DMA Burst Length */
-#define GTIM_DCR_DBL_MASK (0x1f << GTIM_DCR_DBL_SHIFT)
#define GTIM_DCR_DBA_SHIFT (0) /* Bits 4-0: DMA Base Address */
#define GTIM_DCR_DBA_MASK (0x1f << GTIM_DCR_DBA_SHIFT)
+#define GTIM_DCR_DBL_SHIFT (8) /* Bits 12-8: DMA Burst Length */
+#define GTIM_DCR_DBL_MASK (0x1f << GTIM_DCR_DBL_SHIFT)
/* Timer 2/5 option register */
@@ -996,6 +1296,17 @@
# define TIM11_OR_TI1_HSERTC (3 << TIM11_OR_TI1_RMP_SHIFT) /* 11: TIM11_CH1 input connected to HSE_RTC clock */
#endif
+/* Timer 16 Option Register */
+
+#ifdef CONFIG_STM32_STM32F30XX
+# define TIM16_OR_RMP_SHIFT (0) /* Bits 0-1: Timer 16 input 1 connection */
+# define TIM16_OR_RMP_MASK (3 << TIM16_OR_RMP_SHIFT)
+# define TIM16_OR_RMP_GPRIO (3 << TIM16_OR_RMP_SHIFT) /* TIM16 TI1 is connected to GPIO */
+# define TIM16_OR_RMP_RTC (3 << TIM16_OR_RMP_SHIFT) /* TIM16 TI1 is connected to RTC_clock */
+# define TIM16_OR_RMP_HSEd32 (3 << TIM16_OR_RMP_SHIFT) /* TIM16 TI1 is connected to HSE/32 */
+# define TIM16_OR_RMP_MCO (3 << TIM16_OR_RMP_SHIFT) /* TIM16 TI1 is connected to MCO */
+#endif
+
/* Control register 1 */
#define BTIM_CR1_CEN (1 << 0) /* Bit 0: Counter enable */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_wdg.h b/nuttx/arch/arm/src/stm32/chip/stm32_wdg.h
index 5abb5bc6d..f0f2916f4 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_wdg.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_wdg.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_wdg.h
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,85 +50,102 @@
/* Register Offsets *****************************************************************/
-#define STM32_IWDG_KR_OFFSET 0x0000 /* Key register (32-bit) */
-#define STM32_IWDG_PR_OFFSET 0x0004 /* Prescaler register (32-bit) */
-#define STM32_IWDG_RLR_OFFSET 0x0008 /* Reload register (32-bit) */
-#define STM32_IWDG_SR_OFFSET 0x000c /* Status register (32-bit) */
+#define STM32_IWDG_KR_OFFSET 0x0000 /* Key register (32-bit) */
+#define STM32_IWDG_PR_OFFSET 0x0004 /* Prescaler register (32-bit) */
+#define STM32_IWDG_RLR_OFFSET 0x0008 /* Reload register (32-bit) */
+#define STM32_IWDG_SR_OFFSET 0x000c /* Status register (32-bit) */
+#if defined(CONFIG_STM32_STM32F30XX)
+# define STM32_IWDG_WINR_OFFSET 0x000c /* Window register (32-bit) */
+#endif
-#define STM32_WWDG_CR_OFFSET 0x0000 /* Control Register (32-bit) */
-#define STM32_WWDG_CFR_OFFSET 0x0004 /* Configuration register (32-bit) */
-#define STM32_WWDG_SR_OFFSET 0x0008 /* Status register (32-bit) */
+#define STM32_WWDG_CR_OFFSET 0x0000 /* Control Register (32-bit) */
+#define STM32_WWDG_CFR_OFFSET 0x0004 /* Configuration register (32-bit) */
+#define STM32_WWDG_SR_OFFSET 0x0008 /* Status register (32-bit) */
/* Register Addresses ***************************************************************/
-#define STM32_IWDG_KR (STM32_IWDG_BASE+STM32_IWDG_KR_OFFSET)
-#define STM32_IWDG_PR (STM32_IWDG_BASE+STM32_IWDG_PR_OFFSET)
-#define STM32_IWDG_RLR (STM32_IWDG_BASE+STM32_IWDG_RLR_OFFSET)
-#define STM32_IWDG_SR (STM32_IWDG_BASE+STM32_IWDG_SR_OFFSET)
+#define STM32_IWDG_KR (STM32_IWDG_BASE+STM32_IWDG_KR_OFFSET)
+#define STM32_IWDG_PR (STM32_IWDG_BASE+STM32_IWDG_PR_OFFSET)
+#define STM32_IWDG_RLR (STM32_IWDG_BASE+STM32_IWDG_RLR_OFFSET)
+#define STM32_IWDG_SR (STM32_IWDG_BASE+STM32_IWDG_SR_OFFSET)
+#if defined(CONFIG_STM32_STM32F30XX)
+# define STM32_IWDG_WINR (STM32_IWDG_BASE+STM32_IWDG_WINR_OFFSET)
+#endif
-#define STM32_WWDG_CR (STM32_WWDG_BASE+STM32_WWDG_CR_OFFSET)
-#define STM32_WWDG_CFR (STM32_WWDG_BASE+STM32_WWDG_CFR_OFFSET)
-#define STM32_WWDG_SR (STM32_WWDG_BASE+STM32_WWDG_SR_OFFSET)
+#define STM32_WWDG_CR (STM32_WWDG_BASE+STM32_WWDG_CR_OFFSET)
+#define STM32_WWDG_CFR (STM32_WWDG_BASE+STM32_WWDG_CFR_OFFSET)
+#define STM32_WWDG_SR (STM32_WWDG_BASE+STM32_WWDG_SR_OFFSET)
/* Register Bitfield Definitions ****************************************************/
/* Key register (32-bit) */
-#define IWDG_KR_KEY_SHIFT (0) /* Bits 15-0: Key value (write only, read 0000h) */
-#define IWDG_KR_KEY_MASK (0xffff << IWDG_KR_KEY_SHIFT)
+#define IWDG_KR_KEY_SHIFT (0) /* Bits 15-0: Key value (write only, read 0000h) */
+#define IWDG_KR_KEY_MASK (0xffff << IWDG_KR_KEY_SHIFT)
-#define IWDG_KR_KEY_ENABLE (0x5555) /* Enable register access */
-#define IWDG_KR_KEY_DISABLE (0x0000) /* Disable register access */
-#define IWDG_KR_KEY_RELOAD (0xaaaa) /* Reload the counter */
-#define IWDG_KR_KEY_START (0xcccc) /* Start the watchdog */
+#define IWDG_KR_KEY_ENABLE (0x5555) /* Enable register access */
+#define IWDG_KR_KEY_DISABLE (0x0000) /* Disable register access */
+#define IWDG_KR_KEY_RELOAD (0xaaaa) /* Reload the counter */
+#define IWDG_KR_KEY_START (0xcccc) /* Start the watchdog */
/* Prescaler register (32-bit) */
-#define IWDG_PR_SHIFT (0) /* Bits 2-0: Prescaler divider */
-#define IWDG_PR_MASK (7 << IWDG_PR_SHIFT)
-# define IWDG_PR_DIV4 (0 << IWDG_PR_SHIFT) /* 000: divider /4 */
-# define IWDG_PR_DIV8 (1 << IWDG_PR_SHIFT) /* 001: divider /8 */
-# define IWDG_PR_DIV16 (2 << IWDG_PR_SHIFT) /* 010: divider /16 */
-# define IWDG_PR_DIV32 (3 << IWDG_PR_SHIFT) /* 011: divider /32 */
-# define IWDG_PR_DIV64 (4 << IWDG_PR_SHIFT) /* 100: divider /64 */
-# define IWDG_PR_DIV128 (5 << IWDG_PR_SHIFT) /* 101: divider /128 */
-# define IWDG_PR_DIV256 (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */
+#define IWDG_PR_SHIFT (0) /* Bits 2-0: Prescaler divider */
+#define IWDG_PR_MASK (7 << IWDG_PR_SHIFT)
+# define IWDG_PR_DIV4 (0 << IWDG_PR_SHIFT) /* 000: divider /4 */
+# define IWDG_PR_DIV8 (1 << IWDG_PR_SHIFT) /* 001: divider /8 */
+# define IWDG_PR_DIV16 (2 << IWDG_PR_SHIFT) /* 010: divider /16 */
+# define IWDG_PR_DIV32 (3 << IWDG_PR_SHIFT) /* 011: divider /32 */
+# define IWDG_PR_DIV64 (4 << IWDG_PR_SHIFT) /* 100: divider /64 */
+# define IWDG_PR_DIV128 (5 << IWDG_PR_SHIFT) /* 101: divider /128 */
+# define IWDG_PR_DIV256 (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */
/* Reload register (32-bit) */
-#define IWDG_RLR_RL_SHIFT (0) /* Bits11:0 RL[11:0]: Watchdog counter reload value */
-#define IWDG_RLR_RL_MASK (0x0fff << IWDG_RLR_RL_SHIFT)
+#define IWDG_RLR_RL_SHIFT (0) /* Bits11:0 RL[11:0]: Watchdog counter reload value */
+#define IWDG_RLR_RL_MASK (0x0fff << IWDG_RLR_RL_SHIFT)
-#define IWDG_RLR_MAX (0xfff)
+#define IWDG_RLR_MAX (0xfff)
/* Status register (32-bit) */
-#define IWDG_SR_PVU (1 << 0) /* Bit 0: Watchdog prescaler value update */
-#define IWDG_SR_RVU (1 << 1) /* Bit 1: Watchdog counter reload value update */
+#define IWDG_SR_PVU (1 << 0) /* Bit 0: Watchdog prescaler value update */
+#define IWDG_SR_RVU (1 << 1) /* Bit 1: Watchdog counter reload value update */
+
+#if defined(CONFIG_STM32_STM32F30XX)
+# define IWDG_SR_WVU (1 << 2) /* Bit 2: */
+#endif
+
+/* Window register (32-bit) */
+
+#if defined(CONFIG_STM32_STM32F30XX)
+# define IWDG_WINR_SHIFT (0)
+# define IWDG_WINR_MASK (0x0fff << IWDG_WINR_SHIFT)
+#endif
/* Control Register (32-bit) */
-#define WWDG_CR_T_SHIFT (0) /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */
-#define WWDG_CR_T_MASK (0x7f << WWDG_CR_T_SHIFT)
-# define WWDG_CR_T_MAX (0x3f << WWDG_CR_T_SHIFT)
-# define WWDG_CR_T_RESET (0x40 << WWDG_CR_T_SHIFT)
-#define WWDG_CR_WDGA (1 << 7) /* Bit 7: Activation bit */
+#define WWDG_CR_T_SHIFT (0) /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */
+#define WWDG_CR_T_MASK (0x7f << WWDG_CR_T_SHIFT)
+# define WWDG_CR_T_MAX (0x3f << WWDG_CR_T_SHIFT)
+# define WWDG_CR_T_RESET (0x40 << WWDG_CR_T_SHIFT)
+#define WWDG_CR_WDGA (1 << 7) /* Bit 7: Activation bit */
/* Configuration register (32-bit) */
-#define WWDG_CFR_W_SHIFT (0) /* Bits 6:0 W[6:0] 7-bit window value */
-#define WWDG_CFR_W_MASK (0x7f << WWDG_CFR_W_SHIFT)
-#define WWDG_CFR_WDGTB_SHIFT (7) /* Bits 8:7 [1:0]: Timer Base */
-#define WWDG_CFR_WDGTB_MASK (3 << WWDG_CFR_WDGTB_SHIFT)
-# define WWDG_CFR_PCLK1 (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */
-# define WWDG_CFR_PCLK1d2 (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */
-# define WWDG_CFR_PCLK1d4 (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */
-# define WWDG_CFR_PCLK1d8 (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */
-#define WWDG_CFR_EWI (1 << 9) /* Bit 9: Early Wakeup Interrupt */
+#define WWDG_CFR_W_SHIFT (0) /* Bits 6:0 W[6:0] 7-bit window value */
+#define WWDG_CFR_W_MASK (0x7f << WWDG_CFR_W_SHIFT)
+#define WWDG_CFR_WDGTB_SHIFT (7) /* Bits 8:7 [1:0]: Timer Base */
+#define WWDG_CFR_WDGTB_MASK (3 << WWDG_CFR_WDGTB_SHIFT)
+# define WWDG_CFR_PCLK1 (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */
+# define WWDG_CFR_PCLK1d2 (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */
+# define WWDG_CFR_PCLK1d4 (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */
+# define WWDG_CFR_PCLK1d8 (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */
+#define WWDG_CFR_EWI (1 << 9) /* Bit 9: Early Wakeup Interrupt */
/* Status register (32-bit) */
-#define WWDG_SR_EWIF (1 << 0) /* Bit 0: Early Wakeup Interrupt Flag */
+#define WWDG_SR_EWIF (1 << 0) /* Bit 0: Early Wakeup Interrupt Flag */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f30xxx_adc.h b/nuttx/arch/arm/src/stm32/chip/stm32f30xxx_adc.h
new file mode 100644
index 000000000..40b493d5e
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f30xxx_adc.h
@@ -0,0 +1,543 @@
+/****************************************************************************************************
+ * arch/arm/src/stm32/chip/stm32f30xxx_adc.h
+ *
+ * Copyright (C) 2009, 2011, 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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_CHIP_STM32F30XXX_ADC_H
+#define __ARCH_ARM_SRC_STM32_CHIP_STM32F30XXX_ADC_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/****************************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************************/
+
+/* Register Offsets *********************************************************************************/
+/* Register Offsets for Each ADC (ADC1, 2, 3, and 4). At offset 0x0000 for master and offset 0x0100
+ * for slave.
+ */
+
+#define STM32_ADC_ISR_OFFSET 0x0000 /* ADC interrupt and status register */
+#define STM32_ADC_IER_OFFSET 0x0004 /* ADC interrupt enable register */
+#define STM32_ADC_CR_OFFSET 0x0008 /* ADC control register */
+#define STM32_ADC_CFGR_OFFSET 0x000c /* ADC configuration register */
+#define STM32_ADC_SMPR1_OFFSET 0x0014 /* ADC sample time register 1 */
+#define STM32_ADC_SMPR2_OFFSET 0x0018 /* ADC sample time register 2 */
+#define STM32_ADC_TR1_OFFSET 0x0020 /* ADC watchdog threshold register 1 */
+#define STM32_ADC_TR2_OFFSET 0x0020 /* ADC watchdog threshold register 2 */
+#define STM32_ADC_TR3_OFFSET 0x0020 /* ADC watchdog threshold register 3 */
+#define STM32_ADC_SQR1_OFFSET 0x0030 /* ADC regular sequence register 1 */
+#define STM32_ADC_SQR2_OFFSET 0x0034 /* ADC regular sequence register 2 */
+#define STM32_ADC_SQR3_OFFSET 0x0038 /* ADC regular sequence register 3 */
+#define STM32_ADC_SQR4_OFFSET 0x003c /* ADC regular sequence register 4 */
+#define STM32_ADC_DR_OFFSET 0x0040 /* ADC regular data register */
+#define STM32_ADC_JSQR_OFFSET 0x004c /* ADC injected sequence register */
+#define STM32_ADC_OFR1_OFFSET 0x0060 /* ADC offset register 1 */
+#define STM32_ADC_OFR2_OFFSET 0x0064 /* ADC offset register 2 */
+#define STM32_ADC_OFR3_OFFSET 0x0068 /* ADC offset register 3 */
+#define STM32_ADC_OFR4_OFFSET 0x006c /* ADC data offset register 4 */
+#define STM32_ADC_JDR1_OFFSET 0x0080 /* ADC injected data register 1 */
+#define STM32_ADC_JDR2_OFFSET 0x0084 /* ADC injected data register 2 */
+#define STM32_ADC_JDR3_OFFSET 0x0088 /* ADC injected data register 3 */
+#define STM32_ADC_JDR4_OFFSET 0x008c /* ADC injected data register 4 */
+#define STM32_ADC_AWD2CR_OFFSET 0x00a0 /* ADC analog watchdog 2 configuration register */
+#define STM32_ADC_AWD3CR_OFFSET 0x00a4 /* ADC analog watchdog 3 configuration register */
+#define STM32_ADC_DIFSEL_OFFSET 0x00b0 /* ADC differential mode selection register 2 */
+#define STM32_ADC_CALFACT_OFFSET 0x00b4 /* ADC calibration factors */
+
+/* Master and Slave ADC Common Registers */
+
+#define STM32_ADC_CSR_OFFSET 0x0000 /* Common status register */
+#define STM32_ADC_CCR_OFFSET 0x0008 /* Common control register */
+#define STM32_ADC_CDR_OFFSET 0x000c /* Common regular data register for dual mode */
+
+/* Register Addresses *******************************************************************************/
+
+#define STM32_ADC1_ISR (STM32_ADC1_BASE+STM32_ADC_ISR_OFFSET)
+#define STM32_ADC1_IER (STM32_ADC1_BASE+STM32_ADC_IER_OFFSET)
+#define STM32_ADC1_CR (STM32_ADC1_BASE+STM32_ADC_CR_OFFSET)
+#define STM32_ADC1_CFGR (STM32_ADC1_BASE+STM32_ADC_CFGR_OFFSET)
+#define STM32_ADC1_SMPR1 (STM32_ADC1_BASE+STM32_ADC_SMPR1_OFFSET)
+#define STM32_ADC1_SMPR2 (STM32_ADC1_BASE+STM32_ADC_SMPR2_OFFSET)
+#define STM32_ADC1_TR1 (STM32_ADC1_BASE+STM32_ADC_TR1_OFFSET)
+#define STM32_ADC1_TR2 (STM32_ADC1_BASE+STM32_ADC_TR2_OFFSET)
+#define STM32_ADC1_TR3 (STM32_ADC1_BASE+STM32_ADC_TR3_OFFSET)
+#define STM32_ADC1_SQR1 (STM32_ADC1_BASE+STM32_ADC_SQR1_OFFSET)
+#define STM32_ADC1_SQR2 (STM32_ADC1_BASE+STM32_ADC_SQR2_OFFSET)
+#define STM32_ADC1_SQR3 (STM32_ADC1_BASE+STM32_ADC_SQR3_OFFSET)
+#define STM32_ADC1_SQR4 (STM32_ADC1_BASE+STM32_ADC_SQR4_OFFSET)
+#define STM32_ADC1_DR (STM32_ADC1_BASE+STM32_ADC_DR_OFFSET)
+#define STM32_ADC1_JSQR (STM32_ADC1_BASE+STM32_ADC_JSQR_OFFSET)
+#define STM32_ADC1_OFR1 (STM32_ADC1_BASE+STM32_ADC_OFR1_OFFSET)
+#define STM32_ADC1_OFR2 (STM32_ADC1_BASE+STM32_ADC_OFR2_OFFSET)
+#define STM32_ADC1_OFR3 (STM32_ADC1_BASE+STM32_ADC_OFR3_OFFSET)
+#define STM32_ADC1_OFR4 (STM32_ADC1_BASE+STM32_ADC_OFR4_OFFSET)
+#define STM32_ADC1_JDR1 (STM32_ADC1_BASE+STM32_ADC_JDR1_OFFSET)
+#define STM32_ADC1_JDR2 (STM32_ADC1_BASE+STM32_ADC_JDR2_OFFSET)
+#define STM32_ADC1_JDR3 (STM32_ADC1_BASE+STM32_ADC_JDR3_OFFSET)
+#define STM32_ADC1_JDR4 (STM32_ADC1_BASE+STM32_ADC_JDR4_OFFSET)
+#define STM32_ADC1_AWD2CR (STM32_ADC1_BASE+STM32_ADC_AWD2CR_OFFSET)
+#define STM32_ADC1_AWD3CR (STM32_ADC1_BASE+STM32_ADC_AWD3CR_OFFSET)
+#define STM32_ADC1_DIFSEL (STM32_ADC1_BASE+STM32_ADC_DIFSEL_OFFSET)
+#define STM32_ADC1_CALFACT (STM32_ADC1_BASE+STM32_ADC_CALFACT_OFFSET)
+
+#define STM32_ADC2_ISR (STM32_ADC2_BASE+STM32_ADC_ISR_OFFSET)
+#define STM32_ADC2_IER (STM32_ADC2_BASE+STM32_ADC_IER_OFFSET)
+#define STM32_ADC2_CR (STM32_ADC2_BASE+STM32_ADC_CR_OFFSET)
+#define STM32_ADC2_CFGR (STM32_ADC2_BASE+STM32_ADC_CFGR_OFFSET)
+#define STM32_ADC2_SMPR1 (STM32_ADC2_BASE+STM32_ADC_SMPR1_OFFSET)
+#define STM32_ADC2_SMPR2 (STM32_ADC2_BASE+STM32_ADC_SMPR2_OFFSET)
+#define STM32_ADC2_TR1 (STM32_ADC2_BASE+STM32_ADC_TR1_OFFSET)
+#define STM32_ADC2_TR2 (STM32_ADC2_BASE+STM32_ADC_TR2_OFFSET)
+#define STM32_ADC2_TR3 (STM32_ADC2_BASE+STM32_ADC_TR3_OFFSET)
+#define STM32_ADC2_SQR1 (STM32_ADC2_BASE+STM32_ADC_SQR1_OFFSET)
+#define STM32_ADC2_SQR2 (STM32_ADC2_BASE+STM32_ADC_SQR2_OFFSET)
+#define STM32_ADC2_SQR3 (STM32_ADC2_BASE+STM32_ADC_SQR3_OFFSET)
+#define STM32_ADC2_SQR4 (STM32_ADC2_BASE+STM32_ADC_SQR4_OFFSET)
+#define STM32_ADC2_DR (STM32_ADC2_BASE+STM32_ADC_DR_OFFSET)
+#define STM32_ADC2_JSQR (STM32_ADC2_BASE+STM32_ADC_JSQR_OFFSET)
+#define STM32_ADC2_OFR1 (STM32_ADC2_BASE+STM32_ADC_OFR1_OFFSET)
+#define STM32_ADC2_OFR2 (STM32_ADC2_BASE+STM32_ADC_OFR2_OFFSET)
+#define STM32_ADC2_OFR3 (STM32_ADC2_BASE+STM32_ADC_OFR3_OFFSET)
+#define STM32_ADC2_OFR4 (STM32_ADC2_BASE+STM32_ADC_OFR4_OFFSET)
+#define STM32_ADC2_JDR1 (STM32_ADC2_BASE+STM32_ADC_JDR1_OFFSET)
+#define STM32_ADC2_JDR2 (STM32_ADC2_BASE+STM32_ADC_JDR2_OFFSET)
+#define STM32_ADC2_JDR3 (STM32_ADC2_BASE+STM32_ADC_JDR3_OFFSET)
+#define STM32_ADC2_JDR4 (STM32_ADC2_BASE+STM32_ADC_JDR4_OFFSET)
+#define STM32_ADC2_AWD2CR (STM32_ADC2_BASE+STM32_ADC_AWD2CR_OFFSET)
+#define STM32_ADC2_AWD3CR (STM32_ADC2_BASE+STM32_ADC_AWD3CR_OFFSET)
+#define STM32_ADC2_DIFSEL (STM32_ADC2_BASE+STM32_ADC_DIFSEL_OFFSET)
+#define STM32_ADC2_CALFACT (STM32_ADC2_BASE+STM32_ADC_CALFACT_OFFSET)
+
+#define STM32_ADC12_CSR (STM32_ADC12_BASE+STM32_ADC_CSR_OFFSET)
+#define STM32_ADC12_CCR (STM32_ADC12_BASE+STM32_ADC_CCR_OFFSET)
+#define STM32_ADC12_CDR (STM32_ADC12_BASE+STM32_ADC_CDR_OFFSET)
+
+#define STM32_ADC3_ISR (STM32_ADC3_BASE+STM32_ADC_ISR_OFFSET)
+#define STM32_ADC3_IER (STM32_ADC3_BASE+STM32_ADC_IER_OFFSET)
+#define STM32_ADC3_CR (STM32_ADC3_BASE+STM32_ADC_CR_OFFSET)
+#define STM32_ADC3_CFGR (STM32_ADC3_BASE+STM32_ADC_CFGR_OFFSET)
+#define STM32_ADC3_SMPR1 (STM32_ADC3_BASE+STM32_ADC_SMPR1_OFFSET)
+#define STM32_ADC3_SMPR2 (STM32_ADC3_BASE+STM32_ADC_SMPR2_OFFSET)
+#define STM32_ADC3_TR1 (STM32_ADC3_BASE+STM32_ADC_TR1_OFFSET)
+#define STM32_ADC3_TR2 (STM32_ADC3_BASE+STM32_ADC_TR2_OFFSET)
+#define STM32_ADC3_TR3 (STM32_ADC3_BASE+STM32_ADC_TR3_OFFSET)
+#define STM32_ADC3_SQR1 (STM32_ADC3_BASE+STM32_ADC_SQR1_OFFSET)
+#define STM32_ADC3_SQR2 (STM32_ADC3_BASE+STM32_ADC_SQR2_OFFSET)
+#define STM32_ADC3_SQR3 (STM32_ADC3_BASE+STM32_ADC_SQR3_OFFSET)
+#define STM32_ADC3_SQR4 (STM32_ADC3_BASE+STM32_ADC_SQR4_OFFSET)
+#define STM32_ADC3_DR (STM32_ADC3_BASE+STM32_ADC_DR_OFFSET)
+#define STM32_ADC3_JSQR (STM32_ADC3_BASE+STM32_ADC_JSQR_OFFSET)
+#define STM32_ADC3_OFR1 (STM32_ADC3_BASE+STM32_ADC_OFR1_OFFSET)
+#define STM32_ADC3_OFR2 (STM32_ADC3_BASE+STM32_ADC_OFR2_OFFSET)
+#define STM32_ADC3_OFR3 (STM32_ADC3_BASE+STM32_ADC_OFR3_OFFSET)
+#define STM32_ADC3_OFR4 (STM32_ADC3_BASE+STM32_ADC_OFR4_OFFSET)
+#define STM32_ADC3_JDR1 (STM32_ADC3_BASE+STM32_ADC_JDR1_OFFSET)
+#define STM32_ADC3_JDR2 (STM32_ADC3_BASE+STM32_ADC_JDR2_OFFSET)
+#define STM32_ADC3_JDR3 (STM32_ADC3_BASE+STM32_ADC_JDR3_OFFSET)
+#define STM32_ADC3_JDR4 (STM32_ADC3_BASE+STM32_ADC_JDR4_OFFSET)
+#define STM32_ADC3_AWD2CR (STM32_ADC3_BASE+STM32_ADC_AWD2CR_OFFSET)
+#define STM32_ADC3_AWD3CR (STM32_ADC3_BASE+STM32_ADC_AWD3CR_OFFSET)
+#define STM32_ADC3_DIFSEL (STM32_ADC3_BASE+STM32_ADC_DIFSEL_OFFSET)
+#define STM32_ADC3_CALFACT (STM32_ADC3_BASE+STM32_ADC_CALFACT_OFFSET)
+
+#define STM32_ADC4_ISR (STM32_ADC4_BASE+STM32_ADC_ISR_OFFSET)
+#define STM32_ADC4_IER (STM32_ADC4_BASE+STM32_ADC_IER_OFFSET)
+#define STM32_ADC4_CR (STM32_ADC4_BASE+STM32_ADC_CR_OFFSET)
+#define STM32_ADC4_CFGR (STM32_ADC4_BASE+STM32_ADC_CFGR_OFFSET)
+#define STM32_ADC4_SMPR1 (STM32_ADC4_BASE+STM32_ADC_SMPR1_OFFSET)
+#define STM32_ADC4_SMPR2 (STM32_ADC4_BASE+STM32_ADC_SMPR2_OFFSET)
+#define STM32_ADC4_TR1 (STM32_ADC4_BASE+STM32_ADC_TR1_OFFSET)
+#define STM32_ADC4_TR2 (STM32_ADC4_BASE+STM32_ADC_TR2_OFFSET)
+#define STM32_ADC4_TR3 (STM32_ADC4_BASE+STM32_ADC_TR3_OFFSET)
+#define STM32_ADC4_SQR1 (STM32_ADC4_BASE+STM32_ADC_SQR1_OFFSET)
+#define STM32_ADC4_SQR2 (STM32_ADC4_BASE+STM32_ADC_SQR2_OFFSET)
+#define STM32_ADC4_SQR3 (STM32_ADC4_BASE+STM32_ADC_SQR3_OFFSET)
+#define STM32_ADC4_SQR4 (STM32_ADC4_BASE+STM32_ADC_SQR4_OFFSET)
+#define STM32_ADC4_DR (STM32_ADC4_BASE+STM32_ADC_DR_OFFSET)
+#define STM32_ADC4_JSQR (STM32_ADC4_BASE+STM32_ADC_JSQR_OFFSET)
+#define STM32_ADC4_OFR1 (STM32_ADC4_BASE+STM32_ADC_OFR1_OFFSET)
+#define STM32_ADC4_OFR2 (STM32_ADC4_BASE+STM32_ADC_OFR2_OFFSET)
+#define STM32_ADC4_OFR3 (STM32_ADC4_BASE+STM32_ADC_OFR3_OFFSET)
+#define STM32_ADC4_OFR4 (STM32_ADC4_BASE+STM32_ADC_OFR4_OFFSET)
+#define STM32_ADC4_JDR1 (STM32_ADC4_BASE+STM32_ADC_JDR1_OFFSET)
+#define STM32_ADC4_JDR2 (STM32_ADC4_BASE+STM32_ADC_JDR2_OFFSET)
+#define STM32_ADC4_JDR3 (STM32_ADC4_BASE+STM32_ADC_JDR3_OFFSET)
+#define STM32_ADC4_JDR4 (STM32_ADC4_BASE+STM32_ADC_JDR4_OFFSET)
+#define STM32_ADC4_AWD2CR (STM32_ADC4_BASE+STM32_ADC_AWD2CR_OFFSET)
+#define STM32_ADC4_AWD3CR (STM32_ADC4_BASE+STM32_ADC_AWD3CR_OFFSET)
+#define STM32_ADC4_DIFSEL (STM32_ADC4_BASE+STM32_ADC_DIFSEL_OFFSET)
+#define STM32_ADC4_CALFACT (STM32_ADC4_BASE+STM32_ADC_CALFACT_OFFSET)
+
+#define STM32_ADC34_CSR (STM32_ADC34_BASE+STM32_ADC_CSR_OFFSET)
+#define STM32_ADC34_CCR (STM32_ADC34_BASE+STM32_ADC_CCR_OFFSET)
+#define STM32_ADC34_CDR (STM32_ADC34_BASE+STM32_ADC_CDR_OFFSET)
+
+/* Register Bitfield Definitions ********************************************************************/
+/* ADC interrupt and status register (ISR) and ADC interrupt enable register (IER) */
+
+#define ADC_INT_ARDY (1 << 0) /* Bit 0: ADC ready */
+#define ADC_INT_EOSMP (1 << 1) /* Bit 1: End of sampling flag */
+#define ADC_INT_EOC (1 << 2) /* Bit 2: End of conversion */
+#define ADC_INT_EOS (1 << 3) /* Bit 3: End of regular sequence flag */
+#define ADC_INT_OVR (1 << 4) /* Bit 4: Overrun */
+#define ADC_INT_JEOC (1 << 5) /* Bit 5: Injected channel end of conversion */
+#define ADC_INT_JEOS (1 << 6) /* Bit 6: Injected channel end of sequence flag */
+#define ADC_INT_AWD1 (1 << 7) /* Bit 7: Analog watchdog 1 flag */
+#define ADC_INT_AWD2 (1 << 8) /* Bit 8: Analog watchdog 2 flag */
+#define ADC_INT_AWD3 (1 << 9) /* Bit 9: Analog watchdog 3 flag */
+#define ADC_INT_JQOVF (1 << 10) /* Bit 10: Injected context queue overflow */
+
+/* ADC control register */
+
+#define ADC_CR_ADEN (1 << 0) /* Bit 0: ADC enable control */
+#define ADC_CR_ADDIS (1 << 1) /* Bit 1: ADC disable command */
+#define ADC_CR_ADSTART (1 << 2) /* Bit 2: ADC start of regular conversion */
+#define ADC_CR_JADSTART (1 << 3) /* Bit 3: ADC start of injected conversion */
+#define ADC_CR_ADSTP (1 << 4) /* Bit 4: ADC stop of regular conversion command */
+#define ADC_CR_JADSTP (1 << 5) /* Bit 5: ADC stop of injected conversion command */
+#define ADC_CR_ADVREGEN_SHIFT (28) /* Bits 28-29: ADC voltage regulator enable */
+#define ADC_CR_ADVREGEN_MASK (3 << ADC_CR_ADVREGEN_SHIFT)
+# define ADC_CR_ADVREGEN_INTER (0 << ADC_CR_ADVREGEN_SHIFT) /* Intermediate state */
+# define ADC_CR_ADVREGEN_ENABLED (1 << ADC_CR_ADVREGEN_SHIFT) /* ADC Voltage regulator enabled */
+# define ADC_CR_ADVREGEN_DISABLED (2 << ADC_CR_ADVREGEN_SHIFT) /* ADC Voltage regulator disabled */
+#define ADC_CR_ADCALDIF (1 << 30) /* Bit 30: Differential mode for calibration */
+#define ADC_CR_ADCAL (1 << 31) /* Bit 31: ADC calibration */
+
+/* ADC configuration register */
+
+#define ADC_CFGR_DMACFG (1 << 1) /* Bit 0: Direct memory access configuration */
+#define ACD_CFGR_RES_SHIFT (3) /* Bits 3-4: Data resolution */
+#define ACD_CFGR_RES_MASK (3 << ACD_CFGR_RES_SHIFT)
+# define ACD_CFGR_RES_12BIT (0 << ACD_CFGR_RES_SHIFT) /* 15 ADCCLK clyes */
+# define ACD_CFGR_RES_10BIT (1 << ACD_CFGR_RES_SHIFT) /* 13 ADCCLK clyes */
+# define ACD_CFGR_RES_8BIT (2 << ACD_CFGR_RES_SHIFT) /* 11 ADCCLK clyes */
+# define ACD_CFGR_RES_6BIT (3 << ACD_CFGR_RES_SHIFT) /* 9 ADCCLK clyes */
+#define ADC_CFGR_ALIGN (1 << 5) /* Bit 5: Data Alignment */
+#define ADC_CFGR_EXTSEL_SHIFT (6) /* Bits 6-9: External Event Select for regular group */
+#define ADC_CFGR_EXTSEL_MASK (15 << ADC_CFGR_EXTSEL_SHIFT)
+# define ADC_CFGR_EXTSEL(event) ((event) << ADC_CFGR_EXTSEL_SHIFT) /* Event = 0..15 */
+#define ACD_CFGR_EXTEN_SHIFT (10) /* Bits 10-11: External trigger/polarity selection regular channels */
+#define ACD_CFGR_EXTEN_MASK (3 << ACD_CFGR_EXTEN_SHIFT)
+# define ACD_CFGR_EXTEN_NONE (0 << ACD_CFGR_EXTEN_SHIFT) /* Trigger detection disabled */
+# define ACD_CFGR_EXTEN_RISING (1 << ACD_CFGR_EXTEN_SHIFT) /* Trigger detection on the rising edge */
+# define ACD_CFGR_EXTEN_FALLING (2 << ACD_CFGR_EXTEN_SHIFT) /* Trigger detection on the falling edge */
+# define ACD_CFGR_EXTEN_BOTH (3 << ACD_CFGR_EXTEN_SHIFT) /* Trigger detection on both edges */
+#define ADC_CFGR_OVRMOD (1 << 12) /* Bit 12: Overrun Mode */
+#define ADC_CFGR_CONT (1 << 13) /* Bit 13: Continuous mode for regular conversions */
+#define ADC_CFGR_AUTDLY (1 << 14) /* Bit 14: Delayed conversion mode */
+#define ADC_CFGR_DISCEN (1 << 16) /* Bit 16: Discontinuous mode on regular channels */
+#define ADC_CFGR_DISCNUM_SHIFT (17) /* Bits 17-19: Discontinuous mode channel count */
+#define ADC_CFGR_DISCNUM_MASK (7 << ADC_CFGR_DISCNUM_SHIFT)
+# define ADC_CFGR_DISCNUM(n) (((n) - 1) << ADC_CFGR_DISCNUM_SHIFT) /* n = 1..8 channels */
+#define ADC_CFGR_JDISCEN (1 << 20) /* Bit 20: Discontinuous mode on injected channels */
+#define ADC_CFGR_JQM (1 << 21) /* Bit 21: JSQR queue mode */
+#define ADC_CFGR_AWD1SGL (1 << 22) /* Bit 22: Enable watchdog on single/all channels */
+#define ADC_CFGR_AWD1EN (1 << 23) /* Bit 23: Analog watchdog enable 1 regular channels */
+#define ADC_CFGR_JAWD1EN (1 << 22) /* Bit 22: Analog watchdog enable 1 injected channels */
+#define ADC_CFGR_JAUTO (1 << 25) /* Bit 25: Automatic Injected Group conversion */
+#define ADC_CFGR_AWD1CH_SHIFT (26) /* Bits 26-30: Analog watchdog 1 channel select bits */
+#define ADC_CFGR_AWD1CH_MASK (31 << ADC_CFGR_AWD1CH_SHIFT)
+# define ADC_CFGR_AWD1CH_DISABLED (0 << ADC_CFGR_AWD1CH_SHIFT)
+
+/* ADC sample time register 1 */
+
+#define ADC_SMPR_1p5 0 /* 000: 1.5 cycles */
+#define ADC_SMPR_2p5 1 /* 001: 2.5 cycles */
+#define ADC_SMPR_4p5 2 /* 010: 4.5 cycles */
+#define ADC_SMPR_7p5 3 /* 011: 7.5 cycles */
+#define ADC_SMPR_19p5 4 /* 100: 19.5 cycles */
+#define ADC_SMPR_61p5 5 /* 101: 61.5 cycles */
+#define ADC_SMPR_181p5 6 /* 110: 181.5 cycles */
+#define ADC_SMPR_2601p5 7 /* 111: 601.5 cycles */
+
+#define ADC_SMPR1_SMP1_SHIFT (3) /* Bits 5-3: Channel 1 Sample time selection */
+#define ADC_SMPR1_SMP1_MASK (7 << ADC_SMPR1_SMP1_SHIFT)
+#define ADC_SMPR1_SMP2_SHIFT (6) /* Bits 8-6: Channel 2 Sample time selection */
+#define ADC_SMPR1_SMP2_MASK (7 << ADC_SMPR1_SMP2_SHIFT)
+#define ADC_SMPR1_SMP3_SHIFT (9) /* Bits 11-9: Channel 3 Sample time selection */
+#define ADC_SMPR1_SMP3_MASK (7 << ADC_SMPR1_SMP3_SHIFT)
+#define ADC_SMPR1_SMP4_SHIFT (12) /* Bits 14-12: Channel 4 Sample time selection */
+#define ADC_SMPR1_SMP4_MASK (7 << ADC_SMPR1_SMP4_SHIFT)
+#define ADC_SMPR1_SMP5_SHIFT (15) /* Bits 17-15: Channel 5 Sample time selection */
+#define ADC_SMPR1_SMP5_MASK (7 << ADC_SMPR1_SMP5_SHIFT)
+#define ADC_SMPR1_SMP6_SHIFT (18) /* Bits 20-18: Channel 6 Sample time selection */
+#define ADC_SMPR1_SMP6_MASK (7 << ADC_SMPR1_SMP6_SHIFT)
+#define ADC_SMPR1_SMP7_SHIFT (21) /* Bits 23-21: Channel 7 Sample time selection */
+#define ADC_SMPR1_SMP7_MASK (7 << ADC_SMPR1_SMP7_SHIFT)
+#define ADC_SMPR1_SMP8_SHIFT (24) /* Bits 26-24: Channel 8 Sample time selection */
+#define ADC_SMPR1_SMP8_MASK (7 << ADC_SMPR1_SMP8_SHIFT)
+#define ADC_SMPR1_SMP9_SHIFT (27) /* Bits 29-27: Channel 9 Sample time selection */
+#define ADC_SMPR1_SMP9_MASK (7 << ADC_SMPR1_SMP9_SHIFT)
+
+/* ADC sample time register 2 */
+
+#define ADC_SMPR2_SMP10_SHIFT (0) /* Bits 0-2: Channel 10 Sample time selection */
+#define ADC_SMPR2_SMP10_MASK (7 << ADC_SMPR2_SMP10_SHIFT)
+#define ADC_SMPR2_SMP11_SHIFT (3) /* Bits 3-5: Channel 11 Sample time selection */
+#define ADC_SMPR2_SMP11_MASK (7 << ADC_SMPR2_SMP11_SHIFT)
+#define ADC_SMPR2_SMP12_SHIFT (6) /* Bits 6-8: Channel 12 Sample time selection */
+#define ADC_SMPR2_SMP12_MASK (7 << ADC_SMPR2_SMP12_SHIFT)
+#define ADC_SMPR2_SMP13_SHIFT (9) /* Bits 9-11: Channel 13 Sample time selection */
+#define ADC_SMPR2_SMP13_MASK (7 << ADC_SMPR2_SMP13_SHIFT)
+#define ADC_SMPR2_SMP14_SHIFT (12) /* Bits 12-14: Channel 14 Sample time selection */
+#define ADC_SMPR2_SMP14_MASK (7 << ADC_SMPR2_SMP14_SHIFT)
+#define ADC_SMPR2_SMP15_SHIFT (15) /* Bits 15-17: Channel 15 Sample time selection */
+#define ADC_SMPR2_SMP15_MASK (7 << ADC_SMPR2_SMP15_SHIFT)
+#define ADC_SMPR2_SMP16_SHIFT (18) /* Bits 18-20: Channel 16 Sample time selection */
+#define ADC_SMPR2_SMP16_MASK (7 << ADC_SMPR2_SMP16_SHIFT)
+#define ADC_SMPR2_SMP17_SHIFT (21) /* Bits 21-23: Channel 17 Sample time selection */
+#define ADC_SMPR2_SMP17_MASK (7 << ADC_SMPR2_SMP17_SHIFT)
+#define ADC_SMPR2_SMP18_SHIFT (21) /* Bits 24-26: Channel 18 Sample time selection */
+#define ADC_SMPR2_SMP18_MASK (7 << ADC_SMPR2_SMP17_SHIFT)
+
+/* ADC watchdog threshold register 1 */
+
+#define ADC_TR1_LT_SHIFT (0) /* Bits 0-11: Analog watchdog 1 lower threshold */
+#define ADC_TR1_LT_MASK (0x0fff << ADC_TR1_LT_SHIFT)
+#define ADC_TR1_HT_SHIFT (16) /* Bits 16-27: Analog watchdog 1 higher threshold */
+#define ADC_TR1_HT_MASK (0x0fff << ADC_TR1_HT_SHIFT)
+
+/* ADC watchdog threshold register 2 */
+
+#define ADC_TR2_LT_SHIFT (0) /* Bits 0-7: Analog watchdog 2 lower threshold */
+#define ADC_TR2_LT_MASK (0xff << ADC_TR2_LT_SHIFT)
+#define ADC_TR2_HT_SHIFT (16) /* Bits 16-23: Analog watchdog 2 higher threshold */
+#define ADC_TR2_HT_MASK (0xff << ADC_TR2_HT_SHIFT)
+
+/* ADC watchdog threshold register 3 */
+
+#define ADC_TR3_LT_SHIFT (0) /* Bits 0-7: Analog watchdog 3 lower threshold */
+#define ADC_TR3_LT_MASK (0xff << ADC_TR3_LT_SHIFT)
+#define ADC_TR3_HT_SHIFT (16) /* Bits 16-23: Analog watchdog 3 higher threshold */
+#define ADC_TR3_HT_MASK (0xff << ADC_TR3_HT_SHIFT)
+
+/* ADC regular sequence register 1 */
+
+#define ADC_SQR1_L_SHIFT (0) /* Bits 0-3: Regular channel sequence length */
+#define ADC_SQR1_L_MASK (0x0f << ADC_SQR1_L_SHIFT)
+#define ADC_SQR1_SQ1_SHIFT (6) /* Bits 6-10: 13th conversion in regular sequence */
+#define ADC_SQR1_SQ1_MASK (0x1f << ADC_SQR1_SQ1_SHIFT)
+#define ADC_SQR1_SQ2_SHIFT (12) /* Bits 12-16: 2nd conversion in regular sequence */
+#define ADC_SQR1_SQ2_MASK (0x1f << ADC_SQR1_SQ2_SHIFT)
+#define ADC_SQR1_SQ3_SHIFT (18) /* Bits 18-22: 3rd conversion in regular sequence */
+#define ADC_SQR1_SQ3_MASK (0x1f << ADC_SQR1_SQ3_SHIFT)
+#define ADC_SQR1_SQ4_SHIFT (24) /* Bits 24-28: 4th conversion in regular sequence */
+#define ADC_SQR1_SQ4_MASK (0x1f << ADC_SQR1_SQ4_SHIFT)
+
+/* ADC regular sequence register 2 */
+
+#define ADC_SQR2_SQ5_SHIFT (0) /* Bits 4-0: 5th conversion in regular sequence */
+#define ADC_SQR2_SQ5_MASK (0x1f << ADC_SQR2_SQ5_SHIFT)
+#define ADC_SQR2_SQ6_SHIFT (6) /* Bits 6-10: 6th conversion in regular sequence */
+#define ADC_SQR2_SQ6_MASK (0x1f << ADC_SQR2_SQ6_SHIFT)
+#define ADC_SQR2_SQ7_SHIFT (12) /* Bits 12-16: 7th conversion in regular sequence */
+#define ADC_SQR2_SQ7_MASK (0x1f << ADC_SQR2_SQ7_SHIFT)
+#define ADC_SQR2_SQ8_SHIFT (18) /* Bits 18-22: 8th conversion in regular sequence */
+#define ADC_SQR2_SQ8_MASK (0x1f << ADC_SQR2_SQ8_SHIFT)
+#define ADC_SQR2_SQ9_SHIFT (24) /* Bits 24-28: 9th conversion in regular sequence */
+#define ADC_SQR2_SQ9_MASK (0x1f << ADC_SQR2_SQ9_SHIFT )
+
+/* ADC regular sequence register 3 */
+
+#define ADC_SQR3_SQ10_SHIFT (0) /* Bits 4-0: 10th conversion in regular sequence */
+#define ADC_SQR3_SQ10_MASK (0x1f << ADC_SQR3_SQ10_SHIFT)
+#define ADC_SQR3_SQ11_SHIFT (6) /* Bits 6-10: 11th conversion in regular sequence */
+#define ADC_SQR3_SQ11_MASK (0x1f << ADC_SQR3_SQ11_SHIFT)
+#define ADC_SQR3_SQ12_SHIFT (12) /* Bits 12-16: 12th conversion in regular sequence */
+#define ADC_SQR3_SQ12_MASK (0x1f << ADC_SQR3_SQ12_SHIFT)
+#define ADC_SQR3_SQ13_SHIFT (18) /* Bits 18-22: 13th conversion in regular sequence */
+#define ADC_SQR3_SQ13_MASK (0x1f << ADC_SQR3_SQ13_SHIFT)
+#define ADC_SQR3_SQ14_SHIFT (24) /* Bits 24-28: 14th conversion in regular sequence */
+#define ADC_SQR3_SQ14_MASK (0x1f << ADC_SQR3_SQ14_SHIFT )
+
+/* ADC regular sequence register 4 */
+
+#define ADC_SQR4_SQ15_SHIFT (0) /* Bits 4-0: 14th conversion in regular sequence */
+#define ADC_SQR4_SQ15_MASK (0x1f << ADC_SQR4_SQ15_SHIFT)
+#define ADC_SQR4_SQ16_SHIFT (6) /* Bits 6-10: 15th conversion in regular sequence */
+#define ADC_SQR4_SQ16_MASK (0x1f << ADC_SQR4_SQ16_SHIFT)
+
+/* ADC regular data register */
+
+#define ADC_DR_MASK (0xffff)
+
+/* ADC injected sequence register */
+
+#define ADC_JSQR_JL_SHIFT (0) /* Bits 0-1: Injected Sequence length */
+#define ADC_JSQR_JL_MASK (3 << ADC_JSQR_JL_SHIFT)
+# define ADC_JSQR_JL(n) (((n)-1) << ADC_JSQR_JL_SHIFT) /* n=1..4 */
+#define ADC_JSQR_JEXTSEL_SHIFT (2) /* Bits 2-5: External Trigger Selection for injected group */
+#define ADC_JSQR_JEXTSEL_MASK (15 << ADC_JSQR_JEXTSEL_SHIFT)
+# define ADC_JSQR_JEXTSEL(event) ((event) << ADC_JSQR_JEXTSEL_SHIFT) /* Event = 0..15 */
+# define ADC_JSQR_JEXTEN_SHIFT (6) /* Bits 6-7: External trigger selection for injected greoup */
+# define ADC_JSQR_JEXTEN_MASK (3 << ADC_JSQR_JEXTEN_SHIFT)
+# define ADC_JSQR_JEXTEN_NONE (0 << ADC_JSQR_JEXTEN_SHIFT) /* 00: Trigger detection disabled */
+# define ADC_JSQR_JEXTEN_RISING (1 << ADC_JSQR_JEXTEN_SHIFT) /* 01: Trigger detection on the rising edge */
+# define ADC_JSQR_JEXTEN_FALLING (2 << ADC_JSQR_JEXTEN_SHIFT) /* 10: Trigger detection on the falling edge */
+# define ADC_JSQR_JEXTEN_BOTH (3 << ADC_JSQR_JEXTEN_SHIFT) /* 11: Trigger detection on both the rising and falling edges */
+#define ADC_JSQR_JSQ1_SHIFT (8) /* Bits 8-12: 1st conversion in injected sequence */
+#define ADC_JSQR_JSQ1_MASK (0x1f << ADC_JSQR_JSQ1_SHIFT)
+# define ADC_JSQR_JSQ1(ch) ((ch) << ADC_JSQR_JSQ1_SHIFT) /* Channel number 1..18 */
+#define ADC_JSQR_JSQ2_SHIFT (14) /* Bits 14-18: 2nd conversion in injected sequence */
+#define ADC_JSQR_JSQ2_MASK (0x1f << ADC_JSQR_JSQ2_MASK)
+# define ADC_JSQR_JSQ2(ch) ((ch) << ADC_JSQR_JSQ2_MASK) /* Channel number 1..18 */
+#define ADC_JSQR_JSQ3_SHIFT (20) /* Bits 20-24: 3rd conversion in injected sequence */
+#define ADC_JSQR_JSQ3_MASK (0x1f << ADC_JSQR_JSQ3_SHIFT)
+# define ADC_JSQR_JSQ3(ch) ((ch) << ADC_JSQR_JSQ3_SHIFT) /* Channel number 1..18 */
+#define ADC_JSQR_JSQ4_SHIFT (26) /* Bits 26-30: 4th conversion in injected sequence */
+#define ADC_JSQR_JSQ4_MASK (0x1f << ADC_JSQR_JSQ4_SHIFT)
+# define ADC_JSQR_JSQ4(ch) ((ch) << ADC_JSQR_JSQ4_SHIFT) /* Channel number 1..18 */
+
+/* ADC offset register 1, 2, 3, and 4 */
+
+#define ADC_OFR_OFFSETY_SHIFT (0) /* Bits 0-11: Data offset y for channel OFFSETY_CH */
+#define ADC_OFR_OFFSETY_MASK (0x0fff << ADC_OFR_OFFSETY_SHIFT)
+# define ADC_OFR_OFFSETY(offset) ((offset) << ADC_OFR_OFFSETY_SHIFT)
+#define ADC_OFR_OFFSETY_CH_SHIFT (26) /* Bits 26-30: Channel selection for data offset y */
+#define ADC_OFR_OFFSETY_CH_MASK (31 << ADC_OFR_OFFSETY_CH_SHIFT)
+# define ADC_OFR_OFFSETY_CH(ch) ((ch) << ADC_OFR_OFFSETY_CH_SHIFT)
+#define ADC_OFR_OFFSETY_EN (1 << 31) /* Bit 31: Offset y enable */
+
+/* ADC injected data register 1, 2, 3, and 4 */
+
+#define ADC_JDR_MASK (0xffff)
+
+/* ADC analog watchdog 2 configuration register */
+
+#define ADC_AWD2CR_CH_SHIFT (1) /* Bits 1-18: Analog watchdog 2 channel selection */
+#define ADC_AWD2CR_CH_MASK (0x3ffff << ADC_AWD2CR_CH_SHIFT)
+# define ADC_AWD2CR_CH(n) (1 << (n)) /* Channel n=1..18 */
+
+/* ADC analog watchdog 3 configuration register */
+
+#define ADC_AWD3CR_CH_SHIFT (1) /* Bits 1-18: Analog watchdog 2 channel selection */
+#define ADC_AWD3CR_CH_MASK (0x3ffff << ADC_AWD3CR_CH_SHIFT)
+# define ADC_AWD3CR_CH(n) (1 << (n)) /* Channel n=1..18 */
+
+/* ADC differential mode selection register 2 */
+#define ADC_DIFSEL_
+
+#define ADC_DIFSEL_CH_SHIFT (1) /* Bits 1-18: Analog watchdog 2 channel selection */
+#define ADC_DIFSEL_CH_MASK (0x3ffff << ADC_DIFSEL_CH_SHIFT)
+# define ADC_DIFSEL_CH(n) (1 << (n)) /* Channel n=1..18 */
+
+/* ADC calibration factors */
+
+#define ADC_CALFACT_S_SHIFT (0) /* Bits 0-6: Calibration factors in single-ended mode */
+#define ADC_CALFACT_S_MASK (0x7f << ADC_CALFACT_S_SHIFT)
+#define ADC_CALFACT_D_SHIFT (16) /* Bits 16-22: Calibration Factors indifferential mode */
+#define ADC_CALFACT_D_MASK (0x7f << ADC_CALFACT_D_SHIFT)
+
+/* Common status register */
+
+#define ADC_CSR_ADRDY_MST (1 << 0) /* Bit 0: Master ADC ready */
+#define ADC_CSR_EOSMP_MST (1 << 1) /* Bit 1: End of Sampling phase flag (master ADC) */
+#define ADC_CSR_EOC_MST (1 << 2) /* Bit 2: End of regular conversion (master ADC) */
+#define ADC_CSR_EOS_MST (1 << 3) /* Bit 3: End of regular sequence flag (master ADC) */
+#define ADC_CSR_OVR_MST (1 << 4) /* Bit 4: Overrun flag (master ADC) */
+#define ADC_CSR_JEOC_MST (1 << 5) /* Bit 5: End of injected conversion flag (master ADC) */
+#define ADC_CSR_JEOS_MST (1 << 6) /* Bit 6: End of injected sequence flag (master ADC) */
+#define ADC_CSR_AWD1_MST (1 << 7) /* Bit 7: Analog watchdog 1 flag (master ADC) */
+#define ADC_CSR_AWD2_MST (1 << 8) /* Bit 8: Analog watchdog 2 flag (master ADC) */
+#define ADC_CSR_AWD3_MST (1 << 9) /* Bit 9: Analog watchdog 3 flag (master ADC) */
+#define ADC_CSR_JQOVF_MST (1 << 10) /* Bit 10: Injected Context Queue Overflow flag (master ADC) */
+#define ADC_CSR_ADRDY_SLV (1 << 16) /* Bit 16: Slave ADC ready */
+#define ADC_CSR_EOSMP_SLV (1 << 17) /* Bit 17: End of Sampling phase flag (slave ADC) */
+#define ADC_CSR_EOC_SLV (1 << 18) /* Bit 18: End of regular conversion (slave ADC) */
+#define ADC_CSR_EOS_SLV (1 << 19) /* Bit 19: End of regular sequence flag (slave ADC) */
+#define ADC_CSR_OVR_SLV (1 << 20) /* Bit 20: Overrun flag (slave ADC) */
+#define ADC_CSR_JEOC_SLV (1 << 21) /* Bit 21: End of injected conversion flag (slave ADC) */
+#define ADC_CSR_JEOS_SLV (1 << 22) /* Bit 22: End of injected sequence flag (slave ADC) */
+#define ADC_CSR_AWD1_SLV (1 << 23) /* Bit 23: Analog watchdog 1 flag (slave ADC) */
+#define ADC_CSR_AWD2_SLV (1 << 24) /* Bit 24: Analog watchdog 2 flag (slave ADC) */
+#define ADC_CSR_AWD3_SLV (1 << 25) /* Bit 25: Analog watchdog 3 flag (slave ADC) */
+#define ADC_CSR_JQOVF_SLV (1 << 26) /* Bit 26: Injected Context Queue Overflow flag (slave ADC) */
+
+/* Common control register */
+
+#define ADC_CCR_DUAL_SHIFT (0) /* Bits 0-4: Dual ADC mode selection */
+#define ADC_CCR_DUAL_MASK (31 << ADC_CCR_DUAL_SHIFT)
+# define ADC_CCR_DUAL_IND (0 << ADC_CCR_DUAL_SHIFT) /* Independent mode */
+# define ADC_CCR_DUAL_DUAL (1 << ADC_CCR_DUAL_SHIFT) /* Dual mode, master/slave ADCs together */
+# define ADC_CCR_DUAL_SIMINJ (1 << ADC_CCR_DUAL_SHIFT) /* Combined regular sim. + injected sim. */
+# define ADC_CCR_DUAL_SIMALT (2 << ADC_CCR_DUAL_SHIFT) /* Combined regular sim. + alternate trigger */
+# define ADC_CCR_DUAL_INJECTED (5 << ADC_CCR_DUAL_SHIFT) /* Injected simultaneous mode only */
+# define ADC_CCR_DUAL_SIM (6 << ADC_CCR_DUAL_SHIFT) /* Regular simultaneous mode only */
+# define ADC_CCR_DUAL_INTERLEAVE (7 << ADC_CCR_DUAL_SHIFT) /* Interleaved mode only */
+# define ADC_CCR_DUAL_ALT (9 << ADC_CCR_DUAL_SHIFT) /* Alternate trigger mode only */
+#define ADC_CCR_DELAY_SHIFT (8) /* Bits 8-11: Delay between 2 sampling phases */
+#define ADC_CCR_DELAY_MASK (15 << ADC_CCR_DELAY_SHIFT)
+# define ADC_CCR_DELAY(n) (((n)-1) << ADC_CCR_DELAY_SHIFT) /* n * TADCCLK, 1-13 */
+#define ADC_CCR_DMACFG (1 << 13) /* Bit 13: DMA configuration (for dual ADC mode) */
+#define ADC_CCR_MDMA_SHIFT (14) /* Bits 14-15: Direct memory access mode for dual ADC mode */
+#define ADC_CCR_MDMA_MASK (3 << ADC_CCR_MDMA_SHIFT)
+# define ADC_CCR_MDMA_DISABLE (0 << ADC_CCR_MDMA_SHIFT) /* MDMA mode disabled */
+# define ADC_CCR_MDMA_ 10_12 (2 << ADC_CCR_MDMA_SHIFT) /* MDMA mode enabled (12 / 10-bit) */
+# define ADC_CCR_MDMA_6_8 (3 << ADC_CCR_MDMA_SHIFT) /* MDMA mode enabled (8 / 6-bit) */
+#define ADC_CCR_CKMODE_SHIFT (16) /* Bits 16-17: ADC clock mode */
+#define ADC_CCR_CKMODE_MASK (15 << ADC_CCR_CKMODE_SHIFT)
+# define ADC_CCR_CKMODE_ASYCH (0 << ADC_CCR_CKMODE_SHIFT) /* Asynchronous clock mode */
+# define ADC_CCR_CKMODE_SYNCH_DIV1 (1 << ADC_CCR_CKMODE_SHIFT) /* Synchronous clock mode divided by 1 */
+# define ADC_CCR_CKMODE_SYNCH_DIV2 (2 << ADC_CCR_CKMODE_SHIFT) /* Synchronous clock mode divided by 2 */
+# define ADC_CCR_CKMODE_SYNCH_DIV4 (3 << ADC_CCR_CKMODE_SHIFT) /* Synchronous clock mode divided by 4 */
+#define ADC_CCR_VREFEN (1 << 22) /* Bit 22: VREFINT enable */
+#define ADC_CCR_TSEN (1 << 23) /* Bit 23: Temperature sensor enable */
+#define ADC_CCR_VBATEN (1 << 24) /* Bit 22: VBAT enable */
+
+/* Common regular data register for dual mode */
+
+#define ADC_CDR_RDATA_MST_SHIFT (0) /* Bits 0-15: Regular data of the master ADC */
+#define ADC_CDR_RDATA_MST_MASK (0xffff << ADC_CDR_RDATA_MST_SHIFT)
+#define ADC_CDR_RDATA_SLV_SHIFT (16) /* Bits 16-31: Regular data of the slave ADC */
+#define ADC_CDR_RDATA_SLV_MASK (0xffff << ADC_CDR_RDATA_SLV_SHIFT)
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public Data
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F30XXX_ADC_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c
index f58083468..5ed6c6fe9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.c
@@ -63,9 +63,19 @@
#include "stm32.h"
#include "stm32_adc.h"
+/* ADC "upper half" support must be enabled */
+
#ifdef CONFIG_ADC
+
+/* Some ADC peripheral must be enabled */
+
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+/* This implementation is for the STM32 F1, F2, and F4 only */
+
+#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F20XX) || \
+ defined(CONFIG_STM32_STM32F40XX)
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -1541,6 +1551,6 @@ struct adc_dev_s *stm32_adcinitialize(int intf, const uint8_t *chanlist, int nch
return dev;
}
+#endif /* CONFIG_STM32_STM32F10XX || CONFIG_STM32_STM32F20XX || CONFIG_STM32_STM32F40XX */
#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
#endif /* CONFIG_ADC */
-
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h
index 060fcdfb9..f9e26294e 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.h
@@ -43,7 +43,12 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "chip/stm32_adc.h"
+
+#if defined(CONFIG_STM32_STM32F30XX)
+# include "chip/stm32f30xxx_adc.h"
+#else
+# include "chip/stm32_adc.h"
+#endif
#include <nuttx/analog/adc.h>
diff --git a/nuttx/libc/spawn/lib_psfa_dump.c b/nuttx/libc/spawn/lib_psfa_dump.c
index f71f2701e..49a0f97a5 100644
--- a/nuttx/libc/spawn/lib_psfa_dump.c
+++ b/nuttx/libc/spawn/lib_psfa_dump.c
@@ -113,8 +113,8 @@ void posix_spawn_file_actions_dump(FAR posix_spawn_file_actions_t *file_actions)
FAR struct spawn_open_file_action_s *action =
(FAR struct spawn_open_file_action_s *)entry;
- svdbg(" OPEN: path=%s oflags=%04x mode=%04x fd=%d\n",
- action->path, action->oflags, action->mode, action->fd);
+ dbg(" OPEN: path=%s oflags=%04x mode=%04x fd=%d\n",
+ action->path, action->oflags, action->mode, action->fd);
}
break;