From 2ac33dcffabd9422659c3b013ed8624c09ae90e4 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 9 Mar 2013 13:29:47 +0000 Subject: ZKIT-ARM-1769 support for ADC and DAC from Rashid git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5723 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc17xx/lpc17_adc.c | 210 ++++++++++++++++++++++----------- nuttx/arch/arm/src/lpc17xx/lpc17_dac.c | 2 + 2 files changed, 145 insertions(+), 67 deletions(-) (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c index 81e13e342..a3d20d8eb 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_adc.c @@ -7,7 +7,7 @@ * * This file is a part of NuttX: * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -66,6 +66,10 @@ #if defined(CONFIG_LPC17_ADC) +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + #ifndef CONFIG_ADC0_MASK #define CONFIG_ADC0_MASK 0x01 #endif @@ -82,11 +86,11 @@ struct up_dev_s { - uint8_t mask; + uint8_t mask; uint32_t sps; - int irq; - int32_t buf[8]; - uint8_t count[8]; + int irq; + int32_t buf[8]; + uint8_t count[8]; }; /**************************************************************************** @@ -108,39 +112,45 @@ static int adc_interrupt(int irq, void *context); static const struct adc_ops_s g_adcops = { - .ao_reset =adc_reset, - .ao_setup = adc_setup, + .ao_reset = adc_reset, + .ao_setup = adc_setup, .ao_shutdown = adc_shutdown, - .ao_rxint = adc_rxint, - .ao_ioctl = adc_ioctl, + .ao_rxint = adc_rxint, + .ao_ioctl = adc_ioctl, }; static struct up_dev_s g_adcpriv = { - .sps = CONFIG_ADC0_SPS, - .mask = CONFIG_ADC0_MASK, - .irq = LPC17_IRQ_ADC, + .sps = CONFIG_ADC0_SPS, + .mask = CONFIG_ADC0_MASK, + .irq = LPC17_IRQ_ADC, }; static struct adc_dev_s g_adcdev = { - .ad_ops = &g_adcops, - .ad_priv= &g_adcpriv, + .ad_ops = &g_adcops, + .ad_priv = &g_adcpriv, }; /**************************************************************************** * Private Functions ****************************************************************************/ -/* Reset the ADC device. Called early to initialize the hardware. This - * is called, before ao_setup() and on error conditions. - */ +/**************************************************************************** + * Name: adc_reset + * + * Description: + * Reset the ADC device. Called early to initialize the hardware. This + * is called, before adc_setup() and on error conditions. + * + ****************************************************************************/ static void adc_reset(FAR struct adc_dev_s *dev) { + FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv; irqstate_t flags; + uint32_t clkdiv; uint32_t regval; - FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv; flags = irqsave(); @@ -148,110 +158,176 @@ static void adc_reset(FAR struct adc_dev_s *dev) regval |= SYSCON_PCONP_PCADC; putreg32(regval, LPC17_SYSCON_PCONP); - putreg32(ADC_CR_PDN,LPC17_ADC_CR); + putreg32(ADC_CR_PDN, LPC17_ADC_CR); regval = getreg32(LPC17_SYSCON_PCLKSEL0); regval &= ~SYSCON_PCLKSEL0_ADC_MASK; regval |= (SYSCON_PCLKSEL_CCLK8 << SYSCON_PCLKSEL0_ADC_SHIFT); putreg32(regval, LPC17_SYSCON_PCLKSEL0); - uint32_t clkdiv=LPC17_CCLK/8/65/priv->sps; - clkdiv<<=8; - clkdiv&=0xff00; - putreg32(ADC_CR_PDN|ADC_CR_BURST|clkdiv|priv->mask,LPC17_ADC_CR); - - if(priv->mask&0x01) - lpc17_configgpio(GPIO_AD0p0); - else if(priv->mask&0x02) - lpc17_configgpio(GPIO_AD0p1); - else if(priv->mask&0x04) - lpc17_configgpio(GPIO_AD0p2); - else if(priv->mask&0x08) - lpc17_configgpio(GPIO_AD0p3); - else if(priv->mask&0x10) - lpc17_configgpio(GPIO_AD0p4); - else if(priv->mask&0x20) - lpc17_configgpio(GPIO_AD0p5); - else if(priv->mask&0x40) - lpc17_configgpio(GPIO_AD0p6); - else if(priv->mask&0x80) - lpc17_configgpio(GPIO_AD0p7); + clkdiv = LPC17_CCLK / 8 / 65 / priv->sps; + clkdiv <<= 8; + clkdiv &= 0xff00; + putreg32(ADC_CR_PDN | ADC_CR_BURST | clkdiv | priv->mask, LPC17_ADC_CR); + + if ((priv->mask & 0x01) != 0) + { + lpc17_configgpio(GPIO_AD0p0); + } + else if ((priv->mask & 0x02) != 0) + { + lpc17_configgpio(GPIO_AD0p1); + } + else if ((priv->mask & 0x04) != 0) + { + lpc17_configgpio(GPIO_AD0p2); + } + else if ((priv->mask & 0x08) != 0) + { + lpc17_configgpio(GPIO_AD0p3); + } + else if ((priv->mask & 0x10) != 0) + { + lpc17_configgpio(GPIO_AD0p4); + } + else if ((priv->mask & 0x20) != 0) + { + lpc17_configgpio(GPIO_AD0p5); + } + else if ((priv->mask & 0x40) != 0) + { + lpc17_configgpio(GPIO_AD0p6); + } + else if ((priv->mask & 0x80) != 0) + { + lpc17_configgpio(GPIO_AD0p7); + } irqrestore(flags); } -/* Configure the ADC. This method is called the first time that the ADC - * device is opened. This will occur when the port is first opened. - * This setup includes configuring and attaching ADC interrupts. Interrupts - * are all disabled upon return. - */ +/**************************************************************************** + * Name: adc_setup + * + * Description: + * Configure the ADC. This method is called the first time that the ADC + * device is opened. This will occur when the port is first opened. + * This setup includes configuring and attaching ADC interrupts. Interrupts + * are all disabled upon return. + * + ****************************************************************************/ -static int adc_setup(FAR struct adc_dev_s *dev) +static int adc_setup(FAR struct adc_dev_s *dev) { - int i; FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv; + int i; + int ret = irq_attach(priv->irq, adc_interrupt); if (ret == OK) { for (i = 0; i < 8; i++) { - priv->buf[i]=0; - priv->count[i]=0; + priv->buf[i] = 0; + priv->count[i] = 0; } + up_enable_irq(priv->irq); } + return ret; } -/* Disable the ADC. This method is called when the ADC device is closed. - * This method reverses the operation the setup method. - */ +/**************************************************************************** + * Name: adc_shutdown + * + * Description: + * Disable the ADC. This method is called when the ADC device is closed. + * This method reverses the operation the setup method. + * + ****************************************************************************/ static void adc_shutdown(FAR struct adc_dev_s *dev) { FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv; + + /* Disable ADC interrupts, both at the level of the ADC device and at the + * level of the NVIC. + */ + + putreg32(0, LPC17_ADC_INTEN); up_disable_irq(priv->irq); + + /* Then detach the ADC interrupt handler. */ + irq_detach(priv->irq); } -/* Call to enable or disable RX interrupts */ +/**************************************************************************** + * Name: adc_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ static void adc_rxint(FAR struct adc_dev_s *dev, bool enable) { FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv; + if (enable) - putreg32(ADC_INTEN_GLOBAL, LPC17_ADC_INTEN); + { + putreg32(ADC_INTEN_GLOBAL, LPC17_ADC_INTEN); + } else - putreg32(0x00, LPC17_ADC_INTEN); + { + putreg32(0, LPC17_ADC_INTEN); + } } -/* All ioctl calls will be routed through this method */ +/**************************************************************************** + * Name: adc_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ -static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) +static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) { - dbg("Fix me:Not Implemented\n"); - return 0; + /* No ioctl commands supported */ + + return -ENOTTY; } +/**************************************************************************** + * Name: adc_interrupt + * + * Description: + * ADC interrupt handler + * + ****************************************************************************/ + static int adc_interrupt(int irq, void *context) { - uint32_t regval; FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.ad_priv; + uint32_t regval; unsigned char ch; int32_t value; - regval = getreg32(LPC17_ADC_GDR); - ch = (regval >> 24) & 0x07; - priv->buf[ch] += regval & 0xfff0; + regval = getreg32(LPC17_ADC_GDR); + ch = (regval >> 24) & 0x07; + priv->buf[ch] += regval & 0xfff0; + priv->count[ch]++; if (priv->count[ch] >= CONFIG_ADC0_AVERAGE) { - value = priv->buf[ch] / priv->count[ch]; - value <<= 15; + value = priv->buf[ch] / priv->count[ch]; + value <<= 15; adc_receive(&g_adcdev,ch,value); - priv->buf[ch] = 0; + priv->buf[ch] = 0; priv->count[ch] = 0; } + return OK; } @@ -274,5 +350,5 @@ FAR struct adc_dev_s *lpc17_adcinitialize(void) { return &g_adcdev; } -#endif +#endif /* CONFIG_LPC17_ADC */ diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c index 87f49ba33..4f3e5a512 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_dac.c @@ -62,6 +62,8 @@ #include "chip.h" #include "chip/lpc17_syscon.h" +#include "chip/lpc17_pinconfig.h" +#include "lpc17_gpio.h" #include "lpc17_dac.h" #ifdef CONFIG_LPC17_DAC -- cgit v1.2.3