arch/arm/src/samd2l2 and boards/arm/samd2l2/arduino-m0: Add support to SAMD2L ADC driver and board support to Arduino M0.

This commit is contained in:
Alan Carvalho de Assis 2019-12-15 17:36:59 -06:00 committed by Gregory Nutt
parent 871197b4ec
commit 787128930f
10 changed files with 965 additions and 1 deletions

View File

@ -91,6 +91,10 @@ ifeq ($(CONFIG_ARCH_IRQPRIO),y)
CHIP_CSRCS += sam_irqprio.c
endif
ifeq ($(CONFIG_SAMD2L2_ADC),y)
CHIP_CSRCS += sam_adc.c
endif
ifeq ($(CONFIG_SAMD2L2_DMAC),y)
CHIP_CSRCS += sam_dmac.c
endif

View File

@ -0,0 +1,61 @@
/************************************************************************************
* arch/arm/src/samd2l2/adc.h
*
* Copyright (C) 2019 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_SAMD2L2_ADC_H
#define __ARCH_ARM_SRC_SAMD2L2_ADC_H
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* IOCTL definitions */
#define SAMD_ADC_IOCTL_START 0 /* start adc conversion */
#define SAMD_ADC_IOCTL_STOP 1 /* stop adc conversion */
#define SAMD_ADC_IOCTL_SET_PARAMS 2 /* set parameters when adc is stopped */
#define SAMD_ADC_IOCTL_GET_PARAMS 3 /* get parameters */
/****************************************************************************
* Public Types
****************************************************************************/
struct sam_adc_param_s
{
uint8_t samplen; /* sampling time length */
uint8_t prescaler; /* prescaler configuration */
uint8_t averaging; /* number of samples to be collected */
};
#endif /* __ARCH_ARM_SRC_SAMD2L2_ADC_H */

View File

