summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-19 19:24:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-19 19:24:09 +0000
commitc5ba205781809f0a9124a1bd04d78c411f536ebf (patch)
tree0191fde92a5c4dcd55a24b2aa760fa4c88713242
parent634e46a77bcce80bc04ad44f5efeec0ca273993a (diff)
downloadpx4-nuttx-c5ba205781809f0a9124a1bd04d78c411f536ebf.tar.gz
px4-nuttx-c5ba205781809f0a9124a1bd04d78c411f536ebf.tar.bz2
px4-nuttx-c5ba205781809f0a9124a1bd04d78c411f536ebf.zip
Completes coding of the PWM module
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4200 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xapps/ChangeLog.txt2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_tim.h114
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pwm.c617
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pwm.h230
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rtc.c2
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt13
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt11
-rw-r--r--nuttx/include/nuttx/pwm.h6
8 files changed, 835 insertions, 160 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index fe03dae6a..fe8c057fe 100755
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -144,3 +144,5 @@
by setting CONFIG_NSH_BUILTIN_APPS.
* apps/examples/nettest: Correct some build issues with the nettest is
built for performance evaluation.
+ * apps/examples/adc: Add a very simple test to drive and test an ADC
+ driver.
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_tim.h b/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
index 43a9f0ac4..6af2e515c 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_tim.h
@@ -96,19 +96,13 @@
#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) */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define STM32_ATIM_RCR_OFFSET 0x0030 /* Repetition counter register (16-bit) */
-#endif
+#define STM32_ATIM_RCR_OFFSET 0x0030 /* Repetition counter register (16-bit) */
#define STM32_ATIM_CCR1_OFFSET 0x0034 /* Capture/compare register 1 (16-bit) */
#define STM32_ATIM_CCR2_OFFSET 0x0038 /* Capture/compare register 2 (16-bit) */
#define STM32_ATIM_CCR3_OFFSET 0x003c /* Capture/compare register 3 (16-bit) */
#define STM32_ATIM_CCR4_OFFSET 0x0040 /* Capture/compare register 4 (16-bit) */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define STM32_ATIM_BDTR_OFFSET 0x0044 /* Break and dead-time register (16-bit) */
-#endif
+#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) */
@@ -130,16 +124,12 @@
# define STM32_TIM1_CNT (STM32_TIM1_BASE+STM32_ATIM_CNT_OFFSET)
# define STM32_TIM1_PSC (STM32_TIM1_BASE+STM32_ATIM_PSC_OFFSET)
# define STM32_TIM1_ARR (STM32_TIM1_BASE+STM32_ATIM_ARR_OFFSET)
-# ifdef CONFIG_STM32_STM32F10XX
-# define STM32_TIM1_RCR (STM32_TIM1_BASE+STM32_ATIM_RCR_OFFSET)
-# endif
+# define STM32_TIM1_RCR (STM32_TIM1_BASE+STM32_ATIM_RCR_OFFSET)
# define STM32_TIM1_CCR1 (STM32_TIM1_BASE+STM32_ATIM_CCR1_OFFSET)
# define STM32_TIM1_CCR2 (STM32_TIM1_BASE+STM32_ATIM_CCR2_OFFSET)
# define STM32_TIM1_CCR3 (STM32_TIM1_BASE+STM32_ATIM_CCR3_OFFSET)
# define STM32_TIM1_CCR4 (STM32_TIM1_BASE+STM32_ATIM_CCR4_OFFSET)
-# ifdef CONFIG_STM32_STM32F10XX
-# define STM32_TIM1_BDTR (STM32_TIM1_BASE+STM32_ATIM_BDTR_OFFSET)
-# endif
+# 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)
#endif
@@ -157,16 +147,12 @@
# define STM32_TIM8_CNT (STM32_TIM8_BASE+STM32_ATIM_CNT_OFFSET)
# define STM32_TIM8_PSC (STM32_TIM8_BASE+STM32_ATIM_PSC_OFFSET)
# define STM32_TIM8_ARR (STM32_TIM8_BASE+STM32_ATIM_ARR_OFFSET)
-# ifdef CONFIG_STM32_STM32F10XX
-# define STM32_TIM8_RCR (STM32_TIM8_BASE+STM32_ATIM_RCR_OFFSET)
-# endif
+# define STM32_TIM8_RCR (STM32_TIM8_BASE+STM32_ATIM_RCR_OFFSET)
# define STM32_TIM8_CCR1 (STM32_TIM8_BASE+STM32_ATIM_CCR1_OFFSET)
# define STM32_TIM8_CCR2 (STM32_TIM8_BASE+STM32_ATIM_CCR2_OFFSET)
# define STM32_TIM8_CCR3 (STM32_TIM8_BASE+STM32_ATIM_CCR3_OFFSET)
# define STM32_TIM8_CCR4 (STM32_TIM8_BASE+STM32_ATIM_CCR4_OFFSET)
-# ifdef CONFIG_STM32_STM32F10XX
-# define STM32_TIM8_BDTR (STM32_TIM8_BASE+STM32_ATIM_BDTR_OFFSET)
-# endif
+# 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)
#endif
@@ -402,29 +388,23 @@
/* Control register 2 */
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_CR2_CCPC (1 << 0) /* Bit 0: Capture/Compare Preloaded Control */
-# define ATIM_CR2_CCUS (1 << 2) /* Bit 2: Capture/Compare Control Update Selection */
-#endif
-
+#define ATIM_CR2_CCPC (1 << 0) /* Bit 0: Capture/Compare Preloaded Control */
+#define ATIM_CR2_CCUS (1 << 2) /* Bit 2: Capture/Compare Control Update Selection */
#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 */
+#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 */
#define ATIM_CR2_TI1S (1 << 7) /* Bit 7: TI1 Selection */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# 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) */
-# define ATIM_CR2_OIS2 (1 << 10) /* Bit 10: Output Idle state 2 (OC2 output) */
-# define ATIM_CR2_OIS2N (1 << 11) /* Bit 11: Output Idle state 2 (OC2N output) */
-# define ATIM_CR2_OIS3 (1 << 12) /* Bit 12: Output Idle state 3 (OC3 output) */
-# 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) */
-#endif
+#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) */
+#define ATIM_CR2_OIS2 (1 << 10) /* Bit 10: Output Idle state 2 (OC2 output) */
+#define ATIM_CR2_OIS2N (1 << 11) /* Bit 11: Output Idle state 2 (OC2N output) */
+#define ATIM_CR2_OIS3 (1 << 12) /* Bit 12: Output Idle state 3 (OC3 output) */
+#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) */
/* Slave mode control register */
@@ -667,27 +647,15 @@
#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 */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_CCER_CC1NE (1 << 2) /* Bit 2: Capture/Compare 1 Complementary output enable */
-#endif
-
+#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_CC2E (1 << 4) /* Bit 4: Capture/Compare 2 output enable */
#define ATIM_CCER_CC2P (1 << 5) /* Bit 5: Capture/Compare 2 output Polarity */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_CCER_CC2NE (1 << 6) /* Bit 6: Capture/Compare 2 Complementary output enable */
-#endif
-
+#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_CC3E (1 << 8) /* Bit 8: Capture/Compare 3 output enable */
#define ATIM_CCER_CC3P (1 << 9) /* Bit 9: Capture/Compare 3 output Polarity */
-
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_CCER_CC3NE (1 << 10) /* Bit 10: Capture/Compare 3 Complementary output enable */
-#endif
-
+#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_CC4E (1 << 12) /* Bit 12: Capture/Compare 4 output enable */
#define ATIM_CCER_CC4P (1 << 13) /* Bit 13: Capture/Compare 4 output Polarity */
@@ -698,29 +666,25 @@
/* Repetition counter register */
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_RCR_REP_SHIFT (0) /* Bits 7-0: Repetition Counter Value */
-# define ATIM_RCR_REP_MASK (0xff << ATIM_RCR_REP_SHIFT)
-#endif
+#define ATIM_RCR_REP_SHIFT (0) /* Bits 7-0: Repetition Counter Value */
+#define ATIM_RCR_REP_MASK (0xff << ATIM_RCR_REP_SHIFT)
/* Break and dead-time register */
-#ifdef CONFIG_STM32_STM32F10XX
-# define ATIM_BDTR_DTG_SHIFT (0) /* Bits 7:0 [7:0]: Dead-Time Generator set-up */
-# define ATIM_BDTR_DTG_MASK (0xff << ATIM_BDTR_DTG_SHIFT)
-# define ATIM_BDTR_LOCK_SHIFT (8) /* Bits 9:8 [1:0]: Lock Configuration */
-# define ATIM_BDTR_LOCK_MASK (3 << ATIM_BDTR_LOCK_SHIFT)
-# define ATIM_BDTR_LOCKOFF (0 << ATIM_BDTR_LOCK_SHIFT) /* 00: LOCK OFF - No bit is write protected */
-# define ATIM_BDTR_LOCK1 (1 << ATIM_BDTR_LOCK_SHIFT) /* 01: LOCK Level 1 protection */
-# define ATIM_BDTR_LOCK2 (2 << ATIM_BDTR_LOCK_SHIFT) /* 10: LOCK Level 2 protection */
-# define ATIM_BDTR_LOCK3 (3 << ATIM_BDTR_LOCK_SHIFT) /* 11: LOCK Level 3 protection */ */
-# define ATIM_BDTR_OSSI (1 << 10) /* Bit 10: Off-State Selection for Idle mode */
-# define ATIM_BDTR_OSSR (1 << 11) /* Bit 11: Off-State Selection for Run mode */
-# define ATIM_BDTR_BKE (1 << 12) /* Bit 12: Break enable */
-# define ATIM_BDTR_BKP (1 << 13) /* Bit 13: Break Polarity */
-# define ATIM_BDTR_AOE (1 << 14) /* Bit 14: Automatic Output enable */
-# define ATIM_BDTR_MOE (1 << 15) /* Bit 15: Main Output enable */
-#endif
+#define ATIM_BDTR_DTG_SHIFT (0) /* Bits 7:0 [7:0]: Dead-Time Generator set-up */
+#define ATIM_BDTR_DTG_MASK (0xff << ATIM_BDTR_DTG_SHIFT)
+#define ATIM_BDTR_LOCK_SHIFT (8) /* Bits 9:8 [1:0]: Lock Configuration */
+#define ATIM_BDTR_LOCK_MASK (3 << ATIM_BDTR_LOCK_SHIFT)
+# define ATIM_BDTR_LOCKOFF (0 << ATIM_BDTR_LOCK_SHIFT) /* 00: LOCK OFF - No bit is write protected */
+# define ATIM_BDTR_LOCK1 (1 << ATIM_BDTR_LOCK_SHIFT) /* 01: LOCK Level 1 protection */
+# define ATIM_BDTR_LOCK2 (2 << ATIM_BDTR_LOCK_SHIFT) /* 10: LOCK Level 2 protection */
+# define ATIM_BDTR_LOCK3 (3 << ATIM_BDTR_LOCK_SHIFT) /* 11: LOCK Level 3 protection */ */
+#define ATIM_BDTR_OSSI (1 << 10) /* Bit 10: Off-State Selection for Idle mode */
+#define ATIM_BDTR_OSSR (1 << 11) /* Bit 11: Off-State Selection for Run mode */
+#define ATIM_BDTR_BKE (1 << 12) /* Bit 12: Break enable */
+#define ATIM_BDTR_BKP (1 << 13) /* Bit 13: Break Polarity */
+#define ATIM_BDTR_AOE (1 << 14) /* Bit 14: Automatic Output enable */
+#define ATIM_BDTR_MOE (1 << 15) /* Bit 15: Main Output enable */
/* DMA control register */
@@ -843,7 +807,7 @@
#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) (TIM2-5 and TIM9-14) */
+/* 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 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_pwm.c b/nuttx/arch/arm/src/stm32/stm32_pwm.c
index 8646bfcd7..141b7bb43 100644
--- a/nuttx/arch/arm/src/stm32/stm32_pwm.c
+++ b/nuttx/arch/arm/src/stm32/stm32_pwm.c
@@ -42,9 +42,11 @@
#include <stdint.h>
#include <stdio.h>
#include <assert.h>
+#include <errno.h>
#include <debug.h>
#include <nuttx/pwm.h>
+#include <arch/board/board.h>
#include "up_internal.h"
#include "up_arch.h"
@@ -59,8 +61,7 @@
#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM2_PWM) || \
defined(CONFIG_STM32_TIM3_PWM) || defined(CONFIG_STM32_TIM4_PWM) || \
- defined(CONFIG_STM32_TIM5_PWM) || defined(CONFIG_STM32_TIM6_PWM) || \
- defined(CONFIG_STM32_TIM7_PWM) || defined(CONFIG_STM32_TIM8_PWM) || \
+ defined(CONFIG_STM32_TIM5_PWM) || defined(CONFIG_STM32_TIM8_PWM) || \
defined(CONFIG_STM32_TIM9_PWM) || defined(CONFIG_STM32_TIM10_PWM) || \
defined(CONFIG_STM32_TIM11_PWM) || defined(CONFIG_STM32_TIM12_PWM) || \
defined(CONFIG_STM32_TIM13_PWM) || defined(CONFIG_STM32_TIM14_PWM)
@@ -68,6 +69,19 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_DEBUG_PWM
+# define pwmdbg dbg
+# define pwmvdbg vdbg
+# define pwmlldbg lldbg
+# define pwmllvdbg llvdbg
+#else
+# define pwmdbg(x...)
+# define pwmvdbg(x...)
+# define pwmlldbg(x...)
+# define pwmllvdbg(x...)
+#endif
/****************************************************************************
* Private Types
@@ -76,12 +90,26 @@
struct stm32_pwmtimer_s
{
- uint32_t base; /* The base address of the timer */
+ FAR const struct pwm_ops_s *ops; /* PWM operations */
+ uint8_t timid; /* Timer ID {1,...,14} */
+ uint8_t channel; /* Timer output channel: {1,..4} */
+ uint8_t unused2;
+ uint8_t unused3;
+ uint32_t base; /* The base address of the timer */
+ uint32_t pincfg; /* Output pin configuration */
+ uint32_t pclk; /* The frequency of the peripheral clock
+ * that drives the timer module. */
};
/****************************************************************************
* Static Function Prototypes
****************************************************************************/
+/* Register access */
+
+static uint16_t pwm_getreg(struct stm32_pwmtimer_s *priv, int offset);
+static void pwm_putreg(struct stm32_pwmtimer_s *priv, int offset, uint16_t value);
+
+/* PWM driver methods */
static int pwm_setup(FAR struct pwm_lowerhalf_s *dev);
static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev);
@@ -97,125 +125,155 @@ static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg
static const struct pwm_ops_s g_pwmops =
{
- .setup = pwm_setup(FAR struct pwm_lowerhalf_s *dev);
- .shutdown = pwm_shutdown(FAR struct pwm_lowerhalf_s *dev);
- .start = pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_s *info);
- .stop = pwm_stop(FAR struct pwm_lowerhalf_s *dev);
- .pulsecount = pwm_pulsecount(FAR struct pwm_lowerhalf_s *dev, FAR pwm_count_t *count);
- .ioctl = pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg);
+ .setup = pwm_setup,
+ .shutdown = pwm_shutdown,
+ .start = pwm_start,
+ .stop = pwm_stop,
+ .pulsecount = pwm_pulsecount,
+ .ioctl = pwm_ioctl,
};
-/* The following represent the state of each possible PWM driver */
-
#ifdef CONFIG_STM32_TIM1_PWM
static struct stm32_pwmtimer_s g_pwm1dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM1_BASE;
+ .ops = &g_pwmops,
+ .timid = 1,
+ .channel = CONFIG_STM32_TIM1_CHANNEL,
+ .base = STM32_TIM1_BASE,
+ .pincfg = PWM_TIM1_PINCFG,
+ .pclk = STM32_PCLK2_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM2_PWM
static struct stm32_pwmtimer_s g_pwm2dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM2_BASE;
+ .ops = &g_pwmops,
+ .timid = 2,
+ .channel = CONFIG_STM32_TIM2_CHANNEL,
+ .base = STM32_TIM2_BASE,
+ .pincfg = PWM_TIM2_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM3_PWM
static struct stm32_pwmtimer_s g_pwm3dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM3_BASE;
+ .ops = &g_pwmops,
+ .timid = 3,
+ .channel = CONFIG_STM32_TIM3_CHANNEL,
+ .base = STM32_TIM3_BASE,
+ .pincfg = PWM_TIM3_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM4_PWM
static struct stm32_pwmtimer_s g_pwm4dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM4_BASE;
+ .ops = &g_pwmops,
+ .timid = 4,
+ .channel = CONFIG_STM32_TIM4_CHANNEL,
+ .base = STM32_TIM4_BASE,
+ .pincfg = PWM_TIM4_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM5_PWM
static struct stm32_pwmtimer_s g_pwm5dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM5_BASE;
-};
-#endif
-
-#ifdef CONFIG_STM32_TIM6_PWM
-static struct stm32_pwmtimer_s g_pwm6dev =
-{
- .ops = *g_pwmops;
- .base = STM32_TIM6_BASE;
-};
-#endif
-
-#ifdef CONFIG_STM32_TIM7_PWM
-static struct stm32_pwmtimer_s g_pwm7dev =
-{
- .ops = *g_pwmops;
- .base = STM32_TIM7_BASE;
+ .ops = &g_pwmops,
+ .timid = 5,
+ .channel = CONFIG_STM32_TIM5_CHANNEL,
+ .base = STM32_TIM5_BASE,
+ .pincfg = PWM_TIM5_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM8_PWM
static struct stm32_pwmtimer_s g_pwm8dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM8_BASE;
+ .ops = &g_pwmops,
+ .timid = 8,
+ .channel = CONFIG_STM32_TIM8_CHANNEL,
+ .base = STM32_TIM8_BASE,
+ .pincfg = PWM_TIM8_PINCFG,
+ .pclk = STM32_PCLK2_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM9_PWM
static struct stm32_pwmtimer_s g_pwm9dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM9_BASE;
+ .ops = &g_pwmops,
+ .timid = 9,
+ .channel = CONFIG_STM32_TIM9_CHANNEL,
+ .base = STM32_TIM9_BASE,
+ .pincfg = PWM_TIM9_PINCFG,
+ .pclk = STM32_PCLK2_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM10_PWM
static struct stm32_pwmtimer_s g_pwm10dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM10_BASE;
+ .ops = &g_pwmops,
+ .timid = 10,
+ .channel = CONFIG_STM32_TIM10_CHANNEL,
+ .base = STM32_TIM10_BASE,
+ .pincfg = PWM_TIM10_PINCFG,
+ .pclk = STM32_PCLK2_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM11_PWM
static struct stm32_pwmtimer_s g_pwm11dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM11_BASE;
+ .ops = &g_pwmops,
+ .timid = 11,
+ .channel = CONFIG_STM32_TIM11_CHANNEL,
+ .base = STM32_TIM11_BASE,
+ .pincfg = PWM_TIM11_PINCFG,
+ .pclk = STM32_PCLK2_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM12_PWM
static struct stm32_pwmtimer_s g_pwm12dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM12_BASE;
+ .ops = &g_pwmops,
+ .timid = 12,
+ .channel = CONFIG_STM32_TIM12_CHANNEL,
+ .base = STM32_TIM12_BASE,
+ .pincfg = PWM_TIM12_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM13_PWM
static struct stm32_pwmtimer_s g_pwm13dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM13_BASE;
+ .ops = &g_pwmops,
+ .timid = 13,
+ .channel = CONFIG_STM32_TIM13_CHANNEL,
+ .base = STM32_TIM13_BASE,
+ .pincfg = PWM_TIM13_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
#ifdef CONFIG_STM32_TIM14_PWM
static struct stm32_pwmtimer_s g_pwm14dev =
{
- .ops = *g_pwmops;
- .base = STM32_TIM14_BASE;
+ .ops = &g_pwmops,
+ .timid = 14,
+ .channel = CONFIG_STM32_TIM14_CHANNEL,
+ .base = STM32_TIM14_BASE,
+ .pincfg = PWM_TIM14_PINCFG,
+ .pclk = STM32_PCLK1_FREQUENCY,
};
#endif
@@ -224,6 +282,46 @@ static struct stm32_pwmtimer_s g_pwm14dev =
****************************************************************************/
/****************************************************************************
+ * Name: pwm_getreg
+ *
+ * Description:
+ * Read the value of an ADC timer register.
+ *
+ * Input Parameters:
+ * priv - A reference to the ADC block status
+ * offset - The offset to the register to read
+ *
+ * Returned Value:
+ * The current contents of the specified register
+ *
+ ****************************************************************************/
+
+static uint16_t pwm_getreg(struct stm32_pwmtimer_s *priv, int offset)
+{
+ return getreg16(priv->base + offset);
+}
+
+/****************************************************************************
+ * Name: pwm_putreg
+ *
+ * Description:
+ * Read the value of an ADC timer register.
+ *
+ * Input Parameters:
+ * priv - A reference to the ADC block status
+ * offset - The offset to the register to read
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void pwm_putreg(struct stm32_pwmtimer_s *priv, int offset, uint16_t value)
+{
+ putreg16(value, priv->base + offset);
+}
+
+/****************************************************************************
* Name: pwm_setup
*
* Description:
@@ -237,12 +335,20 @@ static struct stm32_pwmtimer_s g_pwm14dev =
* Returned Value:
* Zero on success; a negated errno value on failure
*
+ * Assumptions:
+ * AHB1 or 2 clocking for the GPIOs and timer has already been configured
+ * by the RCC logic at power up.
+ *
****************************************************************************/
static int pwm_setup(FAR struct pwm_lowerhalf_s *dev)
{
-#warning "Missing logic"
- return -ENOSYS;
+ FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
+
+ /* Configure the PWM output pin, but do not start the timer yet */
+
+ stm32_configgpio(priv->pincfg);
+ return OK;
}
/****************************************************************************
@@ -263,8 +369,27 @@ static int pwm_setup(FAR struct pwm_lowerhalf_s *dev)
static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
{
-#warning "Missing logic"
- return -ENOSYS;
+ FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
+ uint32_t pincfg;
+
+ /* Make sure that the output has been stopped */
+
+ pwm_stop(dev);
+
+ /* Then put the GPIO pin back to the default state */
+
+ pincfg = priv->pincfg & (GPIO_PORT_MASK|GPIO_PIN_MASK);
+
+#if defined(CONFIG_STM32_STM32F10XX)
+ pincfg |= (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT);
+#elif defined(CONFIG_STM32_STM32F40XX)
+ pincfg |= (GPIO_INPUT|GPIO_FLOAT);
+#else
+# error "Unrecognized STM32 chip"
+#endif
+
+ stm32_configgpio(pincfg);
+ return OK;
}
/****************************************************************************
@@ -284,8 +409,281 @@ static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_s *info)
{
-#warning "Missing logic"
- return -ENOSYS;
+ FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
+
+ /* Calculated values */
+
+ uint32_t prescaler;
+ uint32_t timclk;
+ uint32_t reload;
+ uint32_t ccr;
+
+ /* Register contents */
+
+ uint16_t cr1;
+ uint16_t ccer;
+ uint16_t cr2;
+ uint16_t ccmr1;
+ uint16_t ccmr2;
+
+ /* New timer regiser bit settings */
+
+ uint16_t ccenable;
+ uint16_t ocmode1;
+ uint16_t ocmode2;
+
+ /* Caculate optimal values for the timer prescaler and for the timer reload
+ * register. If' frequency' is the desired frequency, then
+ *
+ * reload = timclk / frequency
+ * timclk = pclk / presc
+ *
+ * Or,
+ *
+ * reload = pclk / presc / frequency
+ *
+ * There are many solutions to this this, but the best solution will be the
+ * one that has the largest reload value and the smallest prescaler value.
+ * That is the solution that should give us the most accuracy in the timer
+ * control. Subject to:
+ *
+ * 0 <= presc <= 65536
+ * 1 <= reload <= 65535
+ *
+ * So presc = pclk / 65535 / frequency would be optimal.
+ *
+ * Example:
+ *
+ * pclk = 42 MHz
+ * frequency = 100 Hz
+ *
+ * prescaler = 42,000,000 / 65,535 / 100
+ * = 6.4 (or 7 -- taking the ceiling always)
+ * timclk = 42,000,000 / 7
+ * = 6,000,000
+ * reload = 7,000,000 / 100
+ * = 60,000
+ */
+
+ prescaler = (priv->pclk / info->frequency + 65534) / 65535;
+ if (prescaler < 1)
+ {
+ prescaler = 1;
+ }
+ else if (prescaler > 65536)
+ {
+ prescaler = 65536;
+ }
+
+ timclk = priv->pclk / prescaler;
+
+ reload = timclk / info->frequency;
+ if (reload < 1)
+ {
+ reload = 1;
+ }
+ else if (reload > 65535)
+ {
+ reload = 65535;
+ }
+
+ pwmvdbg("TIM%d PCLK: %d frequency: %d TIMCLK: %d prescaler: %d reload: %d\n",
+ priv->timid, priv->pclk, info->frequency, timclk, prescaler, reload);
+
+ /* Set up the timer CR1 register:
+ *
+ * 1-8 CKD[1:0] ARPE CMS[1:0] DIR OPM URS UDIS CEN
+ * 2-5 CKD[1:0] ARPE CMS DIR OPM URS UDIS CEN
+ * 6-7 ARPE OPM URS UDIS CEN
+ * 9-14 CKD[1:0] ARPE URS UDIS CEN
+ */
+
+ cr1 = pwm_getreg(priv, STM32_GTIM_CR1_OFFSET);
+
+ /* Disable the timer until we get it configured */
+
+ cr1 &= ~GTIM_CR1_CEN;
+
+ /* Set the counter mode for the advanced timers (1,8) and most general
+ * purpose timers (2-5, but not 9-14):
+ */
+
+#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM2_PWM) || \
+ defined(CONFIG_STM32_TIM3_PWM) || defined(CONFIG_STM32_TIM4_PWM) || \
+ defined(CONFIG_STM32_TIM5_PWM) || defined(CONFIG_STM32_TIM8_PWM)
+
+ if ((priv->timid >= 1 && priv->timid <= 5) || priv->timid == 8)
+ {
+ /* Select the Counter Mode == count up:
+ *
+ * ATIM_CR1_EDGE: The counter counts up or down depending on the
+ * direction bit(DIR).
+ * ATIM_CR1_DIR: 0: count up, 1: count down
+ */
+
+ cr1 &= ~(ATIM_CR1_DIR | ATIM_CR1_CMS_MASK);
+ cr1 |= ATIM_CR1_EDGE;
+ }
+#endif
+
+ /* Set the clock division to zero for all (but the basic timers, but there
+ * should be no basic timers in this context
+ */
+
+ cr1 &= ~GTIM_CR1_CKD_MASK;
+ pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
+
+ /* Set the reload and prescaler values */
+
+ pwm_putreg(priv, STM32_GTIM_ARR_OFFSET, reload);
+ pwm_putreg(priv, STM32_GTIM_PSC_OFFSET, prescaler - 1);
+
+ /* Clear the advanced timers repitition counter in all but the advanced timers */
+
+#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM)
+ if (priv->timid == 1 || priv->timid == 8)
+ {
+ pwm_putreg(priv, STM32_ATIM_RCR_OFFSET, 0);
+ }
+#endif
+
+ /* Generate an update event to reload the prescaler (all timers) */
+
+ pwm_putreg(priv, STM32_GTIM_EGR_OFFSET, ATIM_EGR_UG);
+
+ /* Duty cycle:
+ *
+ * duty cycle = ccr / reload (fractional value)
+ */
+
+ ccr = b16toi(info->duty * reload + b16HALF);
+
+ /* Handle channel specific setup */
+
+ ocmode1 = 0;
+ ocmode2 = 0;
+ switch (priv->channel)
+ {
+ case 1: /* PWM Mode configuration: Channel 1 */
+ {
+ ccenable = ATIM_CCER_CC1E;
+ ocmode1 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR1_CC1S_SHIFT) |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) |
+ ATIM_CCMR1_OC1PE;
+ }
+ break;
+
+ case 2: /* PWM Mode configuration: Channel 2 */
+ {
+ ccenable = ATIM_CCER_CC2E;
+ ocmode1 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR1_CC2S_SHIFT) |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) |
+ ATIM_CCMR1_OC2PE;
+ }
+ break;
+
+ case 3: /* PWM Mode configuration: Channel3 */
+ {
+ ccenable = ATIM_CCER_CC3E;
+ ocmode2 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR2_CC3S_SHIFT) |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) |
+ ATIM_CCMR2_OC3PE;
+ }
+ break;
+
+ case 4: /* PWM1 Mode configuration: Channel4 */
+ {
+ ccenable = ATIM_CCER_CC4E;
+ ocmode2 = (ATIM_CCMR_CCS_CCOUT << ATIM_CCMR2_CC4S_SHIFT) |
+ (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC4M_SHIFT) |
+ ATIM_CCMR2_OC4PE;
+ }
+ break;
+
+ default:
+ return -EINVAL;
+ }
+
+ /* Disable the Channel by resetting the CCxE Bit in the CCER register */
+
+ ccer = pwm_getreg(priv, STM32_GTIM_CCER_OFFSET);
+ ccer &= ~ccenable;
+ pwm_putreg(priv, STM32_GTIM_CCER_OFFSET, ccer);
+
+ /* Fetch the CR2, CCMR1, and CCMR2 register (already have cr1 and ccer) */
+
+ cr2 = pwm_getreg(priv, STM32_GTIM_CR2_OFFSET);
+ ccmr1 = pwm_getreg(priv, STM32_GTIM_CCMR1_OFFSET);
+ ccmr2 = pwm_getreg(priv, STM32_GTIM_CCMR1_OFFSET);
+
+ /* Reset the Output Compare Mode Bits and set the select output compare mode */
+
+ ccmr1 &= ~(ATIM_CCMR1_CC1S_MASK | ATIM_CCMR1_OC1M_MASK | ATIM_CCMR1_OC1PE |
+ ATIM_CCMR1_CC2S_MASK | ATIM_CCMR1_OC2M_MASK | ATIM_CCMR1_OC2PE);
+ ccmr2 &= ~(ATIM_CCMR2_CC3S_MASK | ATIM_CCMR2_OC3M_MASK | ATIM_CCMR2_OC3PE |
+ ATIM_CCMR2_CC4S_MASK | ATIM_CCMR2_OC4M_MASK | ATIM_CCMR2_OC4PE);
+ ccmr1 |= ocmode1;
+ ccmr2 |= ocmode2;
+
+ /* Reset the output polarity level of all channels (selects high polarity)*/
+
+ ccer &= ~(ATIM_CCER_CC1P | ATIM_CCER_CC2P | ATIM_CCER_CC3P | ATIM_CCER_CC4P);
+
+ /* Enable the output state of the selected channel (only) */
+
+ ccer &= ~(ATIM_CCER_CC1E | ATIM_CCER_CC2E | ATIM_CCER_CC3E | ATIM_CCER_CC4E);
+ ccer |= ccenable;
+
+ /* Some special setup for advanced timers */
+
+#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM)
+ if (priv->timid == 1 || priv->timid == 8)
+ {
+ /* Reset output N polarity level, output N state, output compre state,
+ * output compare N idle state.
+ */
+
+#ifdef CONFIG_STM32_STM32F40XX
+ ccer &= ~(ATIM_CCER_CC1NE | ATIM_CCER_CC1NP | ATIM_CCER_CC2NE | ATIM_CCER_CC2NP |
+ ATIM_CCER_CC3NE | ATIM_CCER_CC3NP | ATIM_CCER_CC4NP);
+#else
+ ccer &= ~(ATIM_CCER_CC1NE | ATIM_CCER_CC1NP | ATIM_CCER_CC2NE | ATIM_CCER_CC2NP |
+ ATIM_CCER_CC3NE | ATIM_CCER_CC3NP);
+#endif
+
+ /* Reset the output compare and output compare N IDLE State */
+
+ cr2 &= ~(ATIM_CR2_OIS1 | ATIM_CR2_OIS1N | ATIM_CR2_OIS2 | ATIM_CR2_OIS2N |
+ ATIM_CR2_OIS3 | ATIM_CR2_OIS3N | ATIM_CR2_OIS4);
+ }
+#ifdef CONFIG_STM32_STM32F40XX
+ else
+#endif
+#endif
+#ifdef CONFIG_STM32_STM32F40XX
+ {
+ ccer &= ~(GTIM_CCER_CC1NP | GTIM_CCER_CC2NP | GTIM_CCER_CC3NP | GTIM_CCER_CC4NP);
+ }
+#endif
+
+ /* Save the modified register values */
+
+ pwm_putreg(priv, STM32_GTIM_CR2_OFFSET, cr2);
+ pwm_putreg(priv, STM32_GTIM_CCMR1_OFFSET, ccmr1);
+ pwm_putreg(priv, STM32_GTIM_CCMR1_OFFSET, ccmr2);
+ pwm_putreg(priv, STM32_GTIM_CCER_OFFSET, ccer);
+
+ /* Set the ARR Preload Bit */
+
+ cr1 = pwm_getreg(priv, STM32_GTIM_CR1_OFFSET);
+ cr1 |= GTIM_CR1_ARPE;
+ pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, ccmr2);
+
+ /* And, finally, enable the timer */
+
+ cr1 |= GTIM_CR1_CEN;
+ pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, ccmr2);
+ return OK;
}
/****************************************************************************
@@ -304,8 +702,99 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
{
-#warning "Missing logic"
- return -ENOSYS;
+ FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
+
+ uint32_t resetbit;
+ uint32_t regaddr;
+ uint32_t regval;
+
+ switch (priv->timid)
+ {
+#ifdef CONFIG_STM32_TIM1_PWM
+ case 1:
+ regaddr = STM32_RCC_APB2RSTR;
+ resetbit = RCC_APB2RSTR_TIM1RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM2_PWM
+ case 2:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM2RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM3_PWM
+ case 3:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM3RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM4_PWM
+ case 4:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM4RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM5_PWM
+ case 5:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM5RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM8_PWM
+ case 8:
+ regaddr = STM32_RCC_APB2RSTR;
+ resetbit = RCC_APB2RSTR_TIM8RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM9_PWM
+ case 9:
+ regaddr = STM32_RCC_APB2RSTR;
+ resetbit = RCC_APB2RSTR_TIM9RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM10_PWM
+ case 10:
+ regaddr = STM32_RCC_APB2RSTR;
+ resetbit = RCC_APB2RSTR_TIM10RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM11_PWM
+ case 11:
+ regaddr = STM32_RCC_APB2RSTR;
+ resetbit = RCC_APB2RSTR_TIM11RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM12_PWM
+ case 12:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM12RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM13_PWM
+ case 13:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM13RST;
+ break;
+#endif
+#ifdef CONFIG_STM32_TIM14_PWM
+ case 14:
+ regaddr = STM32_RCC_APB1RSTR;
+ resetbit = RCC_APB1RSTR_TIM14RST;
+ break;
+#endif
+ }
+
+ /* Reset the timer - stopping the output and putting the timer back
+ * into a state where pwm_start() can be called.
+ */
+
+ regval = getreg32(regaddr);
+ regval |= resetbit;
+ putreg32(regval, regaddr);
+
+ regval &= ~resetbit;
+ putreg32(regval, regaddr);
+ return OK;
}
/****************************************************************************
@@ -404,16 +893,6 @@ FAR struct pwm_lowerhalf_s *stm32_pwminitialize(int timer)
lower = &g_pwm5dev;
break;
#endif
-#ifdef CONFIG_STM32_TIM6_PWM
- case 6:
- lower = &g_pwm6dev;
- break;
-#endif
-#ifdef CONFIG_STM32_TIM7_PWM
- case 7:
- lower = &g_pwm7dev;
- break;
-#endif
#ifdef CONFIG_STM32_TIM8_PWM
case 8:
lower = &g_pwm8dev;
diff --git a/nuttx/arch/arm/src/stm32/stm32_pwm.h b/nuttx/arch/arm/src/stm32/stm32_pwm.h
index 6204cda21..bd881d3d4 100644
--- a/nuttx/arch/arm/src/stm32/stm32_pwm.h
+++ b/nuttx/arch/arm/src/stm32/stm32_pwm.h
@@ -49,7 +49,6 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "chip/stm32_tim.h"
/************************************************************************************
* Pre-processor Definitions
@@ -76,12 +75,6 @@
#ifndef CONFIG_STM32_TIM5
# undef CONFIG_STM32_TIM5_PWM
#endif
-#ifndef CONFIG_STM32_TIM6
-# undef CONFIG_STM32_TIM6_PWM
-#endif
-#ifndef CONFIG_STM32_TIM7
-# undef CONFIG_STM32_TIM7_PWM
-#endif
#ifndef CONFIG_STM32_TIM8
# undef CONFIG_STM32_TIM8_PWM
#endif
@@ -104,6 +97,228 @@
# undef CONFIG_STM32_TIM14_PWM
#endif
+/* The basic timers (timer 6 and 7) are not capable of generating output pulses */
+
+#undef CONFIG_STM32_TIM6_PWM
+#undef CONFIG_STM32_TIM7_PWM
+
+/* Check if PWM support for any channel is enabled. */
+
+#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM2_PWM) || \
+ defined(CONFIG_STM32_TIM3_PWM) || defined(CONFIG_STM32_TIM4_PWM) || \
+ defined(CONFIG_STM32_TIM5_PWM) || defined(CONFIG_STM32_TIM8_PWM) || \
+ defined(CONFIG_STM32_TIM9_PWM) || defined(CONFIG_STM32_TIM10_PWM) || \
+ defined(CONFIG_STM32_TIM11_PWM) || defined(CONFIG_STM32_TIM12_PWM) || \
+ defined(CONFIG_STM32_TIM13_PWM) || defined(CONFIG_STM32_TIM14_PWM)
+
+#include <arch/board/board.h>
+#include "chip/stm32_tim.h"
+
+/* For each timer that is enabled for PWM usage, we need the following additional
+ * configuration settings:
+ *
+ * CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+ * PWM_TIMx_CHn - One of the values defined in chip/stm32*_pinmap.h. In the case
+ * where there are multiple pin selections, the correct setting must be provided
+ * in the arch/board/board.h file.
+ *
+ * NOTE: The STM32 timers are each capable of generating different signals on
+ * each of the four channels with different duty cycles. That capability is
+ * not supported by this driver: Only one output channel per timer.
+ */
+
+#ifdef CONFIG_STM32_TIM1_PWM
+# if !defined(CONFIG_STM32_TIM1_CHANNEL)
+# error "CONFIG_STM32_TIM1_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM1_CHANNEL == 1
+# define PWM_TIM1_PINCFG GPIO_TIM1_CH1
+# elif CONFIG_STM32_TIM1_CHANNEL == 2
+# define PWM_TIM1_PINCFG GPIO_TIM1_CH2
+# elif CONFIG_STM32_TIM1_CHANNEL == 3
+# define PWM_TIM1_PINCFG GPIO_TIM1_CH3
+# elif CONFIG_STM32_TIM1_CHANNEL == 4
+# define PWM_TIM1_PINCFG GPIO_TIM1_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM1_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM2_PWM
+# if !defined(CONFIG_STM32_TIM2_CHANNEL)
+# error "CONFIG_STM32_TIM2_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM2_CHANNEL == 1
+# define PWM_TIM2_PINCFG GPIO_TIM2_CH1
+# elif CONFIG_STM32_TIM2_CHANNEL == 2
+# define PWM_TIM2_PINCFG GPIO_TIM2_CH2
+# elif CONFIG_STM32_TIM2_CHANNEL == 3
+# define PWM_TIM2_PINCFG GPIO_TIM2_CH3
+# elif CONFIG_STM32_TIM2_CHANNEL == 4
+# define PWM_TIM2_PINCFG GPIO_TIM2_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM2_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM3_PWM
+# if !defined(CONFIG_STM32_TIM3_CHANNEL)
+# error "CONFIG_STM32_TIM3_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM3_CHANNEL == 1
+# define PWM_TIM3_PINCFG GPIO_TIM3_CH1
+# elif CONFIG_STM32_TIM3_CHANNEL == 2
+# define PWM_TIM3_PINCFG GPIO_TIM3_CH2
+# elif CONFIG_STM32_TIM3_CHANNEL == 3
+# define PWM_TIM3_PINCFG GPIO_TIM3_CH3
+# elif CONFIG_STM32_TIM3_CHANNEL == 4
+# define PWM_TIM3_PINCFG GPIO_TIM3_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM3_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM4_PWM
+# if !defined(CONFIG_STM32_TIM4_CHANNEL)
+# error "CONFIG_STM32_TIM4_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM4_CHANNEL == 1
+# define PWM_TIM4_PINCFG GPIO_TIM4_CH1
+# elif CONFIG_STM32_TIM4_CHANNEL == 2
+# define PWM_TIM4_PINCFG GPIO_TIM4_CH2
+# elif CONFIG_STM32_TIM4_CHANNEL == 3
+# define PWM_TIM4_PINCFG GPIO_TIM4_CH3
+# elif CONFIG_STM32_TIM4_CHANNEL == 4
+# define PWM_TIM4_PINCFG GPIO_TIM4_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM4_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM5_PWM
+# if !defined(CONFIG_STM32_TIM5_CHANNEL)
+# error "CONFIG_STM32_TIM5_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM5_CHANNEL == 1
+# define PWM_TIM5_PINCFG GPIO_TIM5_CH1
+# elif CONFIG_STM32_TIM5_CHANNEL == 2
+# define PWM_TIM5_PINCFG GPIO_TIM5_CH2
+# elif CONFIG_STM32_TIM5_CHANNEL == 3
+# define PWM_TIM5_PINCFG GPIO_TIM5_CH3
+# elif CONFIG_STM32_TIM5_CHANNEL == 4
+# define PWM_TIM5_PINCFG GPIO_TIM5_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM5_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM8_PWM
+# if !defined(CONFIG_STM32_TIM8_CHANNEL)
+# error "CONFIG_STM32_TIM8_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM8_CHANNEL == 1
+# define PWM_TIM8_PINCFG GPIO_TIM8_CH1
+# elif CONFIG_STM32_TIM8_CHANNEL == 2
+# define PWM_TIM8_PINCFG GPIO_TIM8_CH2
+# elif CONFIG_STM32_TIM8_CHANNEL == 3
+# define PWM_TIM8_PINCFG GPIO_TIM8_CH3
+# elif CONFIG_STM32_TIM8_CHANNEL == 4
+# define PWM_TIM8_PINCFG GPIO_TIM8_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM8_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM9_PWM
+# if !defined(CONFIG_STM32_TIM9_CHANNEL)
+# error "CONFIG_STM32_TIM9_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM9_CHANNEL == 1
+# define PWM_TIM9_PINCFG GPIO_TIM9_CH1
+# elif CONFIG_STM32_TIM9_CHANNEL == 2
+# define PWM_TIM9_PINCFG GPIO_TIM9_CH2
+# elif CONFIG_STM32_TIM9_CHANNEL == 3
+# define PWM_TIM9_PINCFG GPIO_TIM9_CH3
+# elif CONFIG_STM32_TIM9_CHANNEL == 4
+# define PWM_TIM9_PINCFG GPIO_TIM9_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM9_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM10_PWM
+# if !defined(CONFIG_STM32_TIM10_CHANNEL)
+# error "CONFIG_STM32_TIM10_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM10_CHANNEL == 1
+# define PWM_TIM10_PINCFG GPIO_TIM10_CH1
+# elif CONFIG_STM32_TIM10_CHANNEL == 2
+# define PWM_TIM10_PINCFG GPIO_TIM10_CH2
+# elif CONFIG_STM32_TIM10_CHANNEL == 3
+# define PWM_TIM10_PINCFG GPIO_TIM10_CH3
+# elif CONFIG_STM32_TIM10_CHANNEL == 4
+# define PWM_TIM10_PINCFG GPIO_TIM10_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM10_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM11_PWM
+# if !defined(CONFIG_STM32_TIM11_CHANNEL)
+# error "CONFIG_STM32_TIM11_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM11_CHANNEL == 1
+# define PWM_TIM11_PINCFG GPIO_TIM11_CH1
+# elif CONFIG_STM32_TIM11_CHANNEL == 2
+# define PWM_TIM11_PINCFG GPIO_TIM11_CH2
+# elif CONFIG_STM32_TIM11_CHANNEL == 3
+# define PWM_TIM11_PINCFG GPIO_TIM11_CH3
+# elif CONFIG_STM32_TIM11_CHANNEL == 4
+# define PWM_TIM11_PINCFG GPIO_TIM11_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM11_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM12_PWM
+# if !defined(CONFIG_STM32_TIM12_CHANNEL)
+# error "CONFIG_STM32_TIM12_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM12_CHANNEL == 1
+# define PWM_TIM12_PINCFG GPIO_TIM12_CH1
+# elif CONFIG_STM32_TIM12_CHANNEL == 2
+# define PWM_TIM12_PINCFG GPIO_TIM12_CH2
+# elif CONFIG_STM32_TIM12_CHANNEL == 3
+# define PWM_TIM12_PINCFG GPIO_TIM12_CH3
+# elif CONFIG_STM32_TIM12_CHANNEL == 4
+# define PWM_TIM12_PINCFG GPIO_TIM12_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM12_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM13_PWM
+# if !defined(CONFIG_STM32_TIM13_CHANNEL)
+# error "CONFIG_STM32_TIM13_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM13_CHANNEL == 1
+# define PWM_TIM13_PINCFG GPIO_TIM13_CH1
+# elif CONFIG_STM32_TIM13_CHANNEL == 2
+# define PWM_TIM13_PINCFG GPIO_TIM13_CH2
+# elif CONFIG_STM32_TIM13_CHANNEL == 3
+# define PWM_TIM13_PINCFG GPIO_TIM13_CH3
+# elif CONFIG_STM32_TIM13_CHANNEL == 4
+# define PWM_TIM13_PINCFG GPIO_TIM13_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM13_CHANNEL"
+# endif
+#endif
+
+#ifdef CONFIG_STM32_TIM14_PWM)
+# if !defined(CONFIG_STM32_TIM14_CHANNEL)
+# error "CONFIG_STM32_TIM14_CHANNEL must be provided"
+# elif CONFIG_STM32_TIM14_CHANNEL == 1
+# define PWM_TIM14_PINCFG GPIO_TIM14_CH1
+# elif CONFIG_STM32_TIM14_CHANNEL == 2
+# define PWM_TIM14_PINCFG GPIO_TIM14_CH2
+# elif CONFIG_STM32_TIM14_CHANNEL == 3
+# define PWM_TIM14_PINCFG GPIO_TIM14_CH3
+# elif CONFIG_STM32_TIM14_CHANNEL == 4
+# define PWM_TIM14_PINCFG GPIO_TIM14_CH4
+# else
+# error "Unsupported value of CONFIG_STM32_TIM14_CHANNEL"
+# endif
+#endif
+
/************************************************************************************
* Public Types
************************************************************************************/
@@ -151,4 +366,5 @@ EXTERN FAR struct pwm_lowerhalf_s *stm32_pwminitialize(int timer);
#endif
#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_STM32_TIMx_PWM */
#endif /* __ARCH_ARM_SRC_STM32_STM32_TIM_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rtc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rtc.c
index d2f2ab0b4..c19521695 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rtc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rtc.c
@@ -162,7 +162,7 @@ static void rtc_dumpregs(FAR const char *msg)
rtclldbg(" BK0: %08x\n", getreg32(STM32_RTC_BK0R));
}
#else
-# define tc_dumpregs(msg)
+# define rtc_dumpregs(msg)
#endif
/************************************************************************************
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index eb7c49b95..f8868373f 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -492,8 +492,6 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_STM32_TIM3_PWM
CONFIG_STM32_TIM4_PWM
CONFIG_STM32_TIM5_PWM
- CONFIG_STM32_TIM6_PWM
- CONFIG_STM32_TIM7_PWM
CONFIG_STM32_TIM8_PWM
CONFIG_STM32_TIM1_ADC
@@ -514,7 +512,16 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_STM32_TIM7_DAC
CONFIG_STM32_TIM8_DAC
- Alternate pin mappings (should not be used with the STM3210E-EVAL board):
+ For each timer that is enabled for PWM usage, we need the following additional
+ configuration settings:
+
+ CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+
+ NOTE: The STM32 timers are each capable of generating different signals on
+ each of the four channels with different duty cycles. That capability is
+ not supported by this driver: Only one output channel per timer.
+
+ Alternate pin mappings (should not be used with the STM3210E-EVAL board):
CONFIG_STM32_TIM1_FULL_REMAP
CONFIG_STM32_TIM1_PARTIAL_REMAP
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index 257cb95e0..4fcc63938 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -371,8 +371,6 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_TIM3_PWM
CONFIG_STM32_TIM4_PWM
CONFIG_STM32_TIM5_PWM
- CONFIG_STM32_TIM6_PWM
- CONFIG_STM32_TIM7_PWM
CONFIG_STM32_TIM8_PWM
CONFIG_STM32_TIM9_PWM
CONFIG_STM32_TIM10_PWM
@@ -399,6 +397,15 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_TIM7_DAC
CONFIG_STM32_TIM8_DAC
+ For each timer that is enabled for PWM usage, we need the following additional
+ configuration settings:
+
+ CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+
+ NOTE: The STM32 timers are each capable of generating different signals on
+ each of the four channels with different duty cycles. That capability is
+ not supported by this driver: Only one output channel per timer.
+
JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
diff --git a/nuttx/include/nuttx/pwm.h b/nuttx/include/nuttx/pwm.h
index 2e954d2fc..4cf695b1d 100644
--- a/nuttx/include/nuttx/pwm.h
+++ b/nuttx/include/nuttx/pwm.h
@@ -115,7 +115,7 @@
struct pwm_info_s
{
uint32_t frequency; /* Frequency of the pulse train */
- b16_t duty; /* Duty of the pulse train, "1" to "0" duration */
+ ub16_t duty; /* Duty of the pulse train, "1" to "0" duration */
};
/* This type is used to return pulse counts */
@@ -211,7 +211,7 @@ extern "C" {
#endif
/****************************************************************************
- * "Upper-Half" ADC Driver Interfaces
+ * "Upper-Half" PWM Driver Interfaces
****************************************************************************/
/****************************************************************************
* Name: pwm_register
@@ -241,7 +241,7 @@ extern "C" {
int pwm_register(FAR const char *path, FAR struct pwm_lowerhalf_s *dev);
/****************************************************************************
- * Platform-Independent "Lower-Half" ADC Driver Interfaces
+ * Platform-Independent "Lower-Half" PWM Driver Interfaces
****************************************************************************/
#undef EXTERN