forked from Archive/PX4-Autopilot
Add basic support for pulse count in the PWM interface
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4285 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
d012f2fd06
commit
94e1048f0b
|
@ -2353,4 +2353,6 @@
|
|||
* arch/arm/src/stm32/stm32_serial.c and stm32_lowputc.c: Support for
|
||||
UART4-5 and USART6 added by Mike Smith. Also includes a more flexible
|
||||
way of managing UART pin configurations.
|
||||
* include/nuttx/pwm.h, drivers/pwm.c, arch/arm/src/stm32/stm32_pwm.c: Add
|
||||
support for pulse count in order to better support stepper motors.
|
||||
|
||||
|
|
|
@ -473,9 +473,8 @@ static void can_putcommon(uint32_t addr, uint32_t value)
|
|||
static void can_reset(FAR struct can_dev_s *dev)
|
||||
{
|
||||
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
|
||||
uint32_t baud;
|
||||
int ret;
|
||||
irqstate_t flags;
|
||||
int ret;
|
||||
|
||||
canvdbg("CAN%d\n", priv->port);
|
||||
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/pwm.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
|
@ -69,6 +70,41 @@
|
|||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
/* PWM/Timer Definitions ****************************************************/
|
||||
/* The following definitions are used to identify the various time types */
|
||||
|
||||
#define TIMTYPE_BASIC 0 /* Basic timers: TIM6-7 */
|
||||
#define TIMTYPE_GENERAL16 1 /* General 16-bit timers: TIM2-5 on F1 */
|
||||
#define TIMTYPE_COUNTUP16 2 /* General 16-bit count-up timers: TIM9-14 on F4 */
|
||||
#define TIMTYPE_GENERAL32 3 /* General 32-bit timers: TIM2-5 on F4 */
|
||||
#define TIMTYPE_ADVANCED 4 /* Advanced timers: TIM1-8 */
|
||||
|
||||
#define TIMTYPE_TIM1 TIMTYPE_ADVANCED
|
||||
#ifdef CONFIG_STM32_STM32F10XX
|
||||
# define TIMTYPE_TIM2 TIMTYPE_GENERAL16
|
||||
# define TIMTYPE_TIM3 TIMTYPE_GENERAL16
|
||||
# define TIMTYPE_TIM4 TIMTYPE_GENERAL16
|
||||
# define TIMTYPE_TIM5 TIMTYPE_GENERAL16
|
||||
#else
|
||||
# define TIMTYPE_TIM2 TIMTYPE_GENERAL32
|
||||
# define TIMTYPE_TIM3 TIMTYPE_GENERAL32
|
||||
# define TIMTYPE_TIM4 TIMTYPE_GENERAL32
|
||||
# define TIMTYPE_TIM5 TIMTYPE_GENERAL32
|
||||
#endif
|
||||
#define TIMTYPE_TIM6 TIMTYPE_BASIC
|
||||
#define TIMTYPE_TIM7 TIMTYPE_BASIC
|
||||
#define TIMTYPE_TIM8 TIMTYPE_ADVANCED
|
||||
#define TIMTYPE_TIM9 TIMTYPE_COUNTUP16
|
||||
#define TIMTYPE_TIM10 TIMTYPE_COUNTUP16
|
||||
#define TIMTYPE_TIM11 TIMTYPE_COUNTUP16
|
||||
#define TIMTYPE_TIM12 TIMTYPE_COUNTUP16
|
||||
#define TIMTYPE_TIM13 TIMTYPE_COUNTUP16
|
||||
#define TIMTYPE_TIM14 TIMTYPE_COUNTUP16
|
||||
|
||||
/* The maximum repetition count is 128 */
|
||||
|
||||
#define PWM_MAX_COUNT 128
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
/* Non-standard debug that may be enabled just for testing PWM */
|
||||
|
||||
|
@ -94,12 +130,19 @@ struct stm32_pwmtimer_s
|
|||
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;
|
||||
uint8_t timtype; /* See the TIMTYPE_* definitions */
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
uint8_t irq; /* Timer update IRQ */
|
||||
#else
|
||||
uint8_t unused;
|
||||
#endif
|
||||
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. */
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
FAR void * handle; /* Handle used for upper-half callback */
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -116,13 +159,38 @@ static void pwm_dumpregs(struct stm32_pwmtimer_s *priv, FAR const char *msg);
|
|||
# define pwm_dumpregs(priv,msg)
|
||||
#endif
|
||||
|
||||
/* Timer management */
|
||||
|
||||
static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
|
||||
FAR const struct pwm_info_s *info);
|
||||
|
||||
#if defined(CONFIG_PWM_PULSECOUNT) && (defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM))
|
||||
static int pwm_interrupt(struct stm32_pwmtimer_s *priv);
|
||||
#if defined(CONFIG_STM32_TIM1_PWM)
|
||||
static int pwm_tim1interrupt(int irq, void *context);
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_TIM1_PWM)
|
||||
static int pwm_tim8interrupt(int irq, void *context);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* PWM driver methods */
|
||||
|
||||
static int pwm_setup(FAR struct pwm_lowerhalf_s *dev);
|
||||
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);
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info,
|
||||
FAR void *handle);
|
||||
#else
|
||||
static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info);
|
||||
#endif
|
||||
|
||||
static int pwm_stop(FAR struct pwm_lowerhalf_s *dev);
|
||||
static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg);
|
||||
static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev,
|
||||
int cmd, unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
|
@ -144,6 +212,10 @@ static struct stm32_pwmtimer_s g_pwm1dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 1,
|
||||
.channel = CONFIG_STM32_TIM1_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM1,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM1UP,
|
||||
#endif
|
||||
.base = STM32_TIM1_BASE,
|
||||
.pincfg = PWM_TIM1_PINCFG,
|
||||
.pclk = STM32_APB2_TIM1_CLKIN,
|
||||
|
@ -156,6 +228,10 @@ static struct stm32_pwmtimer_s g_pwm2dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 2,
|
||||
.channel = CONFIG_STM32_TIM2_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM2,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM2,
|
||||
.base = STM32_TIM2_BASE,
|
||||
.pincfg = PWM_TIM2_PINCFG,
|
||||
.pclk = STM32_APB1_TIM2_CLKIN,
|
||||
|
@ -168,6 +244,10 @@ static struct stm32_pwmtimer_s g_pwm3dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 3,
|
||||
.channel = CONFIG_STM32_TIM3_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM3,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM3,
|
||||
.base = STM32_TIM3_BASE,
|
||||
.pincfg = PWM_TIM3_PINCFG,
|
||||
.pclk = STM32_APB1_TIM3_CLKIN,
|
||||
|
@ -180,6 +260,10 @@ static struct stm32_pwmtimer_s g_pwm4dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 4,
|
||||
.channel = CONFIG_STM32_TIM4_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM4,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM4,
|
||||
.base = STM32_TIM4_BASE,
|
||||
.pincfg = PWM_TIM4_PINCFG,
|
||||
.pclk = STM32_APB1_TIM4_CLKIN,
|
||||
|
@ -192,6 +276,10 @@ static struct stm32_pwmtimer_s g_pwm5dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 5,
|
||||
.channel = CONFIG_STM32_TIM5_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM5,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM5,
|
||||
.base = STM32_TIM5_BASE,
|
||||
.pincfg = PWM_TIM5_PINCFG,
|
||||
.pclk = STM32_APB1_TIM5_CLKIN,
|
||||
|
@ -204,6 +292,10 @@ static struct stm32_pwmtimer_s g_pwm8dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 8,
|
||||
.channel = CONFIG_STM32_TIM8_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM8UP,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM8,
|
||||
.base = STM32_TIM8_BASE,
|
||||
.pincfg = PWM_TIM8_PINCFG,
|
||||
.pclk = STM32_APB2_TIM8_CLKIN,
|
||||
|
@ -216,6 +308,10 @@ static struct stm32_pwmtimer_s g_pwm9dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 9,
|
||||
.channel = CONFIG_STM32_TIM9_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM9,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM9,
|
||||
#endif
|
||||
.base = STM32_TIM9_BASE,
|
||||
.pincfg = PWM_TIM9_PINCFG,
|
||||
.pclk = STM32_APB2_TIM9_CLKIN,
|
||||
|
@ -228,6 +324,10 @@ static struct stm32_pwmtimer_s g_pwm10dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 10,
|
||||
.channel = CONFIG_STM32_TIM10_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM10,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM10,
|
||||
#endif
|
||||
.base = STM32_TIM10_BASE,
|
||||
.pincfg = PWM_TIM10_PINCFG,
|
||||
.pclk = STM32_APB2_TIM10_CLKIN,
|
||||
|
@ -240,6 +340,10 @@ static struct stm32_pwmtimer_s g_pwm11dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 11,
|
||||
.channel = CONFIG_STM32_TIM11_CHANNEL,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM11,
|
||||
#endif
|
||||
.timtype = TIMTYPE_TIM11,
|
||||
.base = STM32_TIM11_BASE,
|
||||
.pincfg = PWM_TIM11_PINCFG,
|
||||
.pclk = STM32_APB2_TIM11_CLKIN,
|
||||
|
@ -252,6 +356,10 @@ static struct stm32_pwmtimer_s g_pwm12dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 12,
|
||||
.channel = CONFIG_STM32_TIM12_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM12,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM12,
|
||||
#endif
|
||||
.base = STM32_TIM12_BASE,
|
||||
.pincfg = PWM_TIM12_PINCFG,
|
||||
.pclk = STM32_APB1_TIM12_CLKIN,
|
||||
|
@ -264,6 +372,10 @@ static struct stm32_pwmtimer_s g_pwm13dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 13,
|
||||
.channel = CONFIG_STM32_TIM13_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM13,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM13,
|
||||
#endif
|
||||
.base = STM32_TIM13_BASE,
|
||||
.pincfg = PWM_TIM13_PINCFG,
|
||||
.pclk = STM32_APB1_TIM13_CLKIN,
|
||||
|
@ -276,6 +388,10 @@ static struct stm32_pwmtimer_s g_pwm14dev =
|
|||
.ops = &g_pwmops,
|
||||
.timid = 14,
|
||||
.channel = CONFIG_STM32_TIM14_CHANNEL,
|
||||
.timtype = TIMTYPE_TIM14,
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
.irq = STM32_IRQ_TIM14,
|
||||
#endif
|
||||
.base = STM32_TIM14_BASE,
|
||||
.pincfg = PWM_TIM14_PINCFG,
|
||||
.pclk = STM32_APB1_TIM14_CLKIN,
|
||||
|
@ -365,7 +481,7 @@ static void pwm_dumpregs(struct stm32_pwmtimer_s *priv, FAR const char *msg)
|
|||
pwm_getreg(priv, STM32_GTIM_CCR3_OFFSET),
|
||||
pwm_getreg(priv, STM32_GTIM_CCR4_OFFSET));
|
||||
#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM)
|
||||
if (priv->timid == 1 || priv->timid == 8)
|
||||
if (priv->timtype == TIMTYPE_ADVANCED)
|
||||
{
|
||||
pwmvdbg(" RCR: %04x BDTR: %04x DCR: %04x DMAR: %04x\n",
|
||||
pwm_getreg(priv, STM32_ATIM_RCR_OFFSET),
|
||||
|
@ -384,89 +500,13 @@ static void pwm_dumpregs(struct stm32_pwmtimer_s *priv, FAR const char *msg)
|
|||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_setup
|
||||
*
|
||||
* Description:
|
||||
* This method is called when the driver is opened. The lower half driver
|
||||
* should configure and initialize the device so that it is ready for use.
|
||||
* It should not, however, output pulses until the start method is called.
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
*
|
||||
* 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)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
|
||||
pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->pincfg);
|
||||
pwm_dumpregs(priv, "Initially");
|
||||
|
||||
/* Configure the PWM output pin, but do not start the timer yet */
|
||||
|
||||
stm32_configgpio(priv->pincfg);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_shutdown
|
||||
*
|
||||
* Description:
|
||||
* This method is called when the driver is closed. The lower half driver
|
||||
* stop pulsed output, free any resources, disable the timer hardware, and
|
||||
* put the system into the lowest possible power usage state
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
uint32_t pincfg;
|
||||
|
||||
pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->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;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_start
|
||||
* Name: pwm_timer
|
||||
*
|
||||
* Description:
|
||||
* (Re-)initialize the timer resources and start the pulsed output
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
* priv - A reference to the lower half PWM driver state structure
|
||||
* info - A reference to the characteristics of the pulsed output
|
||||
*
|
||||
* Returned Value:
|
||||
|
@ -474,10 +514,9 @@ 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)
|
||||
static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
|
||||
FAR const struct pwm_info_s *info)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
|
||||
/* Calculated values */
|
||||
|
||||
uint32_t prescaler;
|
||||
|
@ -505,6 +544,13 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
priv->timid, priv->channel, info->frequency, info->duty);
|
||||
DEBUGASSERT(info->frequency > 0 && info->duty > 0 && info->duty < uitoub16(100));
|
||||
|
||||
/* Disable all interrupts and DMA requests, clear all pending status */
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
pwm_putreg(priv, STM32_GTIM_DIER_OFFSET, 0);
|
||||
pwm_putreg(priv, STM32_GTIM_SR_OFFSET, 0);
|
||||
#endif
|
||||
|
||||
/* Calculate optimal values for the timer prescaler and for the timer reload
|
||||
* register. If' frequency' is the desired frequency, then
|
||||
*
|
||||
|
@ -585,24 +631,25 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
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):
|
||||
* purpose timers (all 2-5, but not 9-14), i.e., all but TIMTYPE_COUNTUP16
|
||||
* and TIMTYPE_BASIC
|
||||
*/
|
||||
|
||||
#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)
|
||||
if (priv->timtype != TIMTYPE_BASIC && priv->timtype != TIMTYPE_COUNTUP16)
|
||||
{
|
||||
/* Select the Counter Mode == count up:
|
||||
*
|
||||
* ATIM_CR1_EDGE: The counter counts up or down depending on the
|
||||
* GTIM_CR1_EDGE: The counter counts up or down depending on the
|
||||
* direction bit(DIR).
|
||||
* ATIM_CR1_DIR: 0: count up, 1: count down
|
||||
* GTIM_CR1_DIR: 0: count up, 1: count down
|
||||
*/
|
||||
|
||||
cr1 &= ~(ATIM_CR1_DIR | ATIM_CR1_CMS_MASK);
|
||||
cr1 |= ATIM_CR1_EDGE;
|
||||
cr1 &= ~(GTIM_CR1_DIR | GTIM_CR1_CMS_MASK);
|
||||
cr1 |= GTIM_CR1_EDGE;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -618,12 +665,29 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
pwm_putreg(priv, STM32_GTIM_ARR_OFFSET, (uint16_t)reload);
|
||||
pwm_putreg(priv, STM32_GTIM_PSC_OFFSET, (uint16_t)(prescaler - 1));
|
||||
|
||||
/* Clear the advanced timers repitition counter in all but the advanced timers */
|
||||
/* Set the advanced timer's repitition counter */
|
||||
|
||||
#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM)
|
||||
if (priv->timid == 1 || priv->timid == 8)
|
||||
if (priv->timtype == TIMTYPE_ADVANCED)
|
||||
{
|
||||
pwm_putreg(priv, STM32_ATIM_RCR_OFFSET, 0);
|
||||
/* If a non-zero repetition count has been selected, then set the
|
||||
* repitition counter to the count-1 (pwm_start() has already
|
||||
* assured us that the count value is within range).
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
if (info->count > 0)
|
||||
{
|
||||
pwm_putreg(priv, STM32_ATIM_RCR_OFFSET, info->count - 1);
|
||||
}
|
||||
|
||||
/* Otherwise, just clear the repitition counter */
|
||||
|
||||
else
|
||||
#endif
|
||||
{
|
||||
pwm_putreg(priv, STM32_ATIM_RCR_OFFSET, 0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -747,7 +811,7 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
/* Some special setup for advanced timers */
|
||||
|
||||
#if defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM)
|
||||
if (priv->timid == 1 || priv->timid == 8)
|
||||
if (priv->timtype == TIMTYPE_ADVANCED)
|
||||
{
|
||||
/* Reset output N polarity level, output N state, output compre state,
|
||||
* output compare N idle state.
|
||||
|
@ -789,15 +853,238 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
cr1 |= GTIM_CR1_ARPE;
|
||||
pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
|
||||
|
||||
/* And, finally, enable the timer */
|
||||
/* Setup update interrupt. If info->count is > 0, then we can be
|
||||
* assured that pwm_start() has already verified: (1) that this is an
|
||||
* advanced timer, and that (2) the repetitioncount is within range.
|
||||
*/
|
||||
|
||||
cr1 |= GTIM_CR1_CEN;
|
||||
pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
if (info->count > 0)
|
||||
{
|
||||
/* Enable the update interrupt. */
|
||||
|
||||
pwm_putreg(priv, STM32_GTIM_DIER_OFFSET, ATIM_DIER_UIE);
|
||||
|
||||
/* Enable the timer */
|
||||
|
||||
cr1 |= GTIM_CR1_CEN;
|
||||
pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
|
||||
|
||||
/* And enable timer interrupts at the NVIC */
|
||||
|
||||
up_enable_irq(priv->irq);
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
/* Just enable the timer, leaving all interrupts disabled */
|
||||
|
||||
cr1 |= GTIM_CR1_CEN;
|
||||
pwm_putreg(priv, STM32_GTIM_CR1_OFFSET, cr1);
|
||||
}
|
||||
|
||||
pwm_dumpregs(priv, "After starting");
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_interrupt
|
||||
*
|
||||
* Description:
|
||||
* Handle timer interrupts.
|
||||
*
|
||||
* Input parameters:
|
||||
* priv - A reference to the lower half PWM driver state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_PWM_PULSECOUNT) && (defined(CONFIG_STM32_TIM1_PWM) || defined(CONFIG_STM32_TIM8_PWM))
|
||||
static int pwm_interrupt(struct stm32_pwmtimer_s *priv)
|
||||
{
|
||||
/* Verify that this is an update interrupt. Nothing else is expected. */
|
||||
|
||||
pwmllvdbg("Update interrupt: %04x\n", pwm_getreg(STM32_GTIM_SR_OFFSET));
|
||||
DEBUGASSERT((pwm_getreg(STM32_GTIM_SR_OFFSET) & ATIM_SR_UIF) != 0);
|
||||
|
||||
/* Disable further interrupts and stop the timer */
|
||||
|
||||
(void)pwm_stop((FAR struct pwm_lowerhalf_s *)priv)
|
||||
|
||||
/* Then perform the callback into the upper half driver */
|
||||
|
||||
pwm_expired(priv->handle);
|
||||
priv->handle = NULL;
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_tim1/8interrupt
|
||||
*
|
||||
* Description:
|
||||
* Handle timer 1 and 8 interrupts.
|
||||
*
|
||||
* Input parameters:
|
||||
* Standard NuttX interrupt inputs
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_PWM_PULSECOUNT) && defined(CONFIG_STM32_TIM1_PWM)
|
||||
static int pwm_tim1interrupt(int irq, void *context)
|
||||
{
|
||||
return pwm_interrupt(&g_pwm1dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_PWM_PULSECOUNT) && defined(CONFIG_STM32_TIM8_PWM)
|
||||
static int pwm_tim8interrupt(int irq, void *context)
|
||||
{
|
||||
return pwm_interrupt(&g_pwm8dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_setup
|
||||
*
|
||||
* Description:
|
||||
* This method is called when the driver is opened. The lower half driver
|
||||
* should configure and initialize the device so that it is ready for use.
|
||||
* It should not, however, output pulses until the start method is called.
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
*
|
||||
* 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)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
|
||||
pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->pincfg);
|
||||
pwm_dumpregs(priv, "Initially");
|
||||
|
||||
/* Configure the PWM output pin, but do not start the timer yet */
|
||||
|
||||
stm32_configgpio(priv->pincfg);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_shutdown
|
||||
*
|
||||
* Description:
|
||||
* This method is called when the driver is closed. The lower half driver
|
||||
* stop pulsed output, free any resources, disable the timer hardware, and
|
||||
* put the system into the lowest possible power usage state
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
uint32_t pincfg;
|
||||
|
||||
pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->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;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_start
|
||||
*
|
||||
* Description:
|
||||
* (Re-)initialize the timer resources and start the pulsed output
|
||||
*
|
||||
* Input parameters:
|
||||
* dev - A reference to the lower half PWM driver state structure
|
||||
* info - A reference to the characteristics of the pulsed output
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info,
|
||||
FAR void *handle)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
|
||||
/* Check if a pulsecount has been selected */
|
||||
|
||||
if (info->count > 0)
|
||||
{
|
||||
/* Only the advanced timers (TIM1,8 can support the pulse counting) */
|
||||
|
||||
if (priv->timtype != TIMTYPE_ADVANCED)
|
||||
{
|
||||
pwmdbg("ERROR: TIM%d cannot support pulse count: %d\n",
|
||||
priv->timid, info->count);
|
||||
return -EPERM;
|
||||
}
|
||||
|
||||
/* The maximum repetition count supported by the advanced timers
|
||||
* is PWM_MAX_COUNT.
|
||||
*/
|
||||
|
||||
if (info->count > PWM_MAX_COUNT)
|
||||
{
|
||||
pwmdbg("ERROR: TIM%d count=%d exceeds maximum repeition count: %d\n",
|
||||
priv->timid, info->count, PWM_MAX_COUNT);
|
||||
return -EDOM;
|
||||
}
|
||||
}
|
||||
|
||||
/* Start the time */
|
||||
|
||||
return pwm_timer(priv, info);
|
||||
}
|
||||
#else
|
||||
static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info)
|
||||
{
|
||||
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
|
||||
return pwm_timer(priv, info);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_stop
|
||||
*
|
||||
|
@ -810,6 +1097,11 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_
|
|||
* Returned Value:
|
||||
* Zero on success; a negated errno value on failure
|
||||
*
|
||||
* Assumptions:
|
||||
* This function is called to stop the pulsed output at anytime. This
|
||||
* method is also called from the timer interrupt handler when a repetition
|
||||
* count expires... automatically stopping the timer.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
|
||||
|
@ -822,6 +1114,19 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
|
|||
|
||||
pwmvdbg("TIM%d\n", priv->timid);
|
||||
|
||||
/* Disable interrupts momentary to stop any ongoing timer processing and
|
||||
* to prevent any concurrent access to the reset register.
|
||||
*/
|
||||
|
||||
flags = irqsave();
|
||||
|
||||
/* Disable further interrupts and stop the timer */
|
||||
|
||||
pwm_putreg(priv, STM32_GTIM_DIER_OFFSET, 0);
|
||||
pwm_putreg(priv, STM32_GTIM_SR_OFFSET, 0);
|
||||
|
||||
/* Determine which timer to reset */
|
||||
|
||||
switch (priv->timid)
|
||||
{
|
||||
#ifdef CONFIG_STM32_TIM1_PWM
|
||||
|
@ -898,12 +1203,6 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
|
|||
#endif
|
||||
}
|
||||
|
||||
/* Disable interrupts momentary to stop any ongoing timer processing and
|
||||
* to prevent any concurrent access to the reset register.
|
||||
*/
|
||||
|
||||
flags = irqsave();
|
||||
|
||||
/* Reset the timer - stopping the output and putting the timer back
|
||||
* into a state where pwm_start() can be called.
|
||||
*/
|
||||
|
@ -981,63 +1280,89 @@ FAR struct pwm_lowerhalf_s *stm32_pwminitialize(int timer)
|
|||
#ifdef CONFIG_STM32_TIM1_PWM
|
||||
case 1:
|
||||
lower = &g_pwm1dev;
|
||||
|
||||
/* Attach but disable the TIM1 update interrupt */
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
irq_attach(lower->irq, pwm_tim1interrupt);
|
||||
up_disable_irq(lower->irq);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM2_PWM
|
||||
case 2:
|
||||
lower = &g_pwm2dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM3_PWM
|
||||
case 3:
|
||||
lower = &g_pwm3dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM4_PWM
|
||||
case 4:
|
||||
lower = &g_pwm4dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM5_PWM
|
||||
case 5:
|
||||
lower = &g_pwm5dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM8_PWM
|
||||
case 8:
|
||||
lower = &g_pwm8dev;
|
||||
|
||||
/* Attach but disable the TIM8 update interrupt */
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
irq_attach(lower->irq, pwm_tim8interrupt);
|
||||
up_disable_irq(lower->irq);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM9_PWM
|
||||
case 9:
|
||||
lower = &g_pwm9dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM10_PWM
|
||||
case 10:
|
||||
lower = &g_pwm10dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM11_PWM
|
||||
case 11:
|
||||
lower = &g_pwm11dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM12_PWM
|
||||
case 12:
|
||||
lower = &g_pwm12dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM13_PWM
|
||||
case 13:
|
||||
lower = &g_pwm13dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_TIM14_PWM
|
||||
case 14:
|
||||
lower = &g_pwm14dev;
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
pwmdbg("No such timer configured\n");
|
||||
return NULL;
|
||||
|
|
|
@ -595,7 +595,9 @@ Where <subdir> is one of the following:
|
|||
be manually enabled by selecting:
|
||||
|
||||
CONFIG_PWM=y : Enable the generic PWM infrastructure
|
||||
CONFIG_PWM_PULSECOUNT=n : Disable to support TIM1/8 pulse counts
|
||||
CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output
|
||||
CONFIG_STM32_TIM4_CHANNEL=2
|
||||
|
||||
See also apps/examples/README.txt
|
||||
|
||||
|
|
|
@ -353,6 +353,7 @@ CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100
|
|||
# purpose.
|
||||
#
|
||||
CONFIG_PWM=n
|
||||
CONFIG_PWM_PULSECOUNT=n
|
||||
CONFIG_STM32_TIM4=y
|
||||
CONFIG_STM32_TIM4_PWM=y
|
||||
CONFIG_STM32_TIM4_CHANNEL=2
|
||||
|
|
|
@ -89,10 +89,16 @@
|
|||
|
||||
struct pwm_upperhalf_s
|
||||
{
|
||||
uint8_t crefs; /* The number of times the device has been opened */
|
||||
bool started; /* True: pulsed output is being generated */
|
||||
sem_t sem; /* Supports mutual exclusion */
|
||||
struct pwm_info_s info; /* Pulsed output characteristics */
|
||||
uint8_t crefs; /* The number of times the device has been opened */
|
||||
volatile bool started; /* True: pulsed output is being generated */
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
volatile bool waiting; /* True: Caller is waiting for the pulse count to expire */
|
||||
#endif
|
||||
sem_t exclsem; /* Supports mutual exclusion */
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
sem_t waitsem; /* Used to wait for the pulse count to expire */
|
||||
#endif
|
||||
struct pwm_info_s info; /* Pulsed output characteristics */
|
||||
FAR struct pwm_lowerhalf_s *dev; /* lower-half state */
|
||||
};
|
||||
|
||||
|
@ -104,6 +110,7 @@ static int pwm_open(FAR struct file *filep);
|
|||
static int pwm_close(FAR struct file *filep);
|
||||
static ssize_t pwm_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
|
||||
static ssize_t pwm_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
|
||||
static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags);
|
||||
static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -146,7 +153,7 @@ static int pwm_open(FAR struct file *filep)
|
|||
|
||||
/* Get exclusive access to the device structures */
|
||||
|
||||
ret = sem_wait(&upper->sem);
|
||||
ret = sem_wait(&upper->exclsem);
|
||||
if (ret < 0)
|
||||
{
|
||||
ret = -errno;
|
||||
|
@ -191,7 +198,7 @@ static int pwm_open(FAR struct file *filep)
|
|||
ret = OK;
|
||||
|
||||
errout_with_sem:
|
||||
sem_post(&upper->sem);
|
||||
sem_post(&upper->exclsem);
|
||||
|
||||
errout:
|
||||
return ret;
|
||||
|
@ -215,7 +222,7 @@ static int pwm_close(FAR struct file *filep)
|
|||
|
||||
/* Get exclusive access to the device structures */
|
||||
|
||||
ret = sem_wait(&upper->sem);
|
||||
ret = sem_wait(&upper->exclsem);
|
||||
if (ret < 0)
|
||||
{
|
||||
ret = -errno;
|
||||
|
@ -248,7 +255,7 @@ static int pwm_close(FAR struct file *filep)
|
|||
ret = OK;
|
||||
|
||||
//errout_with_sem:
|
||||
sem_post(&upper->sem);
|
||||
sem_post(&upper->exclsem);
|
||||
|
||||
errout:
|
||||
return ret;
|
||||
|
@ -282,6 +289,112 @@ static ssize_t pwm_write(FAR struct file *filep, FAR const char *buffer, size_t
|
|||
return 0;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: pwm_start
|
||||
*
|
||||
* Description:
|
||||
* Handle the PWMIOC_START ioctl command
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags)
|
||||
{
|
||||
FAR struct pwm_lowerhalf_s *lower = upper->dev;
|
||||
irqstate_t flags;
|
||||
int ret = OK;
|
||||
|
||||
DEBUGASSERT(upper != NULL && lower->ops->start != NULL);
|
||||
|
||||
/* Verify that the PWM is not already running */
|
||||
|
||||
if (!upper->started)
|
||||
{
|
||||
/* Disable interrupts to avoid race conditions */
|
||||
|
||||
flags = irqsave();
|
||||
|
||||
/* Indicate that if will be waiting for the pulse count to complete.
|
||||
* Note that we will only wait if a non-zero pulse count is specified
|
||||
* and if the PWM driver was opened in normal, blocking mode. Also
|
||||
* assume for now that the pulse train will be successfully started.
|
||||
*
|
||||
* We do these things before starting the PWM to avoid race conditions.
|
||||
*/
|
||||
|
||||
upper->waiting = (upper->info.count > 0) && ((oflags & O_NONBLOCK) != 0);
|
||||
upper->started = true;
|
||||
|
||||
/* Invoke the bottom half method to start the pulse train */
|
||||
|
||||
ret = lower->ops->start(lower, &upper->info, upper);
|
||||
|
||||
/* A return value of zero means that the pulse train was started
|
||||
* successfully.
|
||||
*/
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Should we wait for the pulse output to complete? Loop in
|
||||
* in case the wakeup form sem_wait() is a false alarm.
|
||||
*/
|
||||
|
||||
while (upper->waiting)
|
||||
{
|
||||
/* Wait until we are awakened by pwm_expired(). When
|
||||
* pwm_expired is called, it will post the waitsem and
|
||||
* clear the waiting flag.
|
||||
*/
|
||||
|
||||
int tmp = sem_wait(&upper->waitsem);
|
||||
DEBUGASSERT(tmp == OK || errno == EINTR);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Looks like we won't be waiting after all */
|
||||
|
||||
upper->started = false;
|
||||
upper->waiting = false;
|
||||
}
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#else
|
||||
static int pwm_start(FAR struct pwm_upperhalf_s *upper, unsigned int oflags)
|
||||
{
|
||||
FAR struct pwm_lowerhalf_s *lower = upper->dev;
|
||||
int ret = OK;
|
||||
|
||||
DEBUGASSERT(upper != NULL && lower->ops->start != NULL);
|
||||
|
||||
/* Verify that the PWM is not already running */
|
||||
|
||||
if (!upper->started)
|
||||
{
|
||||
/* Invoke the bottom half method to start the pulse train */
|
||||
|
||||
ret = lower->ops->start(lower, &upper->info);
|
||||
|
||||
/* A return value of zero means that the pulse train was started
|
||||
* successfully.
|
||||
*/
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Indicate that the pulse train has started */
|
||||
|
||||
upper->started = true;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: pwm_ioctl
|
||||
*
|
||||
|
@ -295,12 +408,20 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct pwm_upperhalf_s *upper = inode->i_private;
|
||||
FAR struct pwm_lowerhalf_s *lower = upper->dev;
|
||||
int ret = OK;
|
||||
|
||||
/* Handle built-in ioctl commands */
|
||||
int ret;
|
||||
|
||||
pwmvdbg("cmd: %d arg: %ld\n", cmd, arg);
|
||||
|
||||
/* Get exclusive access to the device structures */
|
||||
|
||||
ret = sem_wait(&upper->exclsem);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Handle built-in ioctl commands */
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
/* PWMIOC_SETCHARACTERISTICS - Set the characteristics of the next pulsed
|
||||
|
@ -318,13 +439,27 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
FAR const struct pwm_info_s *info = (FAR const struct pwm_info_s*)((uintptr_t)arg);
|
||||
DEBUGASSERT(info != NULL && lower->ops->start != NULL);
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
pwmvdbg("PWMIOC_SETCHARACTERISTICS frequency: %d duty: %08x count: %d started: %d\n",
|
||||
info->frequency, info->duty, info->count, upper->started);
|
||||
#else
|
||||
pwmvdbg("PWMIOC_SETCHARACTERISTICS frequency: %d duty: %08x started: %d\n",
|
||||
info->frequency, info->duty, upper->started);
|
||||
#endif
|
||||
|
||||
/* Save the pulse train characteristics */
|
||||
|
||||
memcpy(&upper->info, info, sizeof(struct pwm_info_s));
|
||||
|
||||
/* If PWM is already running, then re-start it with the new characteristics */
|
||||
|
||||
if (upper->started)
|
||||
{
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
ret = lower->ops->start(lower, &upper->info, upper);
|
||||
#else
|
||||
ret = lower->ops->start(lower, &upper->info);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -342,8 +477,14 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
DEBUGASSERT(info != NULL);
|
||||
|
||||
memcpy(info, &upper->info, sizeof(struct pwm_info_s));
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
pwmvdbg("PWMIOC_GETCHARACTERISTICS frequency: %d duty: %08x count: %d\n",
|
||||
info->frequency, info->duty, info->count);
|
||||
#else
|
||||
pwmvdbg("PWMIOC_GETCHARACTERISTICS frequency: %d duty: %08x\n",
|
||||
info->frequency, info->duty);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -355,16 +496,19 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
|
||||
case PWMIOC_START:
|
||||
{
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
pwmvdbg("PWMIOC_START frequency: %d duty: %08x count: %d started: %d\n",
|
||||
upper->info.frequency, upper->info.duty, upper->info.count,
|
||||
upper->started);
|
||||
#else
|
||||
pwmvdbg("PWMIOC_START frequency: %d duty: %08x started: %d\n",
|
||||
upper->info.frequency, upper->info.duty, upper->started);
|
||||
|
||||
#endif
|
||||
DEBUGASSERT(lower->ops->start != NULL);
|
||||
|
||||
if (!upper->started)
|
||||
{
|
||||
ret = lower->ops->start(lower, &upper->info);
|
||||
upper->started = true;
|
||||
}
|
||||
/* Start the pulse train */
|
||||
|
||||
ret = pwm_start(upper, filep->f_oflags);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -382,6 +526,12 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
{
|
||||
ret = lower->ops->stop(lower);
|
||||
upper->started = false;
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
if (upper->waiting)
|
||||
{
|
||||
upper->waiting = FALSE;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -396,6 +546,8 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
}
|
||||
break;
|
||||
}
|
||||
|
||||
sem_post(&upper->exclsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -443,7 +595,10 @@ int pwm_register(FAR const char *path, FAR struct pwm_lowerhalf_s *dev)
|
|||
|
||||
/* Initialize the PWM device structure (it was already zeroed by zalloc()) */
|
||||
|
||||
sem_init(&upper->sem, 0, 1);
|
||||
sem_init(&upper->exclsem, 0, 1);
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
sem_init(&upper->waitsem, 0, 0);
|
||||
#endif
|
||||
upper->dev = dev;
|
||||
|
||||
/* Register the PWM device */
|
||||
|
@ -452,4 +607,67 @@ int pwm_register(FAR const char *path, FAR struct pwm_lowerhalf_s *dev)
|
|||
return register_driver(path, &g_pwmops, 0666, upper);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_expired
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_PWM_PULSECOUNT is defined and the pulse count was configured
|
||||
* to a non-zero value, then the "upper half" driver will wait for the
|
||||
* pulse count to expire. The sequence of expected events is as follows:
|
||||
*
|
||||
* 1. The upper half driver calls the start method, providing the lower
|
||||
* half driver with the pulse train characteristics. If a fixed
|
||||
* number of pulses is required, the 'count' value will be nonzero.
|
||||
* 2. The lower half driver's start() methoc must verify that it can
|
||||
* support the request pulse train (frequency, duty, AND pulse count).
|
||||
* It it cannot, it should return an error. If the pulse count is
|
||||
* non-zero, it should set up the hardware for that number of pulses
|
||||
* and return success. NOTE: That is CONFIG_PWM_PULSECOUNT is
|
||||
* defined, the start() method receives an additional parameter
|
||||
* that must be used in this callback.
|
||||
* 3. When the start() method returns success, the upper half driver
|
||||
* will "sleep" until the pwm_expired method is called.
|
||||
* 4. When the lower half detects that the pulse count has expired
|
||||
* (probably through an interrupt), it must call the pwm_expired
|
||||
* interface using the handle that was previously passed to the
|
||||
* start() method
|
||||
*
|
||||
* Input parameters:
|
||||
* handle - This is the handle that was provided to the lower-half
|
||||
* start() method.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* This function may be called from an interrupt handler.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
void pwm_expired(FAR void *handle)
|
||||
{
|
||||
FAR struct pwm_upperhalf_s *upper = (FAR struct pwm_upperhalf_s *)handle;
|
||||
|
||||
/* Make sure that the PWM is started */
|
||||
|
||||
if (upper->started)
|
||||
{
|
||||
/* Is there a thread waiting for the pulse train to complete? */
|
||||
|
||||
if (upper->waiting)
|
||||
{
|
||||
/* Yes.. clear the waiting flag and awakened the waiting thread */
|
||||
|
||||
upper->waiting = false;
|
||||
sem_post(&upper->waitsem);
|
||||
}
|
||||
|
||||
/* The PWM is now stopped */
|
||||
|
||||
upper->started = false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_PWM */
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/pwm.h
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -66,6 +66,18 @@
|
|||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
/* Configuration ************************************************************/
|
||||
/* CONFIG_PWM - Enables because PWM driver support
|
||||
* CONFIG_PWM_PULSECOUNT - Some hardware will support generation of a fixed
|
||||
* number of pulses. This might be used, for example to support a stepper
|
||||
* motor. If the hardware will support a fixed pulse count, then this
|
||||
* configuration should be set to enable the capability.
|
||||
* CONFIG_DEBUG_PWM - If enabled (with CONFIG_DEBUG and, optionally,
|
||||
* CONFIG_DEBUG_VERBOSE), this will generate output that can be use dto
|
||||
* debug the PWM driver.
|
||||
*/
|
||||
|
||||
/* IOCTL Commands ***********************************************************/
|
||||
/* The PWM module uses a standard character driver framework. However, since
|
||||
* the PWM driver is a devices control interface and not a data transfer
|
||||
* interface, the majority of the functionality is implemented in driver
|
||||
|
@ -75,7 +87,8 @@
|
|||
* output. This command will neither start nor stop the pulsed output.
|
||||
* It will either setup the configuration that will be used when the
|
||||
* output is started; or it will change the characteristics of the pulsed
|
||||
* output on the fly if the timer is already started.
|
||||
* output on the fly if the timer is already started. This command will
|
||||
* set the PWM characteristics and return immediately.
|
||||
*
|
||||
* ioctl argument: A read-only reference to struct pwm_info_s that provides
|
||||
* the characteristics of the pulsed output.
|
||||
|
@ -87,11 +100,16 @@
|
|||
* characteristics of the pulsed output.
|
||||
*
|
||||
* PWMIOC_START - Start the pulsed output. The PWMIOC_SETCHARACTERISTICS
|
||||
* command must have previously been sent.
|
||||
* command must have previously been sent. If CONFIG_PWM_PULSECOUNT is
|
||||
* defined and the pulse count was configured to a non-zero value, then
|
||||
* this ioctl call will, by default, block until the programmed pulse count
|
||||
* completes. That default blocking behavior can be overridden by using
|
||||
* the O_NONBLOCK flag when the PWM driver is opened.
|
||||
*
|
||||
* ioctl argument: None
|
||||
*
|
||||
* PWMIOC_STOP - Stop the pulsed output.
|
||||
* PWMIOC_STOP - Stop the pulsed output. This command will stop the PWM
|
||||
* and return immediately.
|
||||
*
|
||||
* ioctl argument: None
|
||||
*/
|
||||
|
@ -109,7 +127,13 @@
|
|||
struct pwm_info_s
|
||||
{
|
||||
uint32_t frequency; /* Frequency of the pulse train */
|
||||
ub16_t duty; /* Duty of the pulse train, "1" to "0" duration */
|
||||
ub16_t duty; /* Duty of the pulse train, "1"-to-"0" duration.
|
||||
* Maximum: 65535/65536 (0x0000ffff)
|
||||
* Minimum: 1/65536 (0x00000001) */
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
uint32_t count; /* The number of pulse to generate. 0 means to
|
||||
* generate an indefinite number of pulses */
|
||||
#endif
|
||||
};
|
||||
|
||||
/* This structure is a set a callback functions used to call from the upper-
|
||||
|
@ -134,9 +158,19 @@ struct pwm_ops_s
|
|||
|
||||
CODE int (*shutdown)(FAR struct pwm_lowerhalf_s *dev);
|
||||
|
||||
/* (Re-)initialize the timer resources and start the pulsed output */
|
||||
/* (Re-)initialize the timer resources and start the pulsed output. The
|
||||
* start method should return an error if it cannot start the timer with
|
||||
* the given parameter (frequency, duty, or optionally pulse count)
|
||||
*/
|
||||
|
||||
CODE int (*start)(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_s *info);
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
CODE int (*start)(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info,
|
||||
FAR void *handle);
|
||||
#else
|
||||
CODE int (*start)(FAR struct pwm_lowerhalf_s *dev,
|
||||
FAR const struct pwm_info_s *info);
|
||||
#endif
|
||||
|
||||
/* Stop the pulsed output and reset the timer resources*/
|
||||
|
||||
|
@ -144,7 +178,8 @@ struct pwm_ops_s
|
|||
|
||||
/* Lower-half logic may support platform-specific ioctl commands */
|
||||
|
||||
CODE int (*ioctl)(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg);
|
||||
CODE int (*ioctl)(FAR struct pwm_lowerhalf_s *dev,
|
||||
int cmd, unsigned long arg);
|
||||
};
|
||||
|
||||
/* This structure is the generic form of state structure used by lower half
|
||||
|
@ -217,6 +252,47 @@ extern "C" {
|
|||
|
||||
int pwm_register(FAR const char *path, FAR struct pwm_lowerhalf_s *dev);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pwm_expired
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_PWM_PULSECOUNT is defined and the pulse count was configured
|
||||
* to a non-zero value, then the "upper half" driver will wait for the
|
||||
* pulse count to expire. The sequence of expected events is as follows:
|
||||
*
|
||||
* 1. The upper half driver calls the start method, providing the lower
|
||||
* half driver with the pulse train characteristics. If a fixed
|
||||
* number of pulses is required, the 'count' value will be nonzero.
|
||||
* 2. The lower half driver's start() methoc must verify that it can
|
||||
* support the request pulse train (frequency, duty, AND pulse count).
|
||||
* It it cannot, it should return an error. If the pulse count is
|
||||
* non-zero, it should set up the hardware for that number of pulses
|
||||
* and return success. NOTE: That is CONFIG_PWM_PULSECOUNT is
|
||||
* defined, the start() method receives an additional parameter
|
||||
* that must be used in this callback.
|
||||
* 3. When the start() method returns success, the upper half driver
|
||||
* will "sleep" until the pwm_expired method is called.
|
||||
* 4. When the lower half detects that the pulse count has expired
|
||||
* (probably through an interrupt), it must call the pwm_expired
|
||||
* interface using the handle that was previously passed to the
|
||||
* start() method
|
||||
*
|
||||
* Input parameters:
|
||||
* handle - This is the handle that was provided to the lower-half
|
||||
* start() method.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* This function may be called from an interrupt handler.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PWM_PULSECOUNT
|
||||
EXTERN void pwm_expired(FAR void *handle);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Platform-Independent "Lower-Half" PWM Driver Interfaces
|
||||
****************************************************************************/
|
||||
|
|
Loading…
Reference in New Issue