@ -0,0 +1,621 @@
/*****************************************************************************
* arch/arm/include/samd2l2/sam_adc.c
*
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
* Author: Alexander Vasiliev<alexvasiljev@gmail.com>
* Author: Alan Carvalho de Assis <acassis@gmail.com>
*
* 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <unistd.h>
#include <string.h>
#include <semaphore.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/signal.h>
#include <nuttx/semaphore.h>
#include <nuttx/fs/fs.h>
#include <nuttx/analog/adc.h>
#include <nuttx/kmalloc.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "adc.h"
#include "sam_adc.h"
#include "sam_pinmap.h"
#include "sam_gclk.h"
#include "sam_port.h"
#include "sam_fuses.h"
#include "samd_periphclks.h"
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
#define ADC_INSERT_INPUT(n) \
if (ch_pos < priv->num_channels) \
{ \
sam_configport(PORT_AIN##n); \
priv->channels[ch_pos++] = n; \
}
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/* ADC methods */
static int sam_adc_bind(FAR struct adc_dev_s *dev,
FAR const struct adc_callback_s *callback);
static void sam_adc_reset(FAR struct adc_dev_s *dev);
static int sam_adc_setup(FAR struct adc_dev_s *dev);
static void sam_adc_shutdown(FAR struct adc_dev_s *dev);
static void sam_adc_rxint(FAR struct adc_dev_s *dev, bool enable);
static int sam_adc_ioctl(FAR struct adc_dev_s *dev, int cmd,
unsigned long arg);
/****************************************************************************
* Private Types
****************************************************************************/
struct sam_adc_priv
{
int genclk; /* clock generator */
const struct adc_callback_s *adc_callback; /* callback for upper driver */
int cur_channel; /* current channel in progress */
int num_channels; /* number of channels */
int *channels; /* channels to process */
uint8_t ref; /* reference selection */
uint32_t neg; /* negative input selection */
uint8_t samplen; /* sampling time length */
uint32_t prescaler; /* prescaler configuration */
uint8_t averaging; /* number of samples to be collected */
};
/****************************************************************************
* Private Data
****************************************************************************/
static const struct adc_ops_s sam_adc_ops =
{
sam_adc_bind,
sam_adc_reset,
sam_adc_setup,
sam_adc_shutdown,
sam_adc_rxint,
sam_adc_ioctl
};
static struct adc_dev_s g_sam_adc_dev;
/*******************************************************************************
* Private Functions
*******************************************************************************/
static void sam_adc_synchronization(void)
{
while ((getreg8(SAM_ADC_STATUS) & ADC_STATUS_SYNCBUSY) != 0);
}
static int sam_adc_interrupt(int irq, FAR void *context, FAR void *arg)
{
uint32_t result;
struct adc_dev_s *dev = (struct adc_dev_s *)arg;
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
sam_adc_synchronization();
result = getreg16(SAM_ADC_RESULT);
ainfo("ADC Result = %d:\n", result);
priv->adc_callback->au_receive(dev, priv->channels[priv->cur_channel], result);
putreg8(ADC_INT_RESRDY, SAM_ADC_INTFLAG);
/* If all channels were read, restart to the first channel */
if (++priv->cur_channel == priv->num_channels)
{
priv->cur_channel = 0;
}
putreg32(priv->channels[priv->cur_channel] | priv->neg, SAM_ADC_INPUTCTRL);
sam_adc_synchronization();
putreg8(ADC_SWTRIG_START, SAM_ADC_SWTRIG);
return 0;
}
static int sam_adc_init_clock(struct adc_dev_s *dev)
{
uint16_t regval;
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
regval = GCLK_CLKCTRL_ID_ADC;
/* Select and disable the ADC_GCLK_ID_CORE generic clock */
putreg16(regval, SAM_GCLK_CLKCTRL);
/* Wait for clock to become disabled */
while ((getreg16(SAM_GCLK_CLKCTRL) & GCLK_CLKCTRL_CLKEN) != 0);
/* Select the ADC_GCLK_ID_CORE source clock generator */
regval |= (uint16_t)priv->genclk << GCLK_CLKCTRL_GEN_SHIFT;
/* Write the new configuration */
putreg16(regval, SAM_GCLK_CLKCTRL);
/* Enable the ADC_GCLK_ID_CORE generic clock */
regval |= GCLK_CLKCTRL_CLKEN;
putreg16(regval, SAM_GCLK_CLKCTRL);
while ((getreg16(SAM_GCLK_STATUS) & GCLK_STATUS_SYNCBUSY) != 0);
return 0;
}
static int sam_adc_calibrate(struct adc_dev_s *dev)
{
uint8_t linearity;
uint8_t bias;
uint16_t regval;
bias = (getreg8(ADC_FUSES_BIASCAL_ADDR) & ADC_FUSES_BIASCAL_MASK) >>
ADC_FUSES_BIASCAL_SHIFT;
linearity = getreg16(SAM_AUX1_AREA4 + 3) >> 3;
regval = linearity | (bias << ADC_CALIB_BIAS_OFFSET);
putreg16(regval, SAM_ADC_CALIB);
return 0;
}
/* Bind the upper-half driver callbacks to the lower-half implementation. This
* must be called early in order to receive ADC event notifications.
*/
static int sam_adc_bind(FAR struct adc_dev_s *dev,
FAR const struct adc_callback_s *callback)
{
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
priv->adc_callback = callback;
return 0;
}
/****************************************************************************
* Name: sam_adc_reset
*
* Description:
* Reset the ADC device. Called early to initialize the hardware. This
* is called, before sam_adc_setup() and on error conditions.
*
* Input Parameters:
* dev - A reference to the ADC device structure
*
* Returned Value:
* None
*
****************************************************************************/
static void sam_adc_reset(FAR struct adc_dev_s *dev)
{
/* Disable ADC */
putreg8(0, SAM_ADC_CTRLA);
sam_adc_synchronization();
/* Reset ADC */
putreg8(ADC_CTRLA_SWRST, SAM_ADC_CTRLA);
while ((getreg8(SAM_ADC_STATUS) & ADC_STATUS_SYNCBUSY) != 0 ||
(getreg8(SAM_ADC_CTRLA) & ADC_CTRLA_SWRST) != 0);
}
/****************************************************************************
* Name: sam_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.
* Reset the ADC device. Called early to initialize the hardware. This
* is called, before sam_adc_setup() and on error conditions.
*
* Input Parameters:
* dev - A reference to the ADC device structure
*
* Returned Value:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
static int sam_adc_setup(FAR struct adc_dev_s *dev)
{
uint8_t regval;
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
sam_adc_calibrate(dev);
/* ADC continues normal operation during debug mode */
regval = ADC_DBGCTRL_DBGRUN;
putreg8(regval, SAM_ADC_ADC_DBGCTRL);
regval = priv->ref | ADC_REFCTRL_REFCOMP;
putreg8(regval, SAM_ADC_REFCTL);
regval = priv->channels[0] | priv->neg;
putreg32(regval, SAM_ADC_INPUTCTRL);
priv->cur_channel = 0;
sam_adc_synchronization();
regval = priv->samplen;
putreg8(regval, SAM_ADC_SAMPCTRL);
putreg16(ADC_CTRLB_RESSEL_16BIT |
(priv->prescaler << ADC_CTRLB_PRESCALER_OFFSET), SAM_ADC_CTRLB);
sam_adc_synchronization();
regval = priv->averaging;
putreg8(regval, SAM_ADC_AVGCTRL);
/* Enable ADC */
regval = ADC_CTRLA_ENABLE;
putreg8(regval, SAM_ADC_CTRLA);
return 0;
}
/****************************************************************************
* Name: sam_adc_shutdown
*
* Description:
* Disable the ADC. This method is called when the ADC device is closed.
* This method reverses the operation the setup method.
*
* Input Parameters:
* dev - A reference to the ADC device structure
*
* Returned Value:
* None.
*
****************************************************************************/
static void sam_adc_shutdown(FAR struct adc_dev_s *dev)
{
/* Disable ADC */
putreg8(0, SAM_ADC_CTRLA);
sam_adc_synchronization();
}
/****************************************************************************
* Name: sam_adc_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
* Input Parameters:
* dev - A reference to the ADC device structure
*
* Returned Value:
* None.
*
****************************************************************************/
static void sam_adc_rxint(FAR struct adc_dev_s *dev, bool enable)
{
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
if (enable)
{
priv->cur_channel = 0;
putreg8(ADC_INT_RESRDY, SAM_ADC_INTENSET);
sam_adc_synchronization();
putreg8(ADC_SWTRIG_START, SAM_ADC_SWTRIG);
sam_adc_synchronization();
}
else
{
putreg8(0, SAM_ADC_INTENCLR);
sam_adc_synchronization();
}
}
/****************************************************************************
* Name: sam_adc_ioctl
*
* Description:
* All ioctl calls will be routed through this method
*
* Input Parameters:
* dev - A reference to the ADC device structure
*
* Returned Value:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
static int sam_adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
{
int ret = 0;
struct sam_adc_priv *priv = (struct sam_adc_priv *)dev->ad_priv;
struct sam_adc_param_s *params = (struct sam_adc_param_s *)arg;
switch (cmd)
{
case SAMD_ADC_IOCTL_START:
sam_adc_setup(dev);
sam_adc_rxint(dev, true);
break;
case SAMD_ADC_IOCTL_STOP:
sam_adc_rxint(dev, false);
sam_adc_shutdown(dev);
break;
case SAMD_ADC_IOCTL_SET_PARAMS:
if ((getreg8(SAM_ADC_CTRLA) & ADC_CTRLA_ENABLE) != 0)
{
ret = -EBUSY;
break;
}
priv->averaging = params->averaging;
priv->prescaler = params->prescaler;
priv->samplen = params->samplen;
break;
case SAMD_ADC_IOCTL_GET_PARAMS:
params->averaging = priv->averaging;
params->prescaler = priv->prescaler;
params->samplen = priv->samplen;
break;
}
return ret;
}
/*******************************************************************************
* Public Functions
*******************************************************************************/
/****************************************************************************
* Name: sam_adcinitialize
*
* Description:
* Register SAMD2x/L2x ADC driver
*
* Input Parameters:
* genclk - The Clock Generator to be used on ADC block.
*
* Returned Value:
* A reference to the ADC device structure if succeed or NULL otherwise.
*
****************************************************************************/
struct adc_dev_s *sam_adcinitialize(int genclk)
{
irqstate_t flags;
int ret;
int ch_pos = 0;
struct sam_adc_priv *priv = (struct sam_adc_priv *)
kmm_malloc(sizeof(struct sam_adc_priv));
priv->genclk = genclk;
g_sam_adc_dev.ad_priv = priv;
g_sam_adc_dev.ad_ops = &sam_adc_ops;
priv->num_channels = BOARD_ADC_NUM_CHANNELS;
priv->channels = (int *)kmm_malloc(priv->num_channels * sizeof(int));
#if BOARD_ADC_REF == ADC_REFCTRL_REFSEL_VREFA
sam_configport(PORT_ADC_VREFA);
#elif BOARD_ADC_REF == ADC_REFCTRL_REFSEL_VREFB
sam_configport(PORT_ADC_VREFB);
#endif
#if BOARD_ADC_NEG == 0
sam_configport(PORT_AIN0);
#elif BOARD_ADC_NEG == 1
sam_configport(PORT_AIN1);
#elif BOARD_ADC_NEG == 2
sam_configport(PORT_AIN2);
#elif BOARD_ADC_NEG == 3
sam_configport(PORT_AIN3);
#elif BOARD_ADC_NEG == 4
sam_configport(PORT_AIN4);
#elif BOARD_ADC_NEG == 5
sam_configport(PORT_AIN5);
#elif BOARD_ADC_NEG == 6
sam_configport(PORT_AIN6);
#elif BOARD_ADC_NEG == 7
sam_configport(PORT_AIN7);
#endif
priv->ref = BOARD_ADC_REF;
priv->neg = BOARD_ADC_NEG;
#ifdef BOARD_ADC_SAMPLEN
priv->samplen = BOARD_ADC_SAMPLEN;
#else
priv->samplen = ADC_AVGCTRL_SAMPLENUM_32;
#endif
#ifdef BOARD_ADC_AVERAGING
priv->averaging = BOARD_ADC_AVERAGING;
#else
priv->averaging = ADC_AVGCTRL_SAMPLENUM_1024;
#endif
#ifdef BOARD_ADC_PRESCALER
priv->prescaler = BOARD_ADC_PRESCALER;
#else
priv->prescaler = ADC_CTRLB_PRESCALER_DIV256;
#endif
#ifdef BOARD_ADC_INPUT0
ADC_INSERT_INPUT(0);
#endif
#ifdef BOARD_ADC_INPUT1
ADC_INSERT_INPUT(1);
#endif
#ifdef BOARD_ADC_INPUT2
ADC_INSERT_INPUT(2);
#endif
#ifdef BOARD_ADC_INPUT3
ADC_INSERT_INPUT(3);
#endif
#ifdef BOARD_ADC_INPUT4
ADC_INSERT_INPUT(4);
#endif
#ifdef BOARD_ADC_INPUT5
ADC_INSERT_INPUT(5);
#endif
#ifdef BOARD_ADC_INPUT6
ADC_INSERT_INPUT(6);
#endif
#ifdef BOARD_ADC_INPUT7
ADC_INSERT_INPUT(7);
#endif
#ifdef BOARD_ADC_INPUT8
ADC_INSERT_INPUT(8);
#endif
#ifdef BOARD_ADC_INPUT9
ADC_INSERT_INPUT(9);
#endif
#ifdef BOARD_ADC_INPUT10
ADC_INSERT_INPUT(10);
#endif
#ifdef BOARD_ADC_INPUT11
ADC_INSERT_INPUT(11);
#endif
#ifdef BOARD_ADC_INPUT12
ADC_INSERT_INPUT(12);
#endif
#ifdef BOARD_ADC_INPUT13
ADC_INSERT_INPUT(13);
#endif
#ifdef BOARD_ADC_INPUT14
ADC_INSERT_INPUT(14);
#endif
#ifdef BOARD_ADC_INPUT15
ADC_INSERT_INPUT(15);
#endif
#ifdef BOARD_ADC_INPUT16
ADC_INSERT_INPUT(16);
#endif
#ifdef BOARD_ADC_INPUT17
ADC_INSERT_INPUT(17);
#endif
#ifdef BOARD_ADC_INPUT18
ADC_INSERT_INPUT(18);
#endif
#ifdef BOARD_ADC_INPUT19
ADC_INSERT_INPUT(19);
#endif
#ifdef BOARD_ADC_INPUT_BANDGAP
if (ch_pos < priv->num_channels)
{
priv->channels[ch_pos++] = 0x19;
}
#endif
#ifdef BOARD_ADC_INPUT_SCALEDCOREVCC
if (ch_pos < priv->num_channels)
{
priv->channels[ch_pos++] = 0x1a;
}
#endif
#ifdef BOARD_ADC_INPUT_SCALEDIOVCC
if (ch_pos < priv->num_channels)
{
priv->channels[ch_pos++] = 0x1b;
}
#endif
#ifdef BOARD_ADC_INPUT_DAC
if (ch_pos < priv->num_channels)
{
priv->channels[ch_pos++] = 0x1c;
}
#endif
sam_adc_enableperiph();
sam_adc_init_clock(&g_sam_adc_dev);
flags = enter_critical_section();
/* Attach Interrupt Handler */
ret = irq_attach(SAM_IRQ_ADC, sam_adc_interrupt, &g_sam_adc_dev);
if (ret < 0)
{
aerr("ERROR: Failed to attach irq %d\n", SAM_IRQ_ADC);
leave_critical_section(flags);
return NULL;
}
up_enable_irq(SAM_IRQ_ADC);
leave_critical_section(flags);
return (struct adc_dev_s *)&g_sam_adc_dev;
}

