summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-15 13:33:15 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-15 13:33:15 +0000
commit27c16edcc1befe9afeb4a1996c3b22bc9acd8380 (patch)
tree2c95c90c6c7c7a4e31f44d11a9d18df3c1bd9538
parentb7c5ab3982dc862b8e72d45a3121e43b2ba325e6 (diff)
downloadpx4-nuttx-27c16edcc1befe9afeb4a1996c3b22bc9acd8380.tar.gz
px4-nuttx-27c16edcc1befe9afeb4a1996c3b22bc9acd8380.tar.bz2
px4-nuttx-27c16edcc1befe9afeb4a1996c3b22bc9acd8380.zip
Update to STM32 DAC and ADC drivers
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4185 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.c43
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.h38
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dac.c33
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_dac.h35
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt3
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt3
6 files changed, 126 insertions, 29 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c
index f4363ba6a..88f117b6e 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.c
@@ -510,23 +510,23 @@ static void adc_reset(FAR struct adc_dev_s *dev)
/* Configuration of the channels conversions */
regval = adc_getreg(priv, STM32_ADC_SQR3_OFFSET) & ~ADC_SQR3_RESERVED;
- for (i = 1, offset = 0; i <= priv->nchannels && i <= 6; i++, offset += 5)
+ for (i = 0, offset = 0; i < priv->nchannels && i < 6; i++, offset += 5)
{
- regval |= (uint32_t)priv->chanlist[i-1] << offset;
+ regval |= (uint32_t)priv->chanlist[i] << offset;
}
adc_putreg(priv, STM32_ADC_SQR3_OFFSET, regval);
regval = adc_getreg(priv, STM32_ADC_SQR2_OFFSET) & ~ADC_SQR2_RESERVED;
- for (i = 7, offset = 0; i <= priv->nchannels && i <= 12; i++, offset += 5)
+ for (i = 6, offset = 0; i < priv->nchannels && i < 12; i++, offset += 5)
{
- regval |= (uint32_t)priv->chanlist[i-1] << offset;
+ regval |= (uint32_t)priv->chanlist[i] << offset;
}
adc_putreg(priv, STM32_ADC_SQR2_OFFSET, regval);
regval = adc_getreg(priv, STM32_ADC_SQR1_OFFSET) & ~(ADC_SQR1_RESERVED|ADC_SQR1_L_MASK);
- for (i = 13, offset = 0; i <= priv->nchannels && i <= 16; i++, offset += 5)
+ for (i = 12, offset = 0; i < priv->nchannels && i < 16; i++, offset += 5)
{
- regval |= (uint32_t)priv->chanlist[i-1] << offset;
+ regval |= (uint32_t)priv->chanlist[i] << offset;
}
adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
@@ -842,20 +842,21 @@ static int adc123_interrupt(int irq, void *context)
* Name: stm32_adcinitialize
*
* Description:
- * Initialize the ADC. The logic is, save nchannels : # of channels
- * (conversions) in ADC_SQR1_L
- * Then, take the chanlist array and store it in the SQR Regs,
- * chanlist[0] -> ADC_SQR3_SQ1
- * chanlist[1] -> ADC_SQR3_SQ2
- * chanlist[2] -> ADC_SQR3_SQ3
- * chanlist[3] -> ADC_SQR3_SQ4
- * chanlist[4] -> ADC_SQR3_SQ5
- * chanlist[5] -> ADC_SQR3_SQ6
- * ...
- * chanlist[15]-> ADC_SQR1_SQ16
- *
- * up to
- * chanlist[nchannels]
+ * Initialize the ADC.
+ *
+ * The logic is, save nchannels : # of channels (conversions) in ADC_SQR1_L
+ * Then, take the chanlist array and store it in the SQR Regs,
+ * chanlist[0] -> ADC_SQR3_SQ1
+ * chanlist[1] -> ADC_SQR3_SQ2
+ * chanlist[2] -> ADC_SQR3_SQ3
+ * chanlist[3] -> ADC_SQR3_SQ4
+ * chanlist[4] -> ADC_SQR3_SQ5
+ * chanlist[5] -> ADC_SQR3_SQ6
+ * ...
+ * chanlist[15]-> ADC_SQR1_SQ16
+ *
+ * up to
+ * chanlist[nchannels]
*
* Input Parameters:
* intf - Could be {1,2,3} for ADC1, ADC2, or ADC3
@@ -863,7 +864,7 @@ static int adc123_interrupt(int irq, void *context)
* nchannels - Number of channels
*
* Returned Value:
- * Valid can device structure reference on succcess; a NULL on failure
+ * Valid ADC device structure reference on succcess; a NULL on failure
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h
index 6089217fe..508813bd1 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.h
@@ -47,5 +47,43 @@
#include <nuttx/analog/adc.h>
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: stm32_adcinitialize
+ *
+ * Description:
+ * Initialize the ADC.
+ *
+ * Input Parameters:
+ * intf - Could be {1,2,3} for ADC1, ADC2, or ADC3
+ * chanlist - The list of channels
+ * nchannels - Number of channels
+ *
+ * Returned Value:
+ * Valid can device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+struct adc_dev_s;
+EXTERN struct adc_dev_s *stm32_adcinitialize(int intf, uint8_t *chanlist,
+ int nchannels);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
#endif /* __ARCH_ARM_SRC_STM32_STM32_ADC_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_dac.c b/nuttx/arch/arm/src/stm32/stm32_dac.c
index 79a8178da..a7d46707c 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dac.c
+++ b/nuttx/arch/arm/src/stm32/stm32_dac.c
@@ -58,18 +58,33 @@
#include "stm32_internal.h"
#include "stm32_dac.h"
-#if defined(CONFIG_DAC) && defined(CONFIG_STM32_DAC)
+#ifdef CONFIG_DAC
/****************************************************************************
* Private Types
****************************************************************************/
+/* Configuration ************************************************************/
+/* Up to 2 DAC interfaces are supported */
+
+#if STM32_NDAC < 2
+# undef CONFIG_STM32_DAC2
+#endif
+
+#if STM32_NDAC < 1
+# undef CONFIG_STM32_DAC1
+#endif
+
+#if defined(CONFIG_STM32_DAC1) || defined(CONFIG_STM32_DAC2)
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/* Interrupt handler */
+#ifdef CONFIG_STM32_STM32F40XX
static int dac_interrupt(int irq, void *context);
+#endif
/* DAC methods */
@@ -108,7 +123,8 @@ static struct dac_dev_s g_dacdev =
* Name: dac_interrupt
*
* Description:
- * DAC interrupt handler.
+ * DAC interrupt handler. The STM32 F4 family supports a only a DAC
+ * underrun interrupt.
*
* Input Parameters:
*
@@ -116,10 +132,12 @@ static struct dac_dev_s g_dacdev =
*
****************************************************************************/
+#ifdef CONFIG_STM32_STM32F40XX
static int dac_interrupt(int irq, void *context)
{
return OK;
}
+#endif
/****************************************************************************
* Name: dac_reset
@@ -242,20 +260,23 @@ static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg)
****************************************************************************/
/****************************************************************************
- * Name: up_dacinitialize
+ * Name: stm32_dacinitialize
*
* Description:
* Initialize the DAC
*
+ * Input Parameters:
+ * intf - The DAC interface number.
+ *
* Returned Value:
* Valid dac device structure reference on succcess; a NULL on failure
*
****************************************************************************/
-FAR struct dac_dev_s *up_dacinitialize(int channel)
+FAR struct dac_dev_s *stm32_dacinitialize(int intf)
{
return &g_dacdev;
}
-#endif /* CONFIG_DAC && CONFIG_STM32_DAC */
-
+#endif /* CONFIG_STM32_DAC1 || CONFIG_STM32_DAC2 */
+#endif /* CONFIG_DAC */
diff --git a/nuttx/arch/arm/src/stm32/stm32_dac.h b/nuttx/arch/arm/src/stm32/stm32_dac.h
index 64942b05e..41d681ee7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_dac.h
+++ b/nuttx/arch/arm/src/stm32/stm32_dac.h
@@ -47,5 +47,40 @@
#include <nuttx/analog/dac.h>
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: stm32_dacinitialize
+ *
+ * Description:
+ * Initialize the DAC
+ *
+ * Input Parameters:
+ * intf - The DAC interface number.
+ *
+ * Returned Value:
+ * Valid dac device structure reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+struct dac_dev_s;
+EXTERN FAR struct dac_dev_s *stm32_dacinitialize(int intf);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
#endif /* __ARCH_ARM_SRC_STM32_STM32_DAC_H */
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index 2e57a828c..25496db2d 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -461,7 +461,8 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_STM32_CAN
CONFIG_STM32_BKP
CONFIG_STM32_PWR
- CONFIG_STM32_DAC
+ CONFIG_STM32_DAC1
+ CONFIG_STM32_DAC2
CONFIG_STM32_USB
APB2
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index 3368ef1fb..78b384c31 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -334,7 +334,8 @@ STM3240G-EVAL-specific Configuration Options
CONFIG_STM32_I2C3
CONFIG_STM32_CAN1
CONFIG_STM32_CAN2
- CONFIG_STM32_DAC
+ CONFIG_STM32_DAC1
+ CONFIG_STM32_DAC2
CONFIG_STM32_PWR -- Required for RTC
APB2