summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-10-24 16:50:51 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-10-24 16:50:51 -0600
commit3f772ef5b5ab5a26802355ecd024cb824d10bfab (patch)
tree7800b5b72ed38e47b4fa8a5ec4223d5aeb9e849b
parentecbcdd677d9d8d8679b396e66b02f2c1f5e9f1bd (diff)
downloadpx4-nuttx-3f772ef5b5ab5a26802355ecd024cb824d10bfab.tar.gz
px4-nuttx-3f772ef5b5ab5a26802355ecd024cb824d10bfab.tar.bz2
px4-nuttx-3f772ef5b5ab5a26802355ecd024cb824d10bfab.zip
SAMA5 ADC+TC: Early debug fixes + lots of new debug instrumentation
-rw-r--r--nuttx/arch/arm/src/sama5/sam_adc.c74
-rw-r--r--nuttx/arch/arm/src/sama5/sam_dmac.c2
-rw-r--r--nuttx/arch/arm/src/sama5/sam_tc.c66
-rw-r--r--nuttx/arch/arm/src/sama5/sam_tc.h2
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_adc.c118
5 files changed, 239 insertions, 23 deletions
diff --git a/nuttx/arch/arm/src/sama5/sam_adc.c b/nuttx/arch/arm/src/sama5/sam_adc.c
index 3530b2e12..dc458362b 100644
--- a/nuttx/arch/arm/src/sama5/sam_adc.c
+++ b/nuttx/arch/arm/src/sama5/sam_adc.c
@@ -85,7 +85,7 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* Count the number of channels in use */
+/* Count the number of channels in use */
#define SAMA5_CHAN0_INUSE 0
#define SAMA5_CHAN1_INUSE 0
@@ -218,7 +218,7 @@
* is a gain setting for each enabled channel.
*
* Valid gain settings are {0, 1, 2, 3} which may be interpreted as
- * either {1, 1, 2, 4} if the DIFFx bit in COR register is zero or as
+ * either {1, 1, 2, 4} if the DIFFx bit in COR register is zero or as
* {0.5, 1, 2, 2} if the DIFFx bit is set.
*/
@@ -573,7 +573,7 @@ static bool sam_adc_checkreg(struct sam_adc_s *priv, bool wr,
*
* Input Parameters
* arg - The ADC private data structure cast to (void *)
- *
+ *
* Returned Value:
* None
*
@@ -588,6 +588,7 @@ static void sam_adc_dmadone(void *arg)
int chan;
int i;
+ avdbg("ready=%d enabled=%d\n", priv->enabled, priv->ready);
ASSERT(priv != NULL && !priv->ready);
/* If the DMA is disabled, just ignore the data */
@@ -642,6 +643,8 @@ static void sam_adc_dmacallback(DMA_HANDLE handle, void *arg, int result)
struct sam_adc_s *priv = (struct sam_adc_s *)arg;
int ret;
+ allvdbg("ready=%d enabled=%d\n", priv->enabled, priv->ready);
+
/* Check of the bottom half is keeping up with us */
if (priv->ready && priv->enabled)
@@ -698,6 +701,7 @@ static int sam_adc_dmasetup(FAR struct sam_adc_s *priv, FAR uint8_t *buffer,
uint32_t paddr;
uint32_t maddr;
+ avdbg("buffer=%p buflen=%d\n", buffer, (int)buflen);
DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0);
DEBUGASSERT(((uint32_t)buffer & 3) == 0);
@@ -728,13 +732,13 @@ static int sam_adc_dmasetup(FAR struct sam_adc_s *priv, FAR uint8_t *buffer,
* Description:
* This function executes on the worker thread. It is scheduled by
* sam_adc_interrupt whenever any enabled end-of-conversion event occurs.
- * All EOC interrupts are disabled when this function runs.
+ * All EOC interrupts are disabled when this function runs.
* sam_adc_endconversion will re-enable EOC interrupts when it completes
* processing all pending EOC events.
*
* Input Parameters
* arg - The ADC private data structure cast to (void *)
- *
+ *
* Returned Value:
* None
*
@@ -748,6 +752,7 @@ static void sam_adc_endconversion(void *arg)
int chan;
ASSERT(priv != NULL);
+ avdbg("pending=%08x\n", priv->pending);
/* Get the set of unmasked, pending ADC interrupts */
@@ -877,13 +882,20 @@ static void sam_adc_reset(struct adc_dev_s *dev)
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
uint32_t regval;
+ avdbg("Resetting..\n");
+
/* NOTE: We can't really reset the ADC hardware without losing the
* touchscreen configuration.
*/
- /* Stop any DMA */
+ /* Stop any ongoing DMA */
- sam_dmastop(priv->dma);
+#ifdef CONFIG_SAMA5_ADC_DMA
+ if (priv->dma)
+ {
+ sam_dmastop(priv->dma);
+ }
+#endif
/* Stop an release any timer */
@@ -940,6 +952,8 @@ static int sam_adc_setup(struct adc_dev_s *dev)
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
uint32_t regval;
+ avdbg("Setup\n");
+
/* Enable channel number tag. This bit will force the channel number (CHNB)
* to be included in the LDCR register content.
*/
@@ -1006,6 +1020,8 @@ static void sam_adc_shutdown(struct adc_dev_s *dev)
{
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
+ avdbg("Shutdown\n");
+
/* Disable ADC interrupts, both at the level of the ADC device and at the
* level of the AIC.
*/
@@ -1030,6 +1046,8 @@ static void sam_adc_rxint(struct adc_dev_s *dev, bool enable)
{
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
+ avdbg("enable=%d\n", enable);
+
#ifdef CONFIG_SAMA5_ADC_DMA
/* We don't stop the DMA when RX is disabled, we just stop the data transfer */
@@ -1063,6 +1081,8 @@ static void sam_adc_rxint(struct adc_dev_s *dev, bool enable)
static int sam_adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg)
{
+ avdbg("cmd=%d arg=%ld\n", cmd, arg);
+
/* No ioctl commands supported:
*
* REVISIT: Need to implement a ioctl to support software triggering
@@ -1096,6 +1116,8 @@ static int sam_adc_settimer(struct sam_adc_s *priv, uint32_t frequency,
uint32_t mode;
int ret;
+ avdbg("frequency=%ld channel=%d\n", (long)frequency, channel);
+
/* Configure TC for a 1Hz frequency and trigger on RC compare. */
ret = sam_tc_divisor(frequency, &div, &tcclks);
@@ -1123,7 +1145,7 @@ static int sam_adc_settimer(struct sam_adc_s *priv, uint32_t frequency,
adbg("ERROR: Failed to allocate channel %d mode %08x\n", channel, mode);
return -EINVAL;
}
-
+
/* Set up TC_RA and TC_RC */
sam_tc_setregister(priv->tc, TC_REGA, div / 2);
@@ -1149,6 +1171,8 @@ static void sam_adc_freetimer(struct sam_adc_s *priv)
{
/* Is a timer allocated? */
+ avdbg("tc=%p\n", priv->tc);
+
if (priv->tc)
{
/* Yes.. stop it and free it */
@@ -1174,6 +1198,8 @@ static int sam_adc_trigger(struct sam_adc_s *priv)
int ret = OK;
#if defined(CONFIG_SAMA5_ADC_SWTRIG)
+ avdbg("Setup software trigger\n");
+
/* Configure the software trigger */
regval = sam_adc_getreg(priv, SAM_ADC_MR);
@@ -1188,6 +1214,8 @@ static int sam_adc_trigger(struct sam_adc_s *priv)
sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
#elif defined(CONFIG_SAMA5_ADC_ADTRG)
+ avdbg("Setup ADTRG trigger\n");
+
/* Configure the trigger via the external ADTRG signal */
regval = sam_adc_getreg(priv, SAM_ADC_MR);
@@ -1213,6 +1241,8 @@ static int sam_adc_trigger(struct sam_adc_s *priv)
sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
#elif defined(CONFIG_SAMA5_ADC_TIOATRIG)
+ avdbg("Setup timer/counter trigger\n");
+
/* Start the timer */
#if defined(CONFIG_SAMA5_ADC_TIOA0TRIG)
@@ -1291,6 +1321,8 @@ static void sam_adc_autocalibrate(struct sam_adc_s *priv)
#ifdef CONFIG_SAMA5_ADC_AUTOCALIB
uint32_t regval;
+ avdbg("Entry\n");
+
/* Launch an automatic calibration of the ADC cell on next sequence */
regval = sam_adc_getreg(priv, SAM_ADC_CR);
@@ -1316,6 +1348,8 @@ static void sam_adc_offset(struct sam_adc_s *priv)
{
uint32_t regval = 0;
+ avdbg("Entry\n");
+
#ifdef CONFIG_SAMA5_ADC_ANARCH
/* Set the offset for each enabled channel. This centers the analog signal
* on Vrefin/2 before the gain scaling. The Offset applied is: (G-1)Vrefin/2
@@ -1431,6 +1465,8 @@ static void sam_adc_gain(struct sam_adc_s *priv)
#ifdef CONFIG_SAMA5_ADC_ANARCH
uint32_t regval;
+ avdbg("Entry\n");
+
/* Set the gain for each enabled channel */
regval = 0;
@@ -1475,6 +1511,8 @@ static void sam_adc_gain(struct sam_adc_s *priv)
sam_adc_putreg(priv, SAM_ADC_CGR, regval);
#else
+ avdbg("Gain=%d\n", CONFIG_SAMA5_ADC_GAIN);
+
/* Set GAIN0 only. GAIN0 will be used for all channels. */
sam_adc_putreg(priv, SAM_ADC_CGR, ADC_CGR_GAIN0(CONFIG_SAMA5_ADC_GAIN));
@@ -1494,9 +1532,11 @@ static void sam_adc_analogchange(struct sam_adc_s *priv)
{
uint32_t regval;
+ avdbg("Entry\n");
+
/* Enable/disable the analog change feature */
- regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
#ifdef CONFIG_SAMA5_ADC_ANARCH
/* Disable analog change: No analog change on channel switching: DIFF0,
@@ -1526,6 +1566,8 @@ static void sam_adc_analogchange(struct sam_adc_s *priv)
#ifdef CONFIG_SAMA5_ADC_SEQUENCER
static void sam_adc_setseqr(int chan, uint32_t *seqr1, uint32_t *seqr2, int seq)
{
+ avdbg("seqr1=%p seqr2=%p seg=%d\n");
+
if (seq > 8)
{
*seqr2 |= ADC_SEQR2_USCH(seq, chan);
@@ -1545,6 +1587,8 @@ static void sam_adc_sequencer(struct sam_adc_s *priv)
uint32_t seqr2;
int seq;
+ avdbg("Setup sequencer\n");
+
/* Set user configured channel sequence */
seqr1 = 0;
@@ -1632,6 +1676,8 @@ static void sam_adc_sequencer(struct sam_adc_s *priv)
#else
uint32_t regval;
+ avdbg("Disable sequencer\n");
+
/* Disable the sequencer */
regval = sam_adc_getreg(priv, SAM_ADC_MR);
@@ -1653,6 +1699,8 @@ static void sam_adc_channels(struct sam_adc_s *priv)
{
uint32_t regval;
+ avdbg("Entry\n");
+
/* Disable the sequencer */
regval = sam_adc_getreg(priv, SAM_ADC_MR);
@@ -1742,6 +1790,8 @@ struct adc_dev_s *sam_adc_initialize(void)
if (!priv->initialized)
{
+ avdbg("Initializing...\n");
+
/* Disable ADC peripheral clock */
sam_adc_disableclk();
@@ -1792,7 +1842,7 @@ struct adc_dev_s *sam_adc_initialize(void)
/* Initialize the public ADC device data structure */
g_adcdev.ad_ops = &g_adcops;
- g_adcdev.ad_priv = &priv;
+ g_adcdev.ad_priv = priv;
/* Initialize the private ADC device data structure */
@@ -1873,6 +1923,7 @@ struct adc_dev_s *sam_adc_initialize(void)
/* Return a pointer to the device structure */
+ avdbg("Returning %p\n", &g_adcdev);
return &g_adcdev;
}
@@ -1888,6 +1939,8 @@ void sam_adc_lock(FAR struct sam_adc_s *priv)
{
int ret;
+ avdbg("Locking\n");
+
do
{
ret = sem_wait(&priv->exclsem);
@@ -1911,6 +1964,7 @@ void sam_adc_lock(FAR struct sam_adc_s *priv)
void sam_adc_unlock(FAR struct sam_adc_s *priv)
{
+ avdbg("Unlocking\n");
sem_post(&priv->exclsem);
}
diff --git a/nuttx/arch/arm/src/sama5/sam_dmac.c b/nuttx/arch/arm/src/sama5/sam_dmac.c
index cfff7f1c2..1bbdc2ee0 100644
--- a/nuttx/arch/arm/src/sama5/sam_dmac.c
+++ b/nuttx/arch/arm/src/sama5/sam_dmac.c
@@ -657,7 +657,7 @@ static uint8_t sam_channel(uint8_t pid, const struct sam_pidmap_s *table,
}
}
- fdbg("No channel found for pid %d\n", pid);
+ dmadbg("No channel found for pid %d\n", pid);
DEBUGPANIC();
return 0x3f;
}
diff --git a/nuttx/arch/arm/src/sama5/sam_tc.c b/nuttx/arch/arm/src/sama5/sam_tc.c
index b3fdbbbe2..46b728c72 100644
--- a/nuttx/arch/arm/src/sama5/sam_tc.c
+++ b/nuttx/arch/arm/src/sama5/sam_tc.c
@@ -56,6 +56,7 @@
#include <semaphore.h>
#include <assert.h>
#include <errno.h>
+#include <debug.h>
#include <arch/board/board.h>
@@ -90,6 +91,21 @@
# error Cannot realize TC input frequency
#endif
+/* Timer debug is enabled if any timer client is enabled */
+
+#undef DEBUG_TC
+#if defined(CONFIG_SAMA5_ADC)
+# define DEBUG_TC 1
+#endif
+
+#ifdef DEBUG_TC
+# define tcdbg dbg
+# define tcvdbg vdbg
+#else
+# define wddbg(x...)
+# define wdvdbg(x...)
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -110,6 +126,7 @@ struct sam_tcconfig_s
uintptr_t base; /* TC register base address */
uint8_t pid; /* Peripheral ID */
uint8_t chfirst; /* First channel number */
+ uint8_t tc; /* Timer/counter number */
/* Channels */
@@ -191,6 +208,7 @@ static const struct sam_tcconfig_s g_tc012config =
.base = SAM_TC012_VBASE,
.pid = SAM_PID_TC0,
.chfirst = 0,
+ .tc = 0,
.channel =
{
{
@@ -257,6 +275,7 @@ static const struct sam_tcconfig_s g_tc345config =
.base = SAM_TC345_VBASE,
.pid = SAM_PID_TC1,
.chfirst = 3,
+ .tc = 1,
.channel =
{
{
@@ -586,7 +605,7 @@ static inline struct sam_chan_s *sam_tc_initialize(int channel)
/* Select the timer/counter and get the index associated with the
* channel.
*/
-
+
#ifdef CONFIG_SAMA5_TC0
if (channel >= 0 && channel < 3)
{
@@ -627,6 +646,8 @@ static inline struct sam_chan_s *sam_tc_initialize(int channel)
for (i = 0, ch = tcconfig->chfirst; i < SAM_TC_NCHANNELS; i++)
{
+ tcdbg("Initializing TC%d\n", tcconfig->tc);
+
/* Initialize the channel data structure */
chan = &tc->channel[i];
@@ -688,11 +709,16 @@ static inline struct sam_chan_s *sam_tc_initialize(int channel)
{
/* No.. return a failure */
+ tcdbg("Channel %d is in-used\n", channel);
sam_givesem(tc);
return NULL;
}
- /* OK.. return the channel with the semaphore locked */
+ /* Mark the channel "inuse" */
+
+ chan->inuse = true;
+
+ /* And return the channel with the semaphore locked */
return chan;
}
@@ -716,7 +742,7 @@ static inline struct sam_chan_s *sam_tc_initialize(int channel)
* On success, a non-NULL handle value is returned. This handle may be
* used with subsequent timer/counter interfaces to manage the timer. A
* NULL handle value is returned on a failure.
- *
+ *
****************************************************************************/
TC_HANDLE sam_tc_allocate(int channel, int mode)
@@ -727,6 +753,8 @@ TC_HANDLE sam_tc_allocate(int channel, int mode)
* access to the requested channel.
*/
+ tcvdbg("channel=%d mode=%08x\n", channel, mode);
+
chan = sam_tc_initialize(channel);
if (chan)
{
@@ -749,6 +777,7 @@ TC_HANDLE sam_tc_allocate(int channel, int mode)
/* Return an opaque reference to the channel */
+ tcvdbg("Returning %p\n", chan);
return (TC_HANDLE)chan;
}
@@ -763,12 +792,14 @@ TC_HANDLE sam_tc_allocate(int channel, int mode)
*
* Returned Value:
* None
- *
+ *
****************************************************************************/
void sam_tc_free(TC_HANDLE handle)
{
struct sam_chan_s *chan = (struct sam_chan_s *)handle;
+
+ tcvdbg("Freeing %p channel=%d inuse=%d\n", chan, chan->chan, chan->inuse);
DEBUGASSERT(chan && chan->inuse);
/* Make sure that the channel is stopped */
@@ -776,7 +807,7 @@ void sam_tc_free(TC_HANDLE handle)
sam_tc_stop(handle);
/* Mark the channel as available */
-
+
chan->inuse = false;
}
@@ -791,14 +822,16 @@ void sam_tc_free(TC_HANDLE handle)
* handle Channel handle previously allocated by sam_tc_allocate()
*
* Returned Value:
- *
+ *
****************************************************************************/
void sam_tc_start(TC_HANDLE handle)
{
struct sam_chan_s *chan = (struct sam_chan_s *)handle;
+ tcvdbg("Starting channel %d inuse=%d\n", chan->chan, chan->inuse);
DEBUGASSERT(chan && chan->inuse);
+
sam_chan_putreg(chan, SAM_TC_CCR_OFFSET, TC_CCR_CLKEN | TC_CCR_SWTRG);
}
@@ -812,14 +845,16 @@ void sam_tc_start(TC_HANDLE handle)
* handle Channel handle previously allocated by sam_tc_allocate()
*
* Returned Value:
- *
+ *
****************************************************************************/
void sam_tc_stop(TC_HANDLE handle)
{
struct sam_chan_s *chan = (struct sam_chan_s *)handle;
+ tcvdbg("Stopping channel %d inuse=%d\n", chan->chan, chan->inuse);
DEBUGASSERT(chan && chan->inuse);
+
sam_chan_putreg(chan, SAM_TC_CCR_OFFSET, TC_CCR_CLKDIS);
}
@@ -828,10 +863,9 @@ void sam_tc_stop(TC_HANDLE handle)
*
* Description:
* Set TC_RA, TC_RB, or TC_RB using the provided divisor. The actual
- * setting in the regsiter will be the TC input frequency divided by
+ * setting in the register will be the TC input frequency divided by
* the provided divider (which should derive from the divider returned
* by sam_tc_divider).
- *
*
* Input Parameters:
* handle Channel handle previously allocated by sam_tc_allocate()
@@ -844,9 +878,15 @@ void sam_tc_stop(TC_HANDLE handle)
void sam_tc_setregister(TC_HANDLE handle, int reg, unsigned int div)
{
struct sam_chan_s *chan = (struct sam_chan_s *)handle;
+ uint32_t regval;
+
DEBUGASSERT(reg < TC_NREGISTERS);
- sam_chan_putreg(chan, g_regoffset[reg], TC_FREQUENCY / div);
+ regval = TC_FREQUENCY / div;
+ tcvdbg("Channel %d: Set register %d to %d / %d = %d\n",
+ chan->chan, reg, TC_FREQUENCY, div, (unsigned int)regval);
+
+ sam_chan_putreg(chan, g_regoffset[reg], regval);
}
/****************************************************************************
@@ -855,7 +895,6 @@ void sam_tc_setregister(TC_HANDLE handle, int reg, unsigned int div)
* Description:
* Return the timer input frequency, that is, the MCK frequency divided
* down so that the timer/counter is driven within its maximum frequency.
- * This value needed for
*
* Input Parameters:
* None
@@ -899,6 +938,8 @@ int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks)
{
int ndx = 0;
+ tcvdbg("frequency=%d\n", frequency);
+
/* Satisfy lower bound */
while (frequency < (g_divfreq[ndx] >> 16))
@@ -907,6 +948,7 @@ int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks)
{
/* If no divisor can be found, return -ERANGE */
+ tcdbg("Lower bound search failed\n");
return -ERANGE;
}
}
@@ -925,6 +967,7 @@ int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks)
if (div)
{
+ tcvdbg("return div=%d\n", g_divider[ndx]);
*div = g_divider[ndx];
}
@@ -932,6 +975,7 @@ int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks)
if (tcclks)
{
+ tcvdbg("return tcclks=%d\n", ndx);
*tcclks = ndx;
}
diff --git a/nuttx/arch/arm/src/sama5/sam_tc.h b/nuttx/arch/arm/src/sama5/sam_tc.h
index 97e7b0c34..ba5657503 100644
--- a/nuttx/arch/arm/src/sama5/sam_tc.h
+++ b/nuttx/arch/arm/src/sama5/sam_tc.h
@@ -164,7 +164,7 @@ void sam_tc_stop(TC_HANDLE handle);
*
* Description:
* Set TC_RA, TC_RB, or TC_RB using the provided divisor. The actual
- * setting in the regsiter will be the TC input frequency divided by
+ * setting in the register will be the TC input frequency divided by
* the provided divider (which should derive from the divider returned
* by sam_tc_divider).
*
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_adc.c b/nuttx/configs/sama5d3x-ek/src/sam_adc.c
new file mode 100644
index 000000000..7d586ca2b
--- /dev/null
+++ b/nuttx/configs/sama5d3x-ek/src/sam_adc.c
@@ -0,0 +1,118 @@
+/************************************************************************************
+ * configs/sama5d3x-ek/src/up_adc.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/analog/adc.h>
+
+#include "sam_adc.h"
+#include "sama5d3x-ek.h"
+
+#ifdef CONFIG_ADC
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: adc_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/adc.
+ *
+ ************************************************************************************/
+
+int adc_devinit(void)
+{
+#ifdef CONFIG_SAMA5_ADC
+ static bool initialized = false;
+ struct adc_dev_s *adc;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call stm32_adcinitialize() to get an instance of the ADC interface */
+
+ adc = sam_adc_initialize();
+ 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;
+#else
+ return -ENOSYS;
+#endif
+}
+
+#endif /* CONFIG_ADC */ \ No newline at end of file