View File

@ -69,6 +69,23 @@ extern "C"
#define EXTERN extern
#endif
/****************************************************************************
* Name: sam_adcinitialize
*
* Description:
* Initialize the ADC. See sam_adc.c for more details.
*
* Input Parameters:
* genclk - Number of the Clock Generator to use.
*
* Returned Value:
* Valid ADC device structure reference on success; a NULL on failure
*
****************************************************************************/
struct adc_dev_s;
struct adc_dev_s *sam_adcinitialize(int genclk);
#undef EXTERN
#if defined(__cplusplus)
}

View File

@ -470,6 +470,24 @@
#define BOARD_SERCOM5_FREQUENCY BOARD_GCLK0_FREQUENCY
/* ADC definitions **********************************************************/
#define BOARD_ADC_GCLKGEN 0
/* We are using PA3 as Analog Input */
#define PORT_AIN1 PORT_AIN1_1
#define BOARD_ADC_INPUT1 1
#define BOARD_ADC_NUM_CHANNELS 1
/* The negative input is the internal GND */
#define BOARD_ADC_NEG ADC_INPUTCTRL_MUXNEG_GND
/* The VREF is the INTVCC1 = 1/2 VDDANA */
#define BOARD_ADC_REF ADC_REFCTRL_REFSEL_INTVCC1
/* USB definitions **********************************************************/
/* This is the source clock generator for the GCLK_USB clock

View File

@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
ASRCS =
CSRCS = sam_boot.c
CSRCS = sam_boot.c sam_bringup.c
ifeq ($(CONFIG_SAMD2L2_SERCOM0),y)
CSRCS += sam_spi.c
@ -52,6 +52,10 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += sam_buttons.c
endif
ifeq ($(CONFIG_SAMD2L2_ADC),y)
CSRCS += sam_adc.c
endif
ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += sam_appinit.c
endif

View File

@ -97,6 +97,32 @@
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: sam_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_LATE_INITIALIZE=y :
* Called from board_late_initialize().
*
* CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int sam_bringup(void);
/************************************************************************************
* Name: sam_adc_setup
*
* Description:
* Initialize ADC and register the ADC driver.
*
************************************************************************************/
int sam_adc_setup(void);
/****************************************************************************
* Name: sam_spidev_initialize
*

View File

@ -0,0 +1,104 @@
/************************************************************************************
* boards/arm/samd2l2/arduino-m0/src/sam_adc.c
*
* Copyright (C) 2012, 2016 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/board.h>
#include <nuttx/analog/adc.h>
#include <arch/board/board.h>
#include "chip.h"
#include "sam_adc.h"
#include "arduino_m0.h"
#ifdef CONFIG_ADC
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: sam_adc_setup
*
* Description:
* Initialize ADC and register the ADC driver.
*
************************************************************************************/
int sam_adc_setup(void)
{
static bool initialized = false;
struct adc_dev_s *adc;
int ret;
/* Check if we have already initialized */
if (!initialized)
{
/* Call sam_adcinitialize() to get an instance of the ADC interface */
adc = sam_adcinitialize(0);
if (adc == NULL)
{
aerr("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)
{
aerr("ERROR: adc_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif /* CONFIG_ADC */

View File

@ -90,3 +90,26 @@ void sam_boardinitialize(void)
board_autoled_initialize();
#endif
}
/****************************************************************************
* Name: board_late_initialize
*
* Description:
* If CONFIG_BOARD_LATE_INITIALIZE is selected, then an additional
* initialization call will be performed in the boot-up sequence to a
* function called board_late_initialize(). board_late_initialize() will be
* called immediately after up_intitialize() is called and just before the
* initial application is started. This additional initialization phase
* may be used, for example, to initialize board-specific device drivers.
*
****************************************************************************/
#ifdef CONFIG_BOARD_LATE_INITIALIZE
void board_late_initialize(void)
{
/* Perform board initialization */
(void)sam_bringup();
}
#endif /* CONFIG_BOARD_LATE_INITIALIZE */

View File

@ -0,0 +1,86 @@
/****************************************************************************
* boards/arm/samd2l2/arduino-m0/src/sam_bringup.c
*
* Copyright (C) 2019 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 <sys/types.h>
#include <debug.h>
#include <nuttx/board.h>
#include "sam_config.h"
#include "arduino_m0.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: sam_bringup
*
* Description:
* Bring up board features
*
****************************************************************************/
int sam_bringup(void)
{
int ret = OK;
/* Configure the ADC driver */
#ifdef CONFIG_SAMD2L2_ADC
ret = sam_adc_setup();
if (ret < 0)
{
syslog(LOG_ERR, "Failed to initialize the ADC driver: %d\n", ret);
return ret;
}
#endif
return ret;
}