summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-02 18:22:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-02 18:22:19 +0000
commit227420dd5ecb981092e5db9340c6c7f081afbcf3 (patch)
tree8e8f3e816f1c311702c10f0778a7bc06b880f437 /nuttx
parent5e8b86e69a7e259c60a97947702ceb441c07f709 (diff)
downloadpx4-nuttx-227420dd5ecb981092e5db9340c6c7f081afbcf3.tar.gz
px4-nuttx-227420dd5ecb981092e5db9340c6c7f081afbcf3.tar.bz2
px4-nuttx-227420dd5ecb981092e5db9340c6c7f081afbcf3.zip
Add support for STM32 Potentiometer via ADC3
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4252 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.c21
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_adc.c71
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt52
-rw-r--r--nuttx/configs/stm3240g-eval/nsh/appconfig4
-rwxr-xr-xnuttx/configs/stm3240g-eval/nsh/defconfig59
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_adc.c47
8 files changed, 216 insertions, 43 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 6301de0b1..a63f152ee 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2326,3 +2326,6 @@
This error would prevent pins > 15 from being used as interrupt sources.
* arch/arm/src/stm32/stm32_can.c: The CAN driver has been verified in
loopback mode on the STM3240G-EVAL board.
+ * configs/stm3240g-eval/src/up_adc.c: Complete coding of ADC support for the
+ potentiometer on board the STM3240G-EVAL.
+
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index 118814dd0..4239b5af9 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -111,7 +111,7 @@
#define GPIO_ADC3_IN4 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN6)
#define GPIO_ADC3_IN5 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN7)
#define GPIO_ADC3_IN6 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN8)
-#define GPIO_ADC3_IN7 (GPIO_ANALOG|GPIO_PORT |GPIO_PIN9)
+#define GPIO_ADC3_IN7 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN9)
#define GPIO_ADC3_IN9 (GPIO_ANALOG|GPIO_PORTF|GPIO_PIN3)
#define GPIO_ADC3_IN10 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN0)
#define GPIO_ADC3_IN11 (GPIO_ANALOG|GPIO_PORTC|GPIO_PIN1)
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c
index 451bd3cd6..b0ecd1ab3 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.c
@@ -960,7 +960,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
irqstate_t flags;
uint32_t regval;
int offset;
- int ret;
int i;
avdbg("intf: ADC%d\n", priv->intf);
@@ -1007,8 +1006,10 @@ static void adc_reset(FAR struct adc_dev_s *dev)
regval = adc_getreg(priv, STM32_ADC_CR1_OFFSET);
/* Set mode configuration (Independent mode) */
-
+
+#ifdef CONFIG_STM32_STM32F10XX
regval |= ADC_CR1_IND;
+#endif
/* Initialize the Analog watchdog enable */
@@ -1017,10 +1018,19 @@ static void adc_reset(FAR struct adc_dev_s *dev)
/* Enable interrupt flags */
regval |= ADC_CR1_ALLINTS;
-
adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval);
- /* ADC1 CR2 Configuration */
+ /* ADC CCR configuration */
+
+#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);
+#endif
+
+ /* ADC CR2 Configuration */
regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
@@ -1028,7 +1038,7 @@ static void adc_reset(FAR struct adc_dev_s *dev)
regval &= ~ADC_CR2_CONT;
- /*Set ALIGN (Right = 0) */
+ /* Set ALIGN (Right = 0) */
regval &= ~ADC_CR2_ALIGN;
adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
@@ -1239,7 +1249,6 @@ static int adc_interrupt(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
uint32_t adcsr;
- uint32_t regval;
int32_t value;
/* Identifies the interruption AWD or EOC */
diff --git a/nuttx/configs/stm3210e-eval/src/up_adc.c b/nuttx/configs/stm3210e-eval/src/up_adc.c
index 75ac6610a..f2a6cec84 100644
--- a/nuttx/configs/stm3210e-eval/src/up_adc.c
+++ b/nuttx/configs/stm3210e-eval/src/up_adc.c
@@ -2,7 +2,7 @@
* configs/stm3210e-eval/src/up_adc.c
* arch/arm/src/board/up_adc.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -73,10 +73,13 @@
#endif
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+#ifndef CONFIG_STM32_ADC1
+# warning "Channel information only available for ADC1"
+#endif
/* The number of ADC channels in the conversion list */
-#define ADC_NCHANNELS 1
+#define ADC1_NCHANNELS 1
/************************************************************************************
* Private Data
@@ -84,11 +87,13 @@
/* Identifying number of each ADC channel: Variable Resistor */
-static const uint8_t g_chanlist[ADC_NCHANNELS] = {14};
+#ifdef CONFIG_STM32_ADC1
+static const uint8_t g_chanlist[ADC1_NCHANNELS] = {14};
/* Configurations of pins used byte each ADC channels */
-static const uint32_t g_pinlist[ADC_NCHANNELS] = {GPIO_ADC1_IN14};
+static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN14};
+#endif
/************************************************************************************
* Private Functions
@@ -99,47 +104,61 @@ static const uint32_t g_pinlist[ADC_NCHANNELS] = {GPIO_ADC1_IN14};
************************************************************************************/
/************************************************************************************
- * Name: stm32_boardinitialize
+ * Name: adc_devinit
*
* Description:
- * All STM32 architectures must provide the following entry point. This entry point
- * is called early in the intitialization -- after all memory has been configured
- * and mapped but before any devices have been initialized.
+ * All STM32 architectures must provide the following interface to work with
+ * examples/adc.
*
************************************************************************************/
int adc_devinit(void)
{
+#ifdef CONFIG_STM32_ADC1
+ static bool initialized = false;
struct adc_dev_s *adc;
int ret;
int i;
- /* Configure the pins as analog inputs for the selected channels */
+ /* Check if we have already initialized */
- for(i = 0; i < ADC_NCHANNELS; i++)
+ if (!initialized)
{
- stm32_configgpio(g_pinlist[i]);
- }
+ /* Configure the pins as analog inputs for the selected channels */
- /* Call stm32_adcinitialize() to get an instance of the ADC interface */
+ for (i = 0; i < ADC1_NCHANNELS; i++)
+ {
+ stm32_configgpio(g_pinlist[i]);
+ }
- adc = stm32_adcinitialize(1, g_chanlist, ADC_NCHANNELS);
- if (adc == NULL)
- {
- adbg("ERROR: Failed to get ADC interface\n");
- return;
- }
+ /* Call stm32_adcinitialize() to get an instance of the ADC interface */
- /* Register the ADC driver at "/dev/adc0" */
+ adc = stm32_adcinitialize(1, g_chanlist, ADC1_NCHANNELS);
+ if (adc == NULL)
+ {
+ adbg("ERROR: Failed to get ADC interface\n");
+ return;
+ }
- ret = adc_register("/dev/adc0", adc);
- if (ret < 0)
- {
- adbg("adc_register failed: %d\n", ret);
+ /* 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 ret;
+ return OK;
+#else
+ return -ENOSYS;
+#endif
}
-#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
+#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
#endif /* CONFIG_ADC */ \ No newline at end of file
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index fc0d67beb..4ff229f4e 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -590,9 +590,49 @@ Where <subdir> is one of the following:
CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) : Target IP address 10.0.0.2
CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host IP address 10.0.0.1
- NOTE: This example assumes that a network is connected. During its
- initialization, it will try to negotiate the link speed. If you have
- no network connected when you reset the board, there will be a long
- delay (maybe 30 seconds?) before anything happens. That is the timeout
- before the networking finally gives up and decides that no network is
- available.
+ NOTES:
+ 1. This example assumes that a network is connected. During its
+ initialization, it will try to negotiate the link speed. If you have
+ no network connected when you reset the board, there will be a long
+ delay (maybe 30 seconds?) before anything happens. That is the timeout
+ before the networking finally gives up and decides that no network is
+ available.
+
+ 2. This example supports the ADC test (apps/examples/adc) but this must
+ be manually enabled by selecting:
+
+ CONFIG_ADC=y : Enable the generic ADC infrastructure
+ CONFIG_STM32_ADC3=y : Enable ADC3
+ CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to driver ADC3 sampling
+
+ See also apps/examples/README.txt
+
+ General debug for analog devices (ADC/DAC):
+
+ CONFIG_DEBUG_ANALOG
+
+ 3. This example supports the PWM test (apps/examples/pwm) but this must
+ be manually enabled by selecting:
+
+ CONFIG_PWM=y : Enable the generic PWM infrastructure
+ CONFIG_STM32_TIM4_PWM=y : Use TIM4 to generate PWM output
+
+ See also apps/examples/README.txt
+
+ Special PWM-only debug options:
+
+ CONFIG_DEBUG_PWM
+
+ 4. This example supports the CAN loopback test (apps/examples/can) but this
+ must be manually enabled by selecting:
+
+ CONFIG_CAN=y : Enable the generic CAN infrastructure
+ CONFIG_STM32_CAN1=y : Enable CAN1
+ CONFIG_CAN_LOOPBACK=y : Enable CAN loopback mode
+
+ See also apps/examples/README.txt
+
+ Special CAN-only debug options:
+
+ CONFIG_DEBUG_CAN
+ CONFIG_CAN_REGDEBUG
diff --git a/nuttx/configs/stm3240g-eval/nsh/appconfig b/nuttx/configs/stm3240g-eval/nsh/appconfig
index 6e9df6c9c..a2f3b5ebc 100644
--- a/nuttx/configs/stm3240g-eval/nsh/appconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/appconfig
@@ -50,6 +50,10 @@ CONFIGURED_APPS += netutils/webclient
CONFIGURED_APPS += netutils/tftpc
endif
+ifeq ($(CONFIG_ADC),y)
+CONFIGURED_APPS += examples/adc
+endif
+
ifeq ($(CONFIG_PWM),y)
CONFIGURED_APPS += examples/pwm
endif
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index c48619f2b..d85894ac4 100755
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -324,6 +324,15 @@ CONFIG_STM32_ETH_PTP=n
CONFIG_STM32_ETHMAC_REGDEBUG=n
#
+# ADC configuration
+#
+# Enable ADC driver support. The STM3240G-EVAL has a 10 Kohm potentiometer
+# RV1 connected to PF9 of STM32F407IGH6 on the board: TIM14_CH1/ SMC_CD/ADC3_IN7
+#
+CONFIG_ADC=n
+CONFIG_STM32_TIM1_ADC3=y
+
+#
# PWM configuration
#
# The STM3240G-Eval has no real on-board PWM devices, but the board can be configured to output
@@ -459,6 +468,9 @@ CONFIG_DEBUG_LCD=n
CONFIG_DEBUG_USB=n
CONFIG_DEBUG_NET=n
CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
CONFIG_HAVE_CXX=y
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
@@ -1204,6 +1216,53 @@ CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
+# Settings for examples/adc
+#
+# CONFIG_ADC - Enabled ADC support
+# CONFIG_NSH_BUILTIN_APPS - Build the ADC test as an NSH built-in function.
+# Default: Built as a standalone problem
+#
+# CONFIG_EXAMPLES_ADC_DEVPATH - The path to the ADC device. Default: /dev/adc0
+# CONFIG_EXAMPLES_ADC_NSAMPLES - If CONFIG_NSH_BUILTIN_APPS
+# is defined, then the number of samples is provided on the command line
+# and this value is ignored. Otherwise, this number of samples is
+# collected and the program terminates. Default: Samples are collected
+# indefinitely.
+# CONFIG_EXAMPLES_ADC_GROUPSIZE - The number of samples to read at once.
+# Default: 4
+
+#
+# Settings for examples/can
+#
+# CONFIG_CAN - Enables CAN support.
+# CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
+# mode for testing. The STM32 CAN driver does support loopback mode.
+# CONFIG_NSH_BUILTIN_APPS - Build the CAN test as an NSH built-in function.
+# Default: Built as a standalone problem
+#
+# CONFIG_EXAMPLES_CAN_DEVPATH - The path to the CAN device. Default: /dev/can0
+# CONFIG_EXAMPLES_CAN_NMSGS - If CONFIG_NSH_BUILTIN_APPS
+# is defined, then the number of loops is provided on the command line
+# and this value is ignored. Otherwise, this number of CAN message is
+# collected and the program terminates. Default: If built as an NSH
+# built-in, the default is 32. Otherwise messages are sent and received
+# indefinitely.
+
+#
+# Settings for examples/pwm
+#
+# CONFIG_PWM - Enables PWM support.
+# CONFIG_NSH_BUILTIN_APPS - Build the PWM test as an NSH built-in function.
+# Default: Not built! The example can only be used as an NSH built-in
+# application
+#
+# CONFIG_EXAMPLES_PWM_DEVPATH - The path to the PWM device. Default: /dev/pwm0
+# CONFIG_EXAMPLES_PWM_FREQUENCY - The initial PWM frequency. Default: 100 Hz
+# CONFIG_EXAMPLES_PWM_DUTYPCT - The initial PWM duty as a percentage. Default: 50%
+# CONFIG_EXAMPLES_PWM_DURATION - The initial PWM pulse train duration in sectonds.
+# as a percentage. Default: 5 seconds
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/stm3240g-eval/src/up_adc.c b/nuttx/configs/stm3240g-eval/src/up_adc.c
index c7db7a3c3..d376e4036 100644
--- a/nuttx/configs/stm3240g-eval/src/up_adc.c
+++ b/nuttx/configs/stm3240g-eval/src/up_adc.c
@@ -2,7 +2,7 @@
* configs/stm3240g-eval/src/up_adc.c
* arch/arm/src/board/up_adc.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -73,6 +73,30 @@
#endif
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+#ifndef CONFIG_STM32_ADC3
+# warning "Channel information only available for ADC3"
+#endif
+
+/* The number of ADC channels in the conversion list */
+
+#define ADC3_NCHANNELS 1
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+/* The STM3240G-EVAL has a 10 Kohm potentiometer RV1 connected to PF9 of
+ * STM32F407IGH6 on the board: TIM14_CH1/FSMC_CD/ADC3_IN7
+ */
+
+/* Identifying number of each ADC channel: Variable Resistor. */
+
+#ifdef CONFIG_STM32_ADC3
+static const uint8_t g_chanlist[ADC3_NCHANNELS] = {7};
+
+/* Configurations of pins used byte each ADC channels */
+
+static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN7};
+#endif
/************************************************************************************
* Private Functions
@@ -93,19 +117,31 @@
int adc_devinit(void)
{
+#ifdef CONFIG_STM32_ADC3
static bool initialized = false;
struct adc_dev_s *adc;
int ret;
+ int i;
/* Check if we have already initialized */
if (!initialized)
{
/* Configure the pins as analog inputs for the selected channels */
-#warning "Missing Logic"
+
+ for (i = 0; i < ADC3_NCHANNELS; i++)
+ {
+ stm32_configgpio(g_pinlist[i]);
+ }
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
-#warning "Missing Logic"
+
+ adc = stm32_adcinitialize(1, g_chanlist, ADC3_NCHANNELS);
+ if (adc == NULL)
+ {
+ adbg("ERROR: Failed to get ADC interface\n");
+ return -ENODEV;
+ }
/* Register the ADC driver at "/dev/adc0" */
@@ -122,7 +158,10 @@ int adc_devinit(void)
}
return OK;
+#else
+ return -ENOSYS;
+#endif
}
-#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
+#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
#endif /* CONFIG_ADC */ \ No newline at end of file