From 6ab3a2a10626f28693ff0b7db7c41e5b9e760131 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 3 Jan 2012 23:25:49 +0000 Subject: Fixes for STM32 ADC driver on the F4; LC17xx LED initial state git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4257 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/stm32_adc.c | 98 ++++++++++++++-------- .../olimex-lpc1766stk/src/lpc1766stk_internal.h | 7 +- nuttx/configs/stm3240g-eval/README.txt | 2 + nuttx/configs/stm3240g-eval/src/up_adc.c | 3 +- nuttx/configs/sure-pic32mx/README.txt | 11 ++- nuttx/drivers/can.c | 2 +- 6 files changed, 82 insertions(+), 41 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c index b0ecd1ab3..58ab5abeb 100644 --- a/nuttx/arch/arm/src/stm32/stm32_adc.c +++ b/nuttx/arch/arm/src/stm32/stm32_adc.c @@ -162,7 +162,7 @@ static void adc_timstart(FAR struct stm32_dev_s *priv, bool enable); static int adc_timinit(FAR struct stm32_dev_s *priv); #endif -#ifdef CONFIG_ADC_DMA +#ifdef CONFIG_STM32_STM32F40XX static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable); #endif @@ -226,7 +226,7 @@ static struct stm32_dev_s g_adcpriv2 = .intf = 2; .base = STM32_ADC2_BASE, #ifdef ADC2_HAVE_TIMER - .trigger = CONFIG_STM32_ADC2_TIMTRIG; + .trigger = CONFIG_STM32_ADC2_TIMTRIG, .tbase = ADC2_TIMER_BASE, .extsel = ADC2_EXTSEL_VALUE, .pclck = ADC2_TIMER_PCLK_FREQUENCY, @@ -253,10 +253,10 @@ static struct stm32_dev_s g_adcpriv3 = .irq = STM32_IRQ_ADC, .isr = adc123_interrupt, #endif - .intf = 3; + .intf = 3, .base = STM32_ADC3_BASE, #ifdef ADC3_HAVE_TIMER - .trigger = CONFIG_STM32_ADC3_TIMTRIG; + .trigger = CONFIG_STM32_ADC3_TIMTRIG, .tbase = ADC3_TIMER_BASE, .extsel = ADC3_EXTSEL_VALUE, .pclck = ADC3_TIMER_PCLK_FREQUENCY, @@ -485,27 +485,31 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) uint16_t ccenable; uint16_t ccer; uint16_t egr; - + + avdbg("Initializing timers extsel = %d\n", priv->extsel); + /* If the timer base address is zero, then this ADC was not configured to * use a timer. */ + regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); + +#ifdef CONFIG_STM32_STM32F10XX if (!priv->tbase) { /* Configure the ADC to use the selected timer and timer channel as the trigger * EXTTRIG: External Trigger Conversion mode for regular channels DISABLE */ - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); regval &= ~ADC_CR2_EXTTRIG; adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); return OK; } else { - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); regval |= ADC_CR2_EXTTRIG; } +#endif /* EXTSEL selection: These bits select the external event used to trigger * the start of conversion of a regular group. NOTE: @@ -803,14 +807,14 @@ static int adc_timinit(FAR struct stm32_dev_s *priv) * ****************************************************************************/ -#ifdef CONFIG_ADC_DMA +#ifdef CONFIG_STM32_STM32F40XX static void adc_startconv(struct stm32_dev_s *priv, bool enable) { uint32_t regval; avdbg("enable: %d\n", enable); - regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); + regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET); if (enable) { /* Start conversion of regular channles */ @@ -961,6 +965,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) uint32_t regval; int offset; int i; + int ret; avdbg("intf: ADC%d\n", priv->intf); flags = irqsave(); @@ -1014,21 +1019,24 @@ static void adc_reset(FAR struct adc_dev_s *dev) /* Initialize the Analog watchdog enable */ regval |= ADC_CR1_AWDEN; - + regval |= (priv->chanlist[0] << ADC_CR1_AWDCH_SHIFT); + /* Enable interrupt flags */ regval |= ADC_CR1_ALLINTS; - adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval); + +#ifdef CONFIG_STM32_STM32F40XX - /* ADC CCR configuration */ + /* Enable or disable Overrun interrupt */ + + regval &= ~ADC_CR1_OVRIE; + + /* Set the resolution of the conversion */ -#ifdef CONFIG_STM32_STM32F40XX - regval |= adc_getreg(priv, STM32_ADC_CCR_OFFSET); - regval &= ~(ADC_CCR_MULTI_MASK | ADC_CCR_DELAY_MASK | ADC_CCR_DDS | ADC_CCR_DMA_MASK | - ADC_CCR_ADCPRE_MASK | ADC_CCR_VBATE | ADC_CCR_TSVREFE); - regval |= (ADC_CCR_MULTI_NONE | ADC_CCR_DMA_DISABLED | ADC_CCR_ADCPRE_DIV2); - adc_putreg(priv, STM32_ADC_CCR_OFFSET, regval); + regval |= ACD_CR1_RES_12BIT; #endif + + adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval); /* ADC CR2 Configuration */ @@ -1041,22 +1049,15 @@ static void adc_reset(FAR struct adc_dev_s *dev) /* Set ALIGN (Right = 0) */ regval &= ~ADC_CR2_ALIGN; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); - -#if 0 -#ifdef CONFIG_STM32_STM32F10XX - /* ADC reset calibaration register */ - regval |= ADC_CR2_RSTCAL; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); - usleep(5); - - /* A/D Calibration */ - - regval |= ADC_CR2_CAL; - adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); -#endif + +#ifdef CONFIG_STM32_STM32F40XX + /* External trigger enable for regular channels */ + + regval |= ACD_CR2_EXTEN_RISING; #endif + adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval); + /* Configuration of the channel conversions */ regval = adc_getreg(priv, STM32_ADC_SQR3_OFFSET) & ADC_SQR3_RESERVED; @@ -1078,6 +1079,16 @@ static void adc_reset(FAR struct adc_dev_s *dev) { regval |= (uint32_t)priv->chanlist[i] << offset; } + + /* ADC CCR configuration */ + +#ifdef CONFIG_STM32_STM32F40XX + regval = getreg32(STM32_ADC_CCR); + regval &= ~(ADC_CCR_MULTI_MASK | ADC_CCR_DELAY_MASK | ADC_CCR_DDS | ADC_CCR_DMA_MASK | + ADC_CCR_ADCPRE_MASK | ADC_CCR_VBATE | ADC_CCR_TSVREFE); + regval |= (ADC_CCR_MULTI_NONE | ADC_CCR_DMA_DISABLED | ADC_CCR_ADCPRE_DIV2); + putreg32(regval, STM32_ADC_CCR); +#endif /* Set the number of conversions */ @@ -1101,12 +1112,16 @@ static void adc_reset(FAR struct adc_dev_s *dev) adbg("Error initializing the timers\n"); } #else +#ifdef CONFIG_STM32_STM32F10XX /* Set ADON (Again) to start the conversion. Only if Timers are not * configured as triggers */ adc_enable(priv, true); -#endif +#else + adc_startconv(priv, true); +#endif /* CONFIG_STM32_STM32F10XX */ +#endif /* ADC_HAVE_TIMER */ irqrestore(flags); @@ -1118,6 +1133,10 @@ static void adc_reset(FAR struct adc_dev_s *dev) adc_getreg(priv, STM32_ADC_SQR1_OFFSET), adc_getreg(priv, STM32_ADC_SQR2_OFFSET), adc_getreg(priv, STM32_ADC_SQR3_OFFSET)); +#ifdef CONFIG_STM32_STM32F40XX + avdbg("CCR: 0x%08x\n", + getreg32(STM32_ADC_CCR)); +#endif } /**************************************************************************** @@ -1228,7 +1247,7 @@ static void adc_rxint(FAR struct adc_dev_s *dev, bool enable) * ****************************************************************************/ -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) { return -ENOTTY; } @@ -1251,14 +1270,21 @@ static int adc_interrupt(FAR struct adc_dev_s *dev) uint32_t adcsr; int32_t value; - /* Identifies the interruption AWD or EOC */ + /* Identifies the interruption AWD, OVR or EOC */ adcsr = adc_getreg(priv, STM32_ADC_SR_OFFSET); if ((adcsr & ADC_SR_AWD) != 0) { - adbg("WARNING: Analog Watchdog, Value converted out of range!\n"); + alldbg("WARNING: Analog Watchdog, Value converted out of range!\n"); } +#ifdef CONFIG_STM32_STM32F40XX + if ((adcsr & ADC_SR_OVR) != 0) + { + alldbg("WARNING: Overrun has ocurred!\n"); + } +#endif + /* EOC: End of conversion */ if ((adcsr & ADC_SR_EOC) != 0) diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h index d1c0ebe80..31159de52 100755 --- a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h +++ b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h @@ -127,10 +127,13 @@ * -------------------------------- ---- -------------- * P1[25]/MC1A/MAT1[1] 39 LED1 * P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ + * + * LEDs are connected to +3.3V through a diode on one side and must be pulled + * low (through a resistor) on the LPC17xx side in order to illuminuate them. */ -#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN25) -#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4) +#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN25) +#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN4) /* Buttons GPIO PIN SIGNAL NAME * -------------------------------- ---- -------------- diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 4ff229f4e..cdf3d82ae 100755 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -603,7 +603,9 @@ Where is one of the following: CONFIG_ADC=y : Enable the generic ADC infrastructure CONFIG_STM32_ADC3=y : Enable ADC3 + CONFIG_STM32_TIM1=y : Enable Timer 1 CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to driver ADC3 sampling + CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100 : Select a sampling frequency See also apps/examples/README.txt diff --git a/nuttx/configs/stm3240g-eval/src/up_adc.c b/nuttx/configs/stm3240g-eval/src/up_adc.c index d376e4036..e42651761 100644 --- a/nuttx/configs/stm3240g-eval/src/up_adc.c +++ b/nuttx/configs/stm3240g-eval/src/up_adc.c @@ -40,6 +40,7 @@ #include +#include #include #include @@ -136,7 +137,7 @@ int adc_devinit(void) /* Call stm32_adcinitialize() to get an instance of the ADC interface */ - adc = stm32_adcinitialize(1, g_chanlist, ADC3_NCHANNELS); + adc = stm32_adcinitialize(3, g_chanlist, ADC3_NCHANNELS); if (adc == NULL) { adbg("ERROR: Failed to get ADC interface\n"); diff --git a/nuttx/configs/sure-pic32mx/README.txt b/nuttx/configs/sure-pic32mx/README.txt index b7d2ae236..365ac8277 100644 --- a/nuttx/configs/sure-pic32mx/README.txt +++ b/nuttx/configs/sure-pic32mx/README.txt @@ -329,7 +329,6 @@ PIC32MX Configuration Options CONFIG_PIC32MX_USBDEV - USB device CONFIG_PIC32MX_USBHOST - USB host - PIC32MX Configuration Settings DEVCFG0: CONFIG_PIC32MX_DEBUGGER - Background Debugger Enable. Default 3 (disabled). The @@ -431,3 +430,13 @@ Where is one of the following: ostest: This configuration directory, performs a simple OS test using apps/examples/ostest. + + nsh: + Configures the NuttShell (nsh) located at apps/examples/nsh. The + Configuration enables only the serial NSH interface. + + The examples/usbterm program can be included as an NSH built-in + function by defined the following in your .config file: + + CONFIG_USBEV=y : Enable basic USB device support + CONFIG_PIC32MX_USBDEV=y : Enable PIC32 USB device support diff --git a/nuttx/drivers/can.c b/nuttx/drivers/can.c index 8c9f8ea13..41c3548ea 100644 --- a/nuttx/drivers/can.c +++ b/nuttx/drivers/can.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/can.c * - * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without -- cgit v1.2.3