From 2dad881e22746b8c56e97757e9fcb3928d196bd4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 23 Jun 2014 12:13:52 -0600 Subject: Add support for the LPCXpresso's RTC, ADC, DAC, Timer, PWM, and MCPWM. All form Max --- nuttx/arch/arm/src/lpc17xx/Kconfig | 29 +- nuttx/arch/arm/src/lpc17xx/Make.defs | 18 +- nuttx/arch/arm/src/lpc17xx/lpc176x_rtc.c | 452 +++++++++++++++++ nuttx/arch/arm/src/lpc17xx/lpc17_dac.c | 8 +- nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.c | 683 ++++++++++++++++++++++++++ nuttx/arch/arm/src/lpc17xx/lpc17_pwm.c | 655 ++++++++++++++++++++++++ nuttx/arch/arm/src/lpc17xx/lpc17_timer.c | 667 +++++++++++++++++++++++++ nuttx/configs/lpcxpresso-lpc1768/src/Makefile | 4 +- nuttx/configs/lpcxpresso-lpc1768/src/up_adc.c | 123 +++++ nuttx/configs/lpcxpresso-lpc1768/src/up_dac.c | 100 ++++ nuttx/configs/lpcxpresso-lpc1768/src/up_pwm.c | 152 ++++++ 11 files changed, 2885 insertions(+), 6 deletions(-) create mode 100644 nuttx/arch/arm/src/lpc17xx/lpc176x_rtc.c create mode 100644 nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.c create mode 100644 nuttx/arch/arm/src/lpc17xx/lpc17_pwm.c create mode 100644 nuttx/arch/arm/src/lpc17xx/lpc17_timer.c create mode 100644 nuttx/configs/lpcxpresso-lpc1768/src/up_adc.c create mode 100644 nuttx/configs/lpcxpresso-lpc1768/src/up_dac.c create mode 100644 nuttx/configs/lpcxpresso-lpc1768/src/up_pwm.c diff --git a/nuttx/arch/arm/src/lpc17xx/Kconfig b/nuttx/arch/arm/src/lpc17xx/Kconfig index b876835ca..e17100b4c 100644 --- a/nuttx/arch/arm/src/lpc17xx/Kconfig +++ b/nuttx/arch/arm/src/lpc17xx/Kconfig @@ -244,6 +244,15 @@ config LPC17_TMR0 bool "Timer 0" default n +config LPC17_MAT0_PIN + int "TIM1 MAT0 Output Pin" + default 1 + range 1 4 + depends on LPC17_TMR0 + ---help--- + If TIM1 is enabled for PWM usage, you also need specifies the timer output + channel {1,..,4} + config LPC17_TMR1 bool "Timer 1" default n @@ -267,13 +276,31 @@ config LPC17_PWM0 config LPC17_PWM1 bool "PWM1" default n - depends on ARCH_FAMILY_LPC177X || ARCH_FAMILY_LPC178X + depends on ARCH_FAMILY_LPC177X || ARCH_FAMILY_LPC178X || ARCH_FAMILY_LPC176X + +config LPC17_PWM1_PIN + int "TIM1 PWM Output Pin" + default 1 + range 1 4 + depends on LPC17_PWM1 + ---help--- + If TIM1 is enabled for PWM usage, you also need specifies the timer output + channel {1,..,4} config LPC17_MCPWM bool "MCPWM" default n depends on ARCH_FAMILY_LPC175X || ARCH_FAMILY_LPC176X +config LPC17_MCPWM1_PIN + int "TIM1 MCPWM Output Pin" + default 1 + range 1 4 + depends on LPC17_MCPWM + ---help--- + If TIM1 is enabled for PWM usage, you also need specifies the timer output + channel {1,..,4} + config LPC17_QEI bool "QEI" default n diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs index a7fa299df..5230c9e92 100644 --- a/nuttx/arch/arm/src/lpc17xx/Make.defs +++ b/nuttx/arch/arm/src/lpc17xx/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/arm/src/lpc17xx/Make.defs # -# Copyright (C) 2010-2011, 2013 Gregory Nutt. All rights reserved. +# Copyright (C) 2010-2011, 2013-2014 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -162,3 +162,19 @@ endif ifeq ($(CONFIG_LPC17_DAC),y) CHIP_CSRCS += lpc17_dac.c endif + +ifeq ($(CONFIG_LPC17_RTC),y) +CHIP_CSRCS += lpc176x_rtc.c +endif + +ifeq ($(CONFIG_LPC17_PWM1),y) +CHIP_CSRCS += lpc17_pwm.c +endif + +ifeq ($(CONFIG_LPC17_MCPWM),y) +CHIP_CSRCS += lpc17_mcpwm.c +endif + +ifeq ($(CONFIG_LPC17_TMR0),y) +CHIP_CSRCS += lpc17_timer.c +endif diff --git a/nuttx/arch/arm/src/lpc17xx/lpc176x_rtc.c b/nuttx/arch/arm/src/lpc17xx/lpc176x_rtc.c new file mode 100644 index 000000000..28a4c5e61 --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/lpc176x_rtc.c @@ -0,0 +1,452 @@ +/************************************************************************************ + * arch/arm/src/lpc17xx/lpc176x_rtcc.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "chip.h" +#include "chip/lpc17_syscon.h" + +#include "lpc17_rtc.h" + +#ifdef CONFIG_RTC + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ +/* This RTC implementation supports only date/time RTC hardware */ + +#ifndef CONFIG_RTC_DATETIME +# error "CONFIG_RTC_DATETIME must be set to use this driver" +#endif + +#ifdef CONFIG_RTC_HIRES +# error "CONFIG_RTC_HIRES must NOT be set with this driver" +#endif + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_RTC +#endif + +/* Constants ************************************************************************/ + +/* Debug ****************************************************************************/ + +#ifdef CONFIG_DEBUG_RTC +# define rtcdbg dbg +# define rtcvdbg vdbg +# define rtclldbg lldbg +# define rtcllvdbg llvdbg +#else +# define rtcdbg(x...) +# define rtcvdbg(x...) +# define rtclldbg(x...) +# define rtcllvdbg(x...) +#endif + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/* Callback to use when the alarm expires */ + +#ifdef CONFIG_RTC_ALARM +static alarmcb_t g_alarmcb; +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/* g_rtc_enabled is set true after the RTC has successfully initialized */ + +volatile bool g_rtc_enabled = false; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ +/************************************************************************************ + * Name: rtc_dumpregs + * + * Description: + * Disable RTC write protection + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifdef CONFIG_DEBUG_RTC +static void rtc_dumpregs(FAR const char *msg) +{ + rtclldbg("%s:\n", msg); + rtclldbg(" DOM : %08x\n", (getreg32(LPC17_RTC_DOM) & RTC_DOM_MASK)); + rtclldbg(" DOW : %08x\n", (getreg32(LPC17_RTC_DOW) & RTC_DOW_MASK)); +} +#else +# define rtc_dumpregs(msg) +#endif + +/************************************************************************************ + * Name: rtc_dumptime + * + * Description: + * Disable RTC write protection + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifdef CONFIG_DEBUG_RTC +static void rtc_dumptime(FAR struct tm *tp, FAR const char *msg) +{ + rtclldbg("%s:\n", msg); + rtclldbg(" tm_sec: %08x\n", tp->tm_sec); + rtclldbg(" tm_min: %08x\n", tp->tm_min); + rtclldbg(" tm_hour: %08x\n", tp->tm_hour); + rtclldbg(" tm_mday: %08x\n", tp->tm_mday); + rtclldbg(" tm_mon: %08x\n", tp->tm_mon); + rtclldbg(" tm_year: %08x\n", tp->tm_year); +} +#else +# define rtc_dumptime(tp, msg) +#endif + +/************************************************************************************ + * Name: rtc_setup + * + * Description: + * Performs first time configuration of the RTC. A special value written into + * back-up register 0 will prevent this function from being called on sub-sequent + * resets or power up. + * + * Input Parameters: + * None + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +static int rtc_setup(void) +{ + uint32_t regval; + int ret; + + /* Clear all register to be default */ + + putreg32((uint32_t)0x00, LPC17_RTC_ILR); + putreg32((uint32_t)0x00, LPC17_RTC_CCR); + putreg32((uint32_t)0x00, LPC17_RTC_CIIR); + putreg32((uint32_t)0xff, LPC17_RTC_AMR); + putreg32((uint32_t)0x00, LPC17_RTC_CALIB); + + /* Enable power to the RTC module */ + + regval = getreg32(LPC17_SYSCON_PCONP); + regval |= SYSCON_PCONP_PCRTC; + putreg32(regval, LPC17_SYSCON_PCONP); + + /* Enable counters */ + + putreg32((uint32_t)0x01, LPC17_RTC_CCR); + return ret; +} + +/************************************************************************************ + * Name: rtc_resume + * + * Description: + * Called when the RTC was already initialized on a previous power cycle. This + * just brings the RTC back into full operation. + * + * Input Parameters: + * None + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +static int rtc_resume(void) +{ +#ifdef CONFIG_RTC_ALARM + uint32_t regval; +#endif + int ret; + + /* Clear the RTC alarm flags */ + +#ifdef CONFIG_RTC_ALARM +#endif + return ret; +} + +/************************************************************************************ + * Name: rtc_interrupt + * + * Description: + * RTC interrupt service routine + * + * Input Parameters: + * irq - The IRQ number that generated the interrupt + * context - Architecture specific register save information. + * + * Returned Value: + * Zero (OK) on success; A negated errno value on failure. + * + ************************************************************************************/ + +#if CONFIG_RTC_ALARM +static int rtc_interrupt(int irq, void *context) +{ +#warning "Missing logic" + return OK; +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: up_rtcinitialize + * + * Description: + * Initialize the hardware RTC per the selected configuration. This function is + * called once during the OS initialization sequence + * + * Input Parameters: + * None + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +int up_rtcinitialize(void) +{ + uint32_t regval; + int ret; + + rtc_dumpregs("On reset"); + + /* Attach the RTC interrupt handler */ + + ret = irq_attach(LPC17_IRQ_RTC, rtc_interrupt); + if (ret == OK) + { + up_enable_irq(LPC17_IRQ_RTC); + } + + /* Perform the one-time setup of the RTC */ + + ret = rtc_setup(); + + /* Configure RTC interrupt to catch alarm interrupts. All RTC interrupts are + * connected to the EXTI controller. To enable the RTC Alarm interrupt, the + * following sequence is required: + * + * 1. Configure and enable the EXTI Line 17 in interrupt mode and select the + * rising edge sensitivity. + * 2. Configure and enable the RTC_Alarm IRQ channel in the NVIC. + * 3. Configure the RTC to generate RTC alarms (Alarm A or Alarm B). + */ + + g_rtc_enabled = true; + rtc_dumpregs("After Initialization"); + return OK; +} + +/************************************************************************************ + * Name: up_rtc_getdatetime + * + * Description: + * Get the current date and time from the date/time RTC. This interface + * is only supported by the date/time RTC hardware implementation. + * It is used to replace the system timer. It is only used by the RTOS during + * initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME + * are selected (and CONFIG_RTC_HIRES is not). + * + * NOTE: Some date/time RTC hardware is capability of sub-second accuracy. That + * sub-second accuracy is lost in this interface. However, since the system time + * is reinitialized on each power-up/reset, there will be no timing inaccuracy in + * the long run. + * + * Input Parameters: + * tp - The location to return the high resolution time value. + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +int up_rtc_getdatetime(FAR struct tm *tp) +{ + rtc_dumpregs("Reading Time"); + + /* Convert the RTC time to fields in struct tm format. All of the STM32 + * All of the ranges of values correspond between struct tm and the time + * register. + */ + + tp->tm_sec = ((getreg32(LPC17_RTC_SEC) & RTC_SEC_MASK)); + tp->tm_min = ((getreg32(LPC17_RTC_MIN) & RTC_MIN_MASK)); + tp->tm_hour = ((getreg32(LPC17_RTC_HOUR) & RTC_HOUR_MASK)); + + /* Now convert the RTC date to fields in struct tm format: + * Days: 1-31 match in both cases. + * Month: STM32 is 1-12, struct tm is 0-11. + * Years: STM32 is 00-99, struct tm is years since 1900. + * + * Issue: I am not sure what the STM32 years mean. Are these the + * years 2000-2099? I'll assume so. + */ + + tp->tm_mday = ((getreg32(LPC17_RTC_DOM) & RTC_DOM_MASK)); + tp->tm_mon = ((getreg32(LPC17_RTC_MONTH) & RTC_MONTH_MASK)) - 1; + tp->tm_year = ((getreg32(LPC17_RTC_YEAR) & RTC_YEAR_MASK)-1900); + + rtc_dumptime(tp, "Returning"); + return OK; +} + +/************************************************************************************ + * Name: up_rtc_settime + * + * Description: + * Set the RTC to the provided time. All RTC implementations must be able to + * set their time based on a standard timespec. + * + * Input Parameters: + * tp - the time to use + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +int up_rtc_settime(FAR const struct timespec *tp) +{ + FAR struct tm newtime; + int ret; + + /* Break out the time values (not that the time is set only to units of seconds) */ + + (void)gmtime_r(&tp->tv_sec, &newtime); + rtc_dumptime(&newtime, "Setting time"); + + /* Then write the broken out values to the RTC */ + + putreg32(((newtime.tm_sec) & RTC_SEC_MASK), LPC17_RTC_SEC); + putreg32(((newtime.tm_min) & RTC_MIN_MASK), LPC17_RTC_MIN); + putreg32(((newtime.tm_hour) & RTC_HOUR_MASK), LPC17_RTC_HOUR); + putreg32(((newtime.tm_mday) & RTC_DOM_MASK), LPC17_RTC_DOM); + putreg32((((newtime.tm_mon)+1) & RTC_MONTH_MASK), LPC17_RTC_MONTH); + putreg32(((newtime.tm_year) & RTC_YEAR_MASK)+1900, LPC17_RTC_YEAR); + + return ret; +} + +/************************************************************************************ + * Name: up_rtc_setalarm + * + * Description: + * Set up an alarm. Up to two alarms can be supported (ALARM A and ALARM B). + * + * Input Parameters: + * tp - the time to set the alarm + * callback - the function to call when the alarm expires. + * + * Returned Value: + * Zero (OK) on success; a negated errno on failure + * + ************************************************************************************/ + +#ifdef CONFIG_RTC_ALARM +int up_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback) +{ + irqstate_t flags; + int ret = -EBUSY; + + /* Is there already something waiting on the ALARM? */ + + if (g_alarmcb == NULL) + { + /* No.. Save the callback function pointer */ + + g_alarmcb = callback; + + /* Break out the time values */ +#warning "Missing logic" + + /* The set the alarm */ +#warning "Missing logic" + + ret = OK; + } + return ret; +} +#endif + +#endif /* CONFIG_RTC */ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c index 87cc6a717..7c7c31311 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c @@ -7,7 +7,7 @@ * * This file is a part of NuttX: * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2014 Gregory Nutt. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -159,7 +159,11 @@ static void dac_txint(FAR struct dac_dev_s *dev, bool enable) static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg) { - putreg32((msg->am_data>>16)&0xfffff,LPC17_DAC_CR); + /* adjust the binary value to the lpc1768's register format (plus high + * speed profile in bit 16) + */ + + putreg32(((((msg->am_data) << 6) | 0x10000) & 0xffff), LPC17_DAC_CR); dac_txdone(&g_dacdev); return 0; } diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.c b/nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.c new file mode 100644 index 000000000..13876a155 --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_mcpwm.c @@ -0,0 +1,683 @@ +/**************************************************************************** + * arch/arm/src/lpc17xx/lpc17_mcpwm.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "chip/lpc17_syscon.h" +#include "lpc17_pwm.h" +#include "chip/lpc176x_pinconfig.h" +#include "lpc17_gpio.h" +#include "lpc176x_gpio.h" + +/* This module then only compiles if there is at least one enabled timer + * intended for use with the PWM upper half driver. + */ + +#if defined(CONFIG_LPC17_MCPWM) + +/**************************************************************************** + * 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 + +/* Debug ********************************************************************/ +/* Non-standard debug that may be enabled just for testing PWM */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_PWM +#endif + +#ifdef CONFIG_DEBUG_PWM +# define pwmdbg dbg +# define pwmlldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define pwmvdbg vdbg +# define pwmllvdbg llvdbg +# define pwm_dumpgpio(p,m) stm32_dumpgpio(p,m) +# else +# define pwmlldbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +# endif +#else +# define pwmdbg(x...) +# define pwmlldbg(x...) +# define pwmvdbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure represents the state of one PWM timer */ + +struct lpc17_mcpwmtimer_s +{ + FAR const struct pwm_ops_s *ops; /* PWM operations */ + uint8_t timid; /* Timer ID {0,...,7} */ + uint8_t channel; /* Timer output channel: {1,..4} */ + uint8_t timtype; /* See the TIMTYPE_* definitions */ + 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 uint32_t mcpwm_getreg(struct lpc17_mcpwmtimer_s *priv, int offset); +static void mcpwm_putreg(struct lpc17_mcpwmtimer_s *priv, int offset, uint32_t value); + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void mcpwm_dumpregs(struct lpc17_mcpwmtimer_s *priv, FAR const char *msg); +#else +# define mcpwm_dumpregs(priv,msg) +#endif + +/* Timer management */ + +static int mcpwm_timer(FAR struct lpc17_mcpwmtimer_s *priv, + FAR const struct pwm_info_s *info); + +/* PWM driver methods */ + +static int mcpwm_setup(FAR struct pwm_lowerhalf_s *dev); +static int mcpwm_shutdown(FAR struct pwm_lowerhalf_s *dev); + +static int mcpwm_start(FAR struct pwm_lowerhalf_s *dev, + FAR const struct pwm_info_s *info); + +static int mcpwm_stop(FAR struct pwm_lowerhalf_s *dev); +static int mcpwm_ioctl(FAR struct pwm_lowerhalf_s *dev, + int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* This is the list of lower half PWM driver methods used by the upper half + * driver + */ + +static const struct pwm_ops_s g_pwmops = +{ + .setup = mcpwm_setup, + .shutdown = mcpwm_shutdown, + .start = mcpwm_start, + .stop = mcpwm_stop, + .ioctl = mcpwm_ioctl, +}; + +#ifdef CONFIG_LPC17_MCPWM +static struct lpc17_mcpwmtimer_s g_pwm1dev = +{ + .ops = &g_pwmops, + .timid = 1, + .channel = CONFIG_LPC17_MCPWM1_PIN, + .timtype = TIMTYPE_TIM1, + .base = LPC17_MCPWM_BASE, + .pincfg = GPIO_MCPWM_MCOA0, + .pclk = (0x1<<12), +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mcpwm_getreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * The current contents of the specified register + * + ****************************************************************************/ + +static uint32_t mcpwm_getreg(struct lpc17_mcpwmtimer_s *priv, int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: mcpwm_putreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void mcpwm_putreg(struct lpc17_mcpwmtimer_s *priv, int offset, uint32_t value) +{ + putreg32(value, priv->base + offset); +} + +/**************************************************************************** + * Name: mcpwm_dumpregs + * + * Description: + * Dump all timer registers. + * + * Input parameters: + * priv - A reference to the PWM block status + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void mcpwm_dumpregs(FAR struct lpc17_mcpwmtimer_s *priv, + FAR const char *msg) +{ + pwmvdbg("%s:\n", msg); + pwmvdbg(" CR1: %04x CR2: %04x SMCR: %04x DIER: %04x\n", + mcpwm_getreg(priv, LPC17_PWM_MR0_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR1_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); +#if defined(CONFIG_LPC17_MCPWM) + if (priv->timtype == TIMTYPE_ADVANCED) + { + pwmvdbg(" RCR: %04x BDTR: %04x DCR: %04x DMAR: %04x\n", + mcpwm_getreg(priv, LPC17_PWM_MR0_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR1_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } + else +#endif + { + pwmvdbg(" DCR: %04x DMAR: %04x\n", + mcpwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + mcpwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } +} +#endif + +/**************************************************************************** + * Name: mcpwm_timer + * + * Description: + * (Re-)initialize the timer resources and start the pulsed output + * + * Input parameters: + * priv - 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 + * + ****************************************************************************/ + +static int mcpwm_timer(FAR struct lpc17_mcpwmtimer_s *priv, + FAR const struct pwm_info_s *info) +{ + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + putreg32(info->frequency, LPC17_MCPWM_LIM0); /* Set PWMMR0 = number of counts */ + putreg32(info->duty, LPC17_MCPWM_MAT0); /* Set PWM cycle */ + + irqrestore(flags); + mcpwm_dumpregs(priv, "After starting"); + return OK; +} + +#ifdef XXXXX +/**************************************************************************** + * Name: mcpwm_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 + * + ****************************************************************************/ + +static int mcpwm_interrupt(struct lpc17_mcpwmtimer_s *priv) +{ + uint16_t regval; + + /* Verify that this is an update interrupt. Nothing else is expected. */ + + regval = mcpwm_getreg(priv, STM32_ATIM_SR_OFFSET); + DEBUGASSERT((regval & ATIM_SR_UIF) != 0); + + /* Clear the UIF interrupt bit */ + + mcpwm_putreg(priv, STM32_ATIM_SR_OFFSET, regval & ~ATIM_SR_UIF); + + /* Calculate the new count by subtracting the number of pulses + * since the last interrupt. + */ + + return OK; +} + +/**************************************************************************** + * Name: mcpwm_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 + * + ****************************************************************************/ + +static int mcpwm_tim1interrupt(int irq, void *context) +{ + return mcpwm_interrupt(&g_pwm1dev); +} + +/**************************************************************************** + * Name: mcpwm_set_apb_clock + * + * Description: + * Enable or disable APB clock for the timer peripheral + * + * Input parameters: + * dev - A reference to the lower half PWM driver state structure + * on - Enable clock if 'on' is 'true' and disable if 'false' + * + ****************************************************************************/ + +static void mcpwm_set_apb_clock(FAR struct lpc17_mcpwmtimer_s *priv, bool on) +{ + uint32_t en_bit; + uint32_t regaddr; + + /* Determine which timer to configure */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_MCPWM + case 1: + regaddr = STM32_RCC_APB2ENR; + en_bit = RCC_APB2ENR_TIM1EN; + break; +#endif + } + + /* Enable/disable APB 1/2 clock for timer */ + + if (on) + { + modifyreg32(regaddr, 0, en_bit); + } + else + { + modifyreg32(regaddr, en_bit, 0); + } +} +#endif /*XXXXX*/ + +/**************************************************************************** + * Name: mcpwm_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: + * APB1 or 2 clocking for the GPIOs has already been configured by the RCC + * logic at power up. + * + ****************************************************************************/ + +static int mcpwm_setup(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_mcpwmtimer_s *priv = (FAR struct lpc17_mcpwmtimer_s *)dev; + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + /* Power on the mcpwm peripheral */ + + regval = getreg32(LPC17_SYSCON_PCONP); + regval |= SYSCON_PCONP_PCMCPWM; + putreg32(regval, LPC17_SYSCON_PCONP); + + /* Select clock for the mcpwm peripheral */ + + regval = getreg32(LPC17_SYSCON_PCLKSEL1); + regval &= ~(0x3 << 30); + regval |= (0x2 << 30); /* PCLK_MC peripheral clk = CCLK/2 = 50 MHz */ + putreg32(regval, LPC17_SYSCON_PCLKSEL1); + priv->pclk = (0x1 << 12) | (0x1 << 4); + + putreg32((1 << 15), LPC17_MCPWM_INTENCLR); /* Disable MCABORT pin interrupt */ + putreg32((1 << 0), LPC17_MCPWM_INTENCLR); /* Disable ILIM0 interrupt */ + putreg32((1 << 1), LPC17_MCPWM_INTENCLR); /* Disable IMAT0 interrupt */ + putreg32((1 << 2), LPC17_MCPWM_INTENCLR); /* Disable ICAP0 interrupt */ + putreg32((1 << 4), LPC17_MCPWM_INTENCLR); /* Disable ILIM1 interrupt */ + putreg32((1 << 5), LPC17_MCPWM_INTENCLR); /* Disable IMAT1 interrupt */ + putreg32((1 << 6), LPC17_MCPWM_INTENCLR); /* Disable ICAP1 interrupt */ + putreg32((1 << 8), LPC17_MCPWM_INTENCLR); /* Disable ILIM2 interrupt */ + putreg32((1 << 9), LPC17_MCPWM_INTENCLR); /* Disable IMAT2 interrupt */ + putreg32((1 << 10), LPC17_MCPWM_INTENCLR); /* Disable ICAP2 interrupt */ + + putreg32((0xFFFFFFFF), LPC17_MCPWM_CAPCLR);/* Clear all event capture */ + + /* Configure the output pins*/ + + lpc17_configgpio(GPIO_MCPWM_MCOA0); + lpc17_configgpio(GPIO_MCPWM_MCOB0); + + /* Program the timing registers */ + + putreg32((1 << 0), LPC17_MCPWM_CONCLR); /* Stop MCPWM timer0 */ + putreg32((1 << 8), LPC17_MCPWM_CONCLR); /* Stop MCPWM timer1 */ + putreg32((1 << 16), LPC17_MCPWM_CONCLR); /* Stop MCPWM timer2 */ + + putreg32((1 << 30), LPC17_MCPWM_CONCLR); /* MCPWM not in AC mode */ + + putreg32(1000, LPC17_MCPWM_TC0); /* Count frequency: Fpclk/1000 = 50 MHz/1000 = 50 KHz */ + putreg32(400, LPC17_MCPWM_LIM0); /* Set the starting duty cycle to 0.25 */ + putreg32(0, LPC17_MCPWM_MAT0); /* Reset the timer */ + + putreg32(100000, LPC17_MCPWM_TC1); /* Count frequency:Fpclk/100000 = 50 MHz/100000 = 500 Hz*/ + putreg32(50000, LPC17_MCPWM_LIM1); /* Set the starting duty cycle to 0.5 */ + putreg32(0, LPC17_MCPWM_MAT1); /* Reset the timer */ + + putreg32(1000, LPC17_MCPWM_TC2); /* Count frequency:Fpclk/1000 = 50 MHz/1000 = 50 KHz */ + putreg32(400, LPC17_MCPWM_LIM2); /* Set the starting duty cycle to 0.25 */ + putreg32(0, LPC17_MCPWM_MAT2); /* Reset the timer */ + + putreg32((1 << 2), LPC17_MCPWM_CONCLR); /* Channel 0 polarity set to default */ + putreg32((1 << 10), LPC17_MCPWM_CONCLR); /* Channel 1 polarity set to default */ + putreg32((1 << 18), LPC17_MCPWM_CONCLR); /* Channel 2 polarity set to default */ + + putreg32((1 << 3), LPC17_MCPWM_CONCLR); /* Channel 0 dead time disabled */ + putreg32((1 << 11), LPC17_MCPWM_CONCLR); /* Channel 1 dead time disabled */ + putreg32((1 << 19), LPC17_MCPWM_CONCLR); /* Channel 2 dead time disabled */ + + putreg32((1 << 1), LPC17_MCPWM_CONCLR); /* Channel 0 edge aligned */ + putreg32((1 << 9), LPC17_MCPWM_CONCLR); /* Channel 1 edge aligned */ + putreg32((1 << 17), LPC17_MCPWM_CONCLR); /* Channel 2 edge aligned */ + + putreg32((0xFFFFFFFF), LPC17_MCPWM_CNTCONCLR);/* All channels in counter mode on PCLK */ + + putreg32((1 << 0), LPC17_MCPWM_CONSET); /* Start MCPWM timer0 */ + + irqrestore(flags); + pwm_dumpgpio(priv->pincfg, "PWM setup"); + return OK; +} + +/**************************************************************************** + * Name: mcpwm_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 mcpwm_shutdown(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_mcpwmtimer_s *priv = (FAR struct lpc17_mcpwmtimer_s *)dev; + uint32_t pincfg; + + pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->pincfg); + + /* Make sure that the output has been stopped */ + + return OK; +} + +/**************************************************************************** + * Name: mcpwm_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 + * + ****************************************************************************/ + +static int mcpwm_start(FAR struct pwm_lowerhalf_s *dev, + FAR const struct pwm_info_s *info) +{ + FAR struct lpc17_mcpwmtimer_s *priv = (FAR struct lpc17_mcpwmtimer_s *)dev; + return mcpwm_timer(priv, info); +} + +/**************************************************************************** + * Name: mcpwm_stop + * + * Description: + * Stop the pulsed output and reset the timer resources + * + * 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: + * 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 mcpwm_stop(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_mcpwmtimer_s *priv = (FAR struct lpc17_mcpwmtimer_s *)dev; + uint32_t resetbit; + uint32_t regaddr; + uint32_t regval; + irqstate_t flags; + + 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 */ + + /* Determine which timer to reset */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_MCPWM + case 1: + break; +#endif + } + + /* Reset the timer - stopping the output and putting the timer back + * into a state where mcpwm_start() can be called. + */ + + irqrestore(flags); + + pwmvdbg("regaddr: %08x resetbit: %08x\n", regaddr, resetbit); + mcpwm_dumpregs(priv, "After stop"); + return OK; +} + +/**************************************************************************** + * Name: mcpwm_ioctl + * + * Description: + * Lower-half logic may support platform-specific ioctl commands + * + * Input parameters: + * dev - A reference to the lower half PWM driver state structure + * cmd - The ioctl command + * arg - The argument accompanying the ioctl command + * + * Returned Value: + * Zero on success; a negated errno value on failure + * + ****************************************************************************/ + +static int mcpwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg) +{ +#ifdef CONFIG_DEBUG_PWM + FAR struct lpc17_mcpwmtimer_s *priv = (FAR struct lpc17_mcpwmtimer_s *)dev; + + /* There are no platform-specific ioctl commands */ + + pwmvdbg("TIM%d\n", priv->timid); +#endif + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc17_mcpwminitialize + * + * Description: + * Initialize one timer for use with the upper_level PWM driver. + * + * Input Parameters: + * timer - A number identifying the timer use. The number of valid timer + * IDs varies with the STM32 MCU and MCU family but is somewhere in + * the range of {1,..,14}. + * + * Returned Value: + * On success, a pointer to the STM32 lower half PWM driver is returned. + * NULL is returned on any failure. + * + ****************************************************************************/ + +FAR struct pwm_lowerhalf_s *lpc17_mcpwminitialize(int timer) +{ + FAR struct lpc17_mcpwmtimer_s *lower; + + pwmvdbg("TIM%d\n", timer); + + switch (timer) + { +#ifdef CONFIG_LPC17_MCPWM + case 0: + lower = &g_pwm1dev; + + /* Attach but disable the TIM1 update interrupt */ + + break; +#endif + + default: + pwmdbg("No such timer configured\n"); + return NULL; + } + + return (FAR struct pwm_lowerhalf_s *)lower; +} + +#endif /* CONFIG_LPC17_TIMn_PWM, n = 1,...,14 */ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.c b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.c new file mode 100644 index 000000000..e9efc0cd5 --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.c @@ -0,0 +1,655 @@ +/**************************************************************************** + * arch/arm/src/lpc17xx/lpc17_pwm.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "chip/lpc17_syscon.h" +#include "lpc17_pwm.h" +#include "chip/lpc176x_pinconfig.h" +#include "lpc17_gpio.h" +#include "lpc176x_gpio.h" + +/* This module then only compiles if there is at least one enabled timer + * intended for use with the PWM upper half driver. + */ + +#if defined(CONFIG_LPC17_PWM1) + +/**************************************************************************** + * 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 + + +#define LER0_EN (1 << 0) +#define LER1_EN (1 << 1) +#define LER2_EN (1 << 2) +#define LER3_EN (1 << 3) +#define LER4_EN (1 << 4) +#define LER5_EN (1 << 5) +#define LER6_EN (1 << 6) +#define PWMENA1 (1 << 9) +#define PWMENA2 (1 << 10) +#define PWMENA3 (1 << 11) +#define PWMENA4 (1 << 12) +#define PWMENA5 (1 << 13) +#define PWMENA6 (1 << 14) +#define TCR_CNT_EN (0x00000001) +#define TCR_RESET (0x00000002) +#define TCR_PWM_EN (0x00000008) + +/* Debug ********************************************************************/ +/* Non-standard debug that may be enabled just for testing PWM */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_PWM +#endif + +#ifdef CONFIG_DEBUG_PWM +# define pwmdbg dbg +# define pwmlldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define pwmvdbg vdbg +# define pwmllvdbg llvdbg +# define pwm_dumpgpio(p,m) stm32_dumpgpio(p,m) +# else +# define pwmlldbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +# endif +#else +# define pwmdbg(x...) +# define pwmlldbg(x...) +# define pwmvdbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure represents the state of one PWM timer */ + +struct lpc17_pwmtimer_s +{ + FAR const struct pwm_ops_s *ops; /* PWM operations */ + uint8_t timid; /* Timer ID {0,...,7} */ + uint8_t channel; /* Timer output channel: {1,..4} */ + uint8_t timtype; /* See the TIMTYPE_* definitions */ + 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 uint32_t pwm_getreg(struct lpc17_pwmtimer_s *priv, int offset); +static void pwm_putreg(struct lpc17_pwmtimer_s *priv, int offset, uint32_t value); + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void pwm_dumpregs(struct lpc17_pwmtimer_s *priv, FAR const char *msg); +#else +# define pwm_dumpregs(priv,msg) +#endif + +/* Timer management */ + +static int pwm_timer(FAR struct lpc17_pwmtimer_s *priv, + FAR const struct pwm_info_s *info); + +/* 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); + +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); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* This is the list of lower half PWM driver methods used by the upper half driver */ + +static const struct pwm_ops_s g_pwmops = +{ + .setup = pwm_setup, + .shutdown = pwm_shutdown, + .start = pwm_start, + .stop = pwm_stop, + .ioctl = pwm_ioctl, +}; + +#ifdef CONFIG_LPC17_PWM1 +static struct lpc17_pwmtimer_s g_pwm1dev = +{ + .ops = &g_pwmops, + .timid = 1, + .channel = CONFIG_LPC17_PWM1_PIN, + .timtype = TIMTYPE_TIM1, + .base = LPC17_PWM1_BASE, + .pincfg = GPIO_PWM1p1_1, + .pclk = (0x1 << 12), +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pwm_getreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * The current contents of the specified register + * + ****************************************************************************/ + +static uint32_t pwm_getreg(struct lpc17_pwmtimer_s *priv, int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: pwm_putreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void pwm_putreg(struct lpc17_pwmtimer_s *priv, int offset, uint32_t value) +{ + putreg32(value, priv->base + offset); +} + +/**************************************************************************** + * Name: pwm_dumpregs + * + * Description: + * Dump all timer registers. + * + * Input parameters: + * priv - A reference to the PWM block status + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void pwm_dumpregs(struct lpc17_pwmtimer_s *priv, FAR const char *msg) +{ + pwmvdbg("%s:\n", msg); + pwmvdbg(" CR1: %04x CR2: %04x SMCR: %04x DIER: %04x\n", + pwm_getreg(priv, LPC17_PWM_MR0_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR1_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); +#if defined(CONFIG_LPC17_PWM1) + if (priv->timtype == TIMTYPE_ADVANCED) + { + pwmvdbg(" RCR: %04x BDTR: %04x DCR: %04x DMAR: %04x\n", + pwm_getreg(priv, LPC17_PWM_MR0_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR1_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } + else +#endif + { + pwmvdbg(" DCR: %04x DMAR: %04x\n", + pwm_getreg(priv, LPC17_PWM_MR2_OFFSET), + pwm_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } +} +#endif + +/**************************************************************************** + * Name: pwm_timer + * + * Description: + * (Re-)initialize the timer resources and start the pulsed output + * + * Input parameters: + * priv - 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 + * + ****************************************************************************/ + +static int pwm_timer(FAR struct lpc17_pwmtimer_s *priv, + FAR const struct pwm_info_s *info) +{ + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + putreg32(info->frequency, LPC17_PWM1_MR0); /* Set PWMMR0 = number of counts */ + putreg32(info->duty, LPC17_PWM1_MR1); /* Set PWM cycle */ + + putreg32(LER0_EN | LER3_EN, LPC17_PWM1_LER); /* Load Shadow register contents */ + putreg32(PWMENA1, LPC17_PWM1_PCR); /* Enable PWM outputs */ + putreg32(TCR_CNT_EN | TCR_PWM_EN, LPC17_PWM1_TCR); /* Enable PWM Timer */ + + irqrestore(flags); + pwm_dumpregs(priv, "After starting"); + return OK; +} + +#ifdef XXXXX +/**************************************************************************** + * 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 + * + ****************************************************************************/ + +static int pwm_interrupt(struct lpc17_pwmtimer_s *priv) +{ + uint16_t regval; + + /* Verify that this is an update interrupt. Nothing else is expected. */ + + regval = pwm_getreg(priv, STM32_ATIM_SR_OFFSET); + DEBUGASSERT((regval & ATIM_SR_UIF) != 0); + + /* Clear the UIF interrupt bit */ + + pwm_putreg(priv, STM32_ATIM_SR_OFFSET, regval & ~ATIM_SR_UIF); + + /* Calculate the new count by subtracting the number of pulses + * since the last interrupt. + */ + + return OK; +} + +/**************************************************************************** + * 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 + * + ****************************************************************************/ + +static int pwm_tim1interrupt(int irq, void *context) +{ + return pwm_interrupt(&g_pwm1dev); +} + +/**************************************************************************** + * Name: pwm_set_apb_clock + * + * Description: + * Enable or disable APB clock for the timer peripheral + * + * Input parameters: + * dev - A reference to the lower half PWM driver state structure + * on - Enable clock if 'on' is 'true' and disable if 'false' + * + ****************************************************************************/ + +static void pwm_set_apb_clock(FAR struct lpc17_pwmtimer_s *priv, bool on) +{ + uint32_t en_bit; + uint32_t regaddr; + + /* Determine which timer to configure */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_PWM1 + case 1: + regaddr = STM32_RCC_APB2ENR; + en_bit = RCC_APB2ENR_TIM1EN; + break; +#endif + } + + /* Enable/disable APB 1/2 clock for timer */ + + if (on) + { + modifyreg32(regaddr, 0, en_bit); + } + else + { + modifyreg32(regaddr, en_bit, 0); + } +} +#endif /*XXXXX*/ + +/**************************************************************************** + * 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: + * APB1 or 2 clocking for the GPIOs has already been configured by the RCC + * logic at power up. + * + ****************************************************************************/ + +static int pwm_setup(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_pwmtimer_s *priv = (FAR struct lpc17_pwmtimer_s *)dev; + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + /* Power on the pwm peripheral */ + + regval = getreg32(LPC17_SYSCON_PCONP); + regval |= SYSCON_PCONP_PCPWM1; + putreg32(regval, LPC17_SYSCON_PCONP); + + /* Select clock for the pwm peripheral */ + + regval = getreg32(LPC17_SYSCON_PCLKSEL0); + regval &= ~(0x3 << 12); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + regval |= (0x1 << 12); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + putreg32(regval, LPC17_SYSCON_PCLKSEL0); + priv->pclk = (0x1 << 12); + + /* Configure the output pin */ + + lpc17_configgpio(GPIO_PWM1p1_1); + + putreg32(1, LPC17_PWM1_PR); /* Prescaler count frequency:Fpclk/1 */ + putreg32(1 << 1, LPC17_PWM1_MCR); /* Reset on match register MR0 */ + + irqrestore(flags); + pwm_dumpgpio(priv->pincfg, "PWM setup"); + 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 lpc17_pwmtimer_s *priv = (FAR struct lpc17_pwmtimer_s *)dev; + uint32_t pincfg; + + pwmvdbg("TIM%d pincfg: %08x\n", priv->timid, priv->pincfg); + + /* Make sure that the output has been stopped */ + + 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 + * + ****************************************************************************/ + +static int pwm_start(FAR struct pwm_lowerhalf_s *dev, + FAR const struct pwm_info_s *info) +{ + FAR struct lpc17_pwmtimer_s *priv = (FAR struct lpc17_pwmtimer_s *)dev; + return pwm_timer(priv, info); +} + +/**************************************************************************** + * Name: pwm_stop + * + * Description: + * Stop the pulsed output and reset the timer resources + * + * 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: + * 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) +{ + FAR struct lpc17_pwmtimer_s *priv = (FAR struct lpc17_pwmtimer_s *)dev; + uint32_t resetbit; + uint32_t regaddr; + uint32_t regval; + irqstate_t flags; + + 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 */ + + /* Determine which timer to reset */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_PWM1 + case 1: + break; +#endif + } + + /* Reset the timer - stopping the output and putting the timer back + * into a state where pwm_start() can be called. + */ + + irqrestore(flags); + + pwmvdbg("regaddr: %08x resetbit: %08x\n", regaddr, resetbit); + pwm_dumpregs(priv, "After stop"); + return OK; +} + +/**************************************************************************** + * Name: pwm_ioctl + * + * Description: + * Lower-half logic may support platform-specific ioctl commands + * + * Input parameters: + * dev - A reference to the lower half PWM driver state structure + * cmd - The ioctl command + * arg - The argument accompanying the ioctl command + * + * Returned Value: + * Zero on success; a negated errno value on failure + * + ****************************************************************************/ + +static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg) +{ +#ifdef CONFIG_DEBUG_PWM + FAR struct lpc17_pwmtimer_s *priv = (FAR struct lpc17_pwmtimer_s *)dev; + + /* There are no platform-specific ioctl commands */ + + pwmvdbg("TIM%d\n", priv->timid); +#endif + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc17_pwminitialize + * + * Description: + * Initialize one timer for use with the upper_level PWM driver. + * + * Input Parameters: + * timer - A number identifying the timer use. The number of valid timer + * IDs varies with the STM32 MCU and MCU family but is somewhere in + * the range of {1,..,14}. + * + * Returned Value: + * On success, a pointer to the STM32 lower half PWM driver is returned. + * NULL is returned on any failure. + * + ****************************************************************************/ + +FAR struct pwm_lowerhalf_s *lpc17_pwminitialize(int timer) +{ + FAR struct lpc17_pwmtimer_s *lower; + + pwmvdbg("TIM%d\n", timer); + + switch (timer) + { +#ifdef CONFIG_LPC17_PWM1 + case 0: + lower = &g_pwm1dev; + + /* Attach but disable the TIM1 update interrupt */ + + break; +#endif + + default: + pwmdbg("No such timer configured\n"); + return NULL; + } + + return (FAR struct pwm_lowerhalf_s *)lower; +} + +#endif /* CONFIG_LPC17_TIMn_PWM, n = 1,...,14 */ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_timer.c b/nuttx/arch/arm/src/lpc17xx/lpc17_timer.c new file mode 100644 index 000000000..c1e2112de --- /dev/null +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_timer.c @@ -0,0 +1,667 @@ +/**************************************************************************** + * arch/arm/src/lpc17xx/lpc17_timer.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "chip/lpc17_syscon.h" +#include "lpc17_timer.h" +#include "chip/lpc176x_pinconfig.h" +#include "lpc17_gpio.h" +#include "lpc176x_gpio.h" + +/* This module then only compiles if there is at least one enabled timer + * intended for use with the TIMER upper half driver. + */ + +#if defined(CONFIG_LPC17_TMR0) + +/**************************************************************************** + * 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 + + +/* Debug ********************************************************************/ +/* Non-standard debug that may be enabled just for testing PWM */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_PWM +#endif + +#ifdef CONFIG_DEBUG_PWM +# define pwmdbg dbg +# define pwmlldbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define pwmvdbg vdbg +# define pwmllvdbg llvdbg +# define pwm_dumpgpio(p,m) stm32_dumpgpio(p,m) +# else +# define pwmlldbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +# endif +#else +# define pwmdbg(x...) +# define pwmlldbg(x...) +# define pwmvdbg(x...) +# define pwmllvdbg(x...) +# define pwm_dumpgpio(p,m) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure represents the state of one PWM timer */ + +struct lpc17_timer_s +{ + FAR const struct pwm_ops_s *ops; /* PWM operations */ + uint8_t timid; /* Timer ID {0,...,7} */ + uint8_t channel; /* Timer output channel: {1,..4} */ + uint8_t timtype; /* See the TIMTYPE_* definitions */ + 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 uint32_t timer_getreg(struct lpc17_timer_s *priv, int offset); +static void timer_putreg(struct lpc17_timer_s *priv, int offset, uint32_t value); + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void timer_dumpregs(struct lpc17_timer_s *priv, FAR const char *msg); +#else +# define timer_dumpregs(priv,msg) +#endif + +/* Timer management */ + +static int timer_timer(FAR struct lpc17_timer_s *priv, + FAR const struct pwm_info_s *info); + +/* PWM driver methods */ + +static int timer_setup(FAR struct pwm_lowerhalf_s *dev); +static int timer_shutdown(FAR struct pwm_lowerhalf_s *dev); + +static int timer_start(FAR struct pwm_lowerhalf_s *dev, + FAR const struct pwm_info_s *info); + +static int timer_stop(FAR struct pwm_lowerhalf_s *dev); +static int timer_ioctl(FAR struct pwm_lowerhalf_s *dev, + int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* This is the list of lower half PWM driver methods used by the upper half driver */ + +static const struct pwm_ops_s g_pwmops = +{ + .setup = timer_setup, + .shutdown = timer_shutdown, + .start = timer_start, + .stop = timer_stop, + .ioctl = timer_ioctl, +}; + +#ifdef CONFIG_LPC17_TMR0 +static struct lpc17_timer_s g_pwm1dev = +{ + .ops = &g_pwmops, + .timid = 1, + .channel = CONFIG_LPC17_MAT0_PIN, + .timtype = TIMTYPE_TIM1, + .base = LPC17_TMR1_BASE, + .pincfg = GPIO_MAT0p1_2, + .pclk = (0x1 << 12), +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: timer_getreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * The current contents of the specified register + * + ****************************************************************************/ + +static uint32_t timer_getreg(struct lpc17_timer_s *priv, int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: timer_putreg + * + * Description: + * Read the value of an PWM timer register. + * + * Input Parameters: + * priv - A reference to the PWM block status + * offset - The offset to the register to read + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void timer_putreg(struct lpc17_timer_s *priv, int offset, + uint32_t value) +{ + putreg32(value, priv->base + offset); +} + +/**************************************************************************** + * Name: timer_dumpregs + * + * Description: + * Dump all timer registers. + * + * Input parameters: + * priv - A reference to the PWM block status + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_PWM) && defined(CONFIG_DEBUG_VERBOSE) +static void timer_dumpregs(struct lpc17_timer_s *priv, FAR const char *msg) +{ + pwmdbg("%s:\n", msg); + pwmdbg(" CR1: %04x CR2: %04x SMCR: %04x DIER: %04x\n", + timer_getreg(priv, LPC17_PWM_MR0_OFFSET), + timer_getreg(priv, LPC17_PWM_MR1_OFFSET), + timer_getreg(priv, LPC17_PWM_MR2_OFFSET), + timer_getreg(priv, LPC17_PWM_MR3_OFFSET)); +#if defined(CONFIG_LPC17_TMR0) + if (priv->timtype == TIMTYPE_ADVANCED) + { + pwmdbg(" RCR: %04x BDTR: %04x DCR: %04x DMAR: %04x\n", + timer_getreg(priv, LPC17_PWM_MR0_OFFSET), + timer_getreg(priv, LPC17_PWM_MR1_OFFSET), + timer_getreg(priv, LPC17_PWM_MR2_OFFSET), + timer_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } + else +#endif + { + pwmdbg(" DCR: %04x DMAR: %04x\n", + timer_getreg(priv, LPC17_PWM_MR2_OFFSET), + timer_getreg(priv, LPC17_PWM_MR3_OFFSET)); + } +} +#endif + +/**************************************************************************** + * Name: timer_timer + * + * Description: + * (Re-)initialize the timer resources and start the pulsed output + * + * Input parameters: + * priv - 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 + * + ****************************************************************************/ + +static int timer_timer(FAR struct lpc17_timer_s *priv, + FAR const struct pwm_info_s *info) +{ + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + putreg32(info->frequency, LPC17_TMR0_MR1); /* Set TIMER MR0 = number of counts */ + putreg32(info->frequency, LPC17_TMR1_MR0); /* Set TIMER MR0 = number of counts */ + + putreg32(1, LPC17_TMR0_TCR); /* Start timer0*/ + putreg32(1, LPC17_TMR1_TCR); /* Start timer0*/ + + irqrestore(flags); + timer_dumpregs(priv, "After starting"); + return OK; +} + +#ifdef XXXXX +/**************************************************************************** + * Name: timer_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 + * + ****************************************************************************/ + +static int timer_interrupt(struct lpc17_timer_s *priv) +{ + uint16_t regval; + + /* Verify that this is an update interrupt. Nothing else is expected. */ + + regval = timer_getreg(priv, STM32_ATIM_SR_OFFSET); + DEBUGASSERT((regval & ATIM_SR_UIF) != 0); + + /* Clear the UIF interrupt bit */ + + timer_putreg(priv, STM32_ATIM_SR_OFFSET, regval & ~ATIM_SR_UIF); + + /* Calculate the new count by subtracting the number of pulses + * since the last interrupt. + */ + + return OK; +} + +/**************************************************************************** + * Name: timer_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 + * + ****************************************************************************/ + +static int timer_tim1interrupt(int irq, void *context) +{ + return timer_interrupt(&g_pwm1dev); +} + +/**************************************************************************** + * Name: timer_set_apb_clock + * + * Description: + * Enable or disable APB clock for the timer peripheral + * + * Input parameters: + * dev - A reference to the lower half PWM driver state structure + * on - Enable clock if 'on' is 'true' and disable if 'false' + * + ****************************************************************************/ + +static void timer_set_apb_clock(FAR struct lpc17_timer_s *priv, bool on) +{ + uint32_t en_bit; + uint32_t regaddr; + + /* Determine which timer to configure */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_TMR0 + case 1: + regaddr = STM32_RCC_APB2ENR; + en_bit = RCC_APB2ENR_TIM1EN; + break; +#endif + } + + /* Enable/disable APB 1/2 clock for timer */ + + if (on) + { + modifyreg32(regaddr, 0, en_bit); + } + else + { + modifyreg32(regaddr, en_bit, 0); + } +} +#endif /*XXXXX*/ + +/**************************************************************************** + * Name: timer_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: + * APB1 or 2 clocking for the GPIOs has already been configured by the RCC + * logic at power up. + * + ****************************************************************************/ + +static int timer_setup(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_timer_s *priv = (FAR struct lpc17_timer_s *)dev; + irqstate_t flags; + uint32_t regval; + + flags = irqsave(); + + /* Power on the timer peripherals*/ + + regval = getreg32(LPC17_SYSCON_PCONP); + regval |= SYSCON_PCONP_PCTIM0; + regval |= SYSCON_PCONP_PCTIM1; + regval |= SYSCON_PCONP_PCTIM2; + regval |= SYSCON_PCONP_PCTIM3; + putreg32(regval, LPC17_SYSCON_PCONP); + + /* Select clock for the timer peripheral*/ + + regval = getreg32(LPC17_SYSCON_PCLKSEL0); + regval &= ~(0x3 << 2); + regval |= (0x1 << 2); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + regval &= ~(0x3 << 4); + regval |= (0x1 << 4); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + putreg32(regval, LPC17_SYSCON_PCLKSEL0); + regval = getreg32(LPC17_SYSCON_PCLKSEL1); + regval &= ~(0x3 << 12); + regval |= (0x1 << 12); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + regval &= ~(0x3 << 14); + regval |= (0x1 << 14); /* PCLK_MC peripheral clk = CCLK = 12.5 MHz */ + putreg32(regval, LPC17_SYSCON_PCLKSEL1); + priv->pclk = (0x1 << 12) | (0x1 << 4); + + putreg32(500, LPC17_TMR0_MR1); /* Set TIMER0 MR1 = number of counts */ + + putreg32(1, LPC17_TMR0_PR); /* Prescaler count frequency:Fpclk/1 */ + putreg32(~(0x3 << 0), LPC17_TMR0_CCR); /* Prescaler count frequency:Fpclk/1 */ + putreg32(~(0x3 << 0), LPC17_TMR0_CTCR);/* Prescaler count frequency:Fpclk/1 */ + putreg32((2 << 3), LPC17_TMR0_MCR); /* Reset on match register MR1*/ + putreg32(((1 << 1)|(3 << 6)), LPC17_TMR0_EMR); /* Output bit toggle on external match event*/ + putreg32((1 << 0), LPC17_TMR0_TCR); /* Start timer0*/ + + /* Sonfigure the output pins GPIO3.26*/ + + lpc17_configgpio(GPIO_MAT0p1_2); + + putreg32(1000, LPC17_TMR1_MR0); /* Set TIMER1 MR0 = number of counts */ + + putreg32(1, LPC17_TMR1_PR); /* Prescaler count frequency:Fpclk/1 */ + putreg32(~(0x3 << 0), LPC17_TMR1_CCR); /* Prescaler count frequency:Fpclk/1 */ + putreg32(~(0x3 << 0), LPC17_TMR1_CTCR);/* Prescaler count frequency:Fpclk/1 */ + putreg32((2 << 0), LPC17_TMR1_MCR); /* Reset on match register MR0 */ +// putreg32(((1 << 0)|(3 << 4)), LPC17_TMR1_EMR); /* Output bit toggle on external match event MAT0*/ + putreg32((1 << 0), LPC17_TMR1_TCR); /* Start timer1*/ + + /* configure the output pins GPIO3.26 */ +// lpc17_configgpio(GPIO_MAT0p1_2); + + irqrestore(flags); + pwm_dumpgpio(priv->pincfg, "TIMER setup"); + return OK; +} + +/**************************************************************************** + * Name: timer_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 TIMER driver state structure + * + * Returned Value: + * Zero on success; a negated errno value on failure + * + ****************************************************************************/ + +static int timer_shutdown(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_timer_s *priv = (FAR struct lpc17_timer_s *)dev; + uint32_t pincfg; + + pwmdbg("TIM%d pincfg: %08x\n", priv->timid, priv->pincfg); + + /* Make sure that the output has been stopped */ + + return OK; +} + +/**************************************************************************** + * Name: timer_start + * + * Description: + * (Re-)initialize the timer resources and start the pulsed output + * + * Input parameters: + * dev - A reference to the lower half TIMER driver state structure + * info - A reference to the characteristics of the pulsed output + * + * Returned Value: + * Zero on success; a negated errno value on failure + * + ****************************************************************************/ + +static int timer_start(FAR struct pwm_lowerhalf_s *dev, + FAR const struct pwm_info_s *info) +{ + FAR struct lpc17_timer_s *priv = (FAR struct lpc17_timer_s *)dev; + return timer_timer(priv, info); +} + +/**************************************************************************** + * Name: timer_stop + * + * Description: + * Stop the pulsed output and reset the timer resources + * + * Input parameters: + * dev - A reference to the lower half TIMER driver state structure + * + * 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 timer_stop(FAR struct pwm_lowerhalf_s *dev) +{ + FAR struct lpc17_timer_s *priv = (FAR struct lpc17_timer_s *)dev; + uint32_t resetbit; + uint32_t regaddr; + uint32_t regval; + irqstate_t flags; + + pwmdbg("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 */ + + /* Determine which timer to reset */ + + switch (priv->timid) + { +#ifdef CONFIG_LPC17_TMR0 + case 1: + break; +#endif + } + + /* Reset the timer - stopping the output and putting the timer back + * into a state where timer_start() can be called. + */ + + irqrestore(flags); + + pwmdbg("regaddr: %08x resetbit: %08x\n", regaddr, resetbit); + timer_dumpregs(priv, "After stop"); + return OK; +} + +/**************************************************************************** + * Name: timer_ioctl + * + * Description: + * Lower-half logic may support platform-specific ioctl commands + * + * Input parameters: + * dev - A reference to the lower half TIMER driver state structure + * cmd - The ioctl command + * arg - The argument accompanying the ioctl command + * + * Returned Value: + * Zero on success; a negated errno value on failure + * + ****************************************************************************/ + +static int timer_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg) +{ +#ifdef CONFIG_DEBUG_TIMER + FAR struct lpc17_timer_s *priv = (FAR struct lpc17_timer_s *)dev; + + /* There are no platform-specific ioctl commands */ + + pwmdbg("TIM%d\n", priv->timid); +#endif + return -ENOTTY; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc17_timerinitialize + * + * Description: + * Initialize one timer for use with the upper_level TIMER driver. + * + * Input Parameters: + * timer - A number identifying the timer use. The number of valid timer + * IDs varies with the STM32 MCU and MCU family but is somewhere in + * the range of {1,..,14}. + * + * Returned Value: + * On success, a pointer to the STM32 lower half TIMER driver is returned. + * NULL is returned on any failure. + * + ****************************************************************************/ + +FAR struct pwm_lowerhalf_s *lpc17_timerinitialize(int timer) +{ + FAR struct lpc17_timer_s *lower; + + pwmdbg("TIM%d\n", timer); + + switch (timer) + { +#ifdef CONFIG_LPC17_TMR0 + case 0: + lower = &g_pwm1dev; + + /* Attach but disable the TIM1 update interrupt */ + + break; +#endif + + default: + pwmdbg("No such timer configured\n"); + return NULL; + } + + return (FAR struct pwm_lowerhalf_s *)lower; +} + +#endif /* CONFIG_LPC17_TIMn_TIMER, n = 1,...,14 */ diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile index 0ad6b33d2..5bdf9459e 100644 --- a/nuttx/configs/lpcxpresso-lpc1768/src/Makefile +++ b/nuttx/configs/lpcxpresso-lpc1768/src/Makefile @@ -1,7 +1,7 @@ ############################################################################ # configs/lpcxpresso-lpc1768/src/Makefile # -# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012, 2014 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -38,7 +38,7 @@ CFLAGS += -I$(TOPDIR)/sched ASRCS = -CSRCS = up_boot.c up_leds.c up_ssp.c +CSRCS = up_boot.c up_leds.c up_ssp.c up_adc.c up_dac.c up_pwm.c ifeq ($(CONFIG_NSH_ARCHINIT),y) CSRCS += up_nsh.c diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_adc.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_adc.c new file mode 100644 index 000000000..cb5b296b9 --- /dev/null +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_adc.c @@ -0,0 +1,123 @@ +/************************************************************************************ + * configs/lpcexpresso-1768/src/up_adc.c + * arch/arm/src/board/up_adc.c + * + * Copyright (C) 2013 Zilogic Systems. All rights reserved. + * Author: Kannan + * + * Based on configs/stm3220g-eval/src/up_adc.c + * + * Copyright (C) 2012, 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "lpc17_adc.h" +#include "lpcxpresso_internal.h" + +#ifdef CONFIG_ADC + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: adc_devinit + * + * Description: + * All LPC17 architectures must provide the following interface to work with + * examples/adc. + * + ************************************************************************************/ + +int adc_devinit(void) +{ + static bool initialized = false; + struct adc_dev_s *adc; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) + { + /* Call lpc17_adcinitialize() to get an instance of the ADC interface */ + + adc = lpc17_adcinitialize(); + if (adc == NULL) + { + adbg("ERROR: Failed to get ADC interface\n"); + return -ENODEV; + } + + /* Register the ADC driver at "/dev/adc0" */ + + ret = adc_register("/dev/adc0", adc); + if (ret < 0) + { + adbg("adc_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_ADC */ diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_dac.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_dac.c new file mode 100644 index 000000000..9b54bea18 --- /dev/null +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_dac.c @@ -0,0 +1,100 @@ +/************************************************************************************ + * configs/zkit-arm-1769/src/up_dac.c + * arch/arm/src/board/up_dac.c + * + * Copyright (C) 2013 Zilogic Systems. All rights reserved. + * Author: Kannan + * + * Based on configs/stm3220g-eval/src/up_dac.c + * + * Copyright (C) 2012, 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "lpc17_dac.h" + +#ifdef CONFIG_DAC + +/************************************************************************************ + * Name: dac_devinit + * + * Description: + * All LPC17xx architectures must provide the following interface to work with + * examples/diag. + * + ************************************************************************************/ + +int dac_devinit(void) +{ + static bool initialized = false; + struct dac_dev_s *dac; + int ret; + + if (!initialized) + { + /* Call lpc17_dacinitialize() to get an instance of the dac interface */ + + dac = lpc17_dacinitialize(); + if (dac == NULL) + { + adbg("ERROR: Failed to get dac interface\n"); + return -ENODEV; + } + + ret = dac_register("/dev/dac0", dac); + if (ret < 0) + { + adbg("dac_register failed: %d\n", ret); + return ret; + } + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_DAC */ diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_pwm.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_pwm.c new file mode 100644 index 000000000..88741fd0d --- /dev/null +++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_pwm.c @@ -0,0 +1,152 @@ +/************************************************************************************ + * configs/lpcexpresso-lpc1768/up_pwm.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "lpc17_pwm.h" +#include "lpc17_timer.h" +#include "lpcxpresso_internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +#ifdef CONFIG_PWM + +FAR struct pwm_lowerhalf_s *lpc17_pwminitialize(int timer); +FAR struct pwm_lowerhalf_s *lpc17_mcpwminitialize(int timer); +FAR struct pwm_lowerhalf_s *lpc17_timerinitialize(int timer); + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: pwm_devinit + * + * Description: + * All LPC17 architectures must provide the following interface to work with + * examples/pwm. + * + ************************************************************************************/ + +int pwm_devinit(void) +{ + static bool initialized = false; + struct pwm_lowerhalf_s *pwm; + struct pwm_lowerhalf_s *mcpwm; + struct pwm_lowerhalf_s *timer; + int ret; + + /* Have we already initialized? */ + + if (!initialized) + { + /* Call lpc17_pwminitialize() to get an instance of the PWM interface */ + + pwm = lpc17_pwminitialize(0); + if (!pwm) + { + adbg("Failed to get the LPC17XX PWM lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/pwm0" */ + + ret = pwm_register("/dev/pwm0", pwm); + if (ret < 0) + { + adbg("pwm_register failed: %d\n", ret); + return ret; + } + + mcpwm = lpc17_mcpwminitialize(0); + if (!mcpwm) + { + adbg("Failed to get the LPC17XX MOTOR PWM lower half\n"); + return -ENODEV; + } + + /* Register the MOTOR CONTROL PWM driver at "/dev/mcpwm0" */ + + ret = pwm_register("/dev/mcpwm0", mcpwm); + if (ret < 0) + { + adbg("mcpwm_register failed: %d\n", ret); + return ret; + } + + timer = lpc17_timerinitialize(0); + if (!timer) + { + adbg("Failed to get the LPC17XX TIMER lower half\n"); + return -ENODEV; + } + + /* Register the PWM driver at "/dev/timer0" */ + + ret = pwm_register("/dev/timer0", timer); + if (ret < 0) + { + adbg("timer_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif /* CONFIG_PWM */ -- cgit v1.2.3 From 08d4aca769f4a4895522ffe93da32ea9a5995061 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 23 Jun 2014 12:14:06 -0600 Subject: Updated ChangeLog --- nuttx/ChangeLog | 3 +++ 1 file changed, 3 insertions(+) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 035eb508b..43c703361 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -7468,4 +7468,7 @@ Kconfig files from Stefan Sperling (2014-6-23). * net/net_send_unbuffered.c: Remove some spurious white space from field selectors. SourceForge ticket #42 (2014-6-23). + * arch/arm/src/lpc17xx and configs/lpcexpresso-lpc1768: Added support + for the lpcxpresso's rtc handler, adc, dac, timers, pwm and mcpwm + drivers. From Max (himax) (2014-6-23). -- cgit v1.2.3