9
0
Fork 0

ADC bugfixes plus new DAC logic from Lzyy

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@3913 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2011-08-25 14:11:39 +00:00
parent 12c64bc38b
commit 3b5a4d48fb
12 changed files with 1404 additions and 27 deletions

View File

@ -2023,4 +2023,8 @@
circles -- both circular outlines and filled circles.
* graphic/nxglib/nxglib_spitline.c: Add a "fudge factor" that eliminates
some problems for rendering nearly horizontal, wide lines.
* drivers/analog, include/nuttx/analog, arch/arch/src/lpcxx: (1) Add
updates to the ADS1255 driver, (2) fix errors from my last merge (sorry),
(3) Add DAC infrastructure, (4) add AD5410 DAC driver, and (5) add
LPC17xx ADC and DAC drivers. All contributed by Li Zhuoyi (Lzyy).

View File

@ -88,3 +88,11 @@ ifeq ($(CONFIG_LPC17_ETHERNET),y)
CHIP_CSRCS += lpc17_ethernet.c
endif
endif
ifeq ($(CONFIG_LPC17_ADC),y)
CHIP_CSRCS += lpc17_adc.c
endif
ifeq ($(CONFIG_LPC17_DAC),y)
CHIP_CSRCS += lpc17_dac.c
endif

View File

@ -0,0 +1,268 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_adc.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-05 initial version
*
* This file is a part of NuttX:
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
*
* 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.
*
************************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
#include <nuttx/analog/adc.h>
#include "up_internal.h"
#include "up_arch.h"
#include "chip.h"
#include "lpc17_internal.h"
#include "lpc17_syscon.h"
#include "lpc17_pinconn.h"
#include "lpc17_adc.h"
#if defined(CONFIG_LPC17_ADC)
#ifndef CONFIG_ADC0_MASK
#define CONFIG_ADC0_MASK 0x01
#endif
#ifndef CONFIG_ADC0_SPS
#define CONFIG_ADC0_SPS 1000
#endif
#ifndef CONFIG_ADC0_AVERAGE
#define CONFIG_ADC0_AVERAGE 200
#endif
/****************************************************************************
* ad_private Types
****************************************************************************/
struct up_dev_s
{
uint8_t mask;
uint32_t sps;
int irq;
int32_t buf[8];
uint8_t count[8];
};
/****************************************************************************
* ad_private Function Prototypes
****************************************************************************/
/* ADC methods */
static void adc_reset(FAR struct adc_dev_s *dev);
static int adc_setup(FAR struct adc_dev_s *dev);
static void adc_shutdown(FAR struct adc_dev_s *dev);
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_interrupt(int irq, void *context);
/****************************************************************************
* ad_private Data
****************************************************************************/
static const struct adc_ops_s g_adcops =
{
.ao_reset =adc_reset,
.ao_setup = adc_setup,
.ao_shutdown = adc_shutdown,
.ao_rxint = adc_rxint,
.ao_ioctl = adc_ioctl,
};
static struct up_dev_s g_adcpriv =
{
.sps = CONFIG_ADC0_SPS,
.mask = CONFIG_ADC0_MASK,
.irq = LPC17_IRQ_ADC,
};
static struct adc_dev_s g_adcdev =
{
.ad_ops = &g_adcops,
.ad_priv= &g_adcpriv,
};
/****************************************************************************
* ad_private Functions
****************************************************************************/
/* Reset the ADC device. Called early to initialize the hardware. This
* is called, before ao_setup() and on error conditions.
*/
static void adc_reset(FAR struct adc_dev_s *dev)
{
irqstate_t flags;
uint32_t regval;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
flags = irqsave();
regval = getreg32(LPC17_SYSCON_PCONP);
regval |= SYSCON_PCONP_PCADC;
putreg32(regval, LPC17_SYSCON_PCONP);
putreg32(ADC_CR_PDN,LPC17_ADC_CR);
regval = getreg32(LPC17_SYSCON_PCLKSEL0);
regval &= ~SYSCON_PCLKSEL0_ADC_MASK;
regval |= (SYSCON_PCLKSEL_CCLK8 << SYSCON_PCLKSEL0_ADC_SHIFT);
putreg32(regval, LPC17_SYSCON_PCLKSEL0);
uint32_t clkdiv=LPC17_CCLK/8/65/priv->sps;
clkdiv<<=8;
clkdiv&=0xff00;
putreg32(ADC_CR_PDN|ADC_CR_BURST|clkdiv|priv->mask,LPC17_ADC_CR);
if(priv->mask&0x01)
lpc17_configgpio(GPIO_AD0p0);
else if(priv->mask&0x02)
lpc17_configgpio(GPIO_AD0p1);
else if(priv->mask&0x04)
lpc17_configgpio(GPIO_AD0p2);
else if(priv->mask&0x08)
lpc17_configgpio(GPIO_AD0p3);
else if(priv->mask&0x10)
lpc17_configgpio(GPIO_AD0p4);
else if(priv->mask&0x20)
lpc17_configgpio(GPIO_AD0p5);
else if(priv->mask&0x40)
lpc17_configgpio(GPIO_AD0p6);
else if(priv->mask&0x80)
lpc17_configgpio(GPIO_AD0p7);
irqrestore(flags);
}
/* 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.
*/
static int adc_setup(FAR struct adc_dev_s *dev)
{
int i;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
int ret = irq_attach(priv->irq, adc_interrupt);
if (ret == OK)
{
for(i=0;i<8;i++)
{
priv->buf[i]=0;
priv->count[i]=0;
}
up_enable_irq(priv->irq);
}
return ret;
}
/* Disable the ADC. This method is called when the ADC device is closed.
* This method reverses the operation the setup method.
*/
static void adc_shutdown(FAR struct adc_dev_s *dev)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
up_disable_irq(priv->irq);
irq_detach(priv->irq);
}
/* Call to enable or disable RX interrupts */
static void adc_rxint(FAR struct adc_dev_s *dev, bool enable)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
if (enable)
putreg32(ADC_INTEN_GLOBAL,LPC17_ADC_INTEN);
else
putreg32(0x00,LPC17_ADC_INTEN);
}
/* All ioctl calls will be routed through this method */
static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
{
dbg("Fix me:Not Implemented\n");
return 0;
}
static int adc_interrupt(int irq, void *context)
{
uint32_t regval;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.ad_priv;
unsigned char ch;
int32_t value;
regval=getreg32(LPC17_ADC_GDR);
ch=(regval>>24)&0x07;
priv->buf[ch]+=regval&0xfff0;
priv->count[ch]++;
if(priv->count[ch]>=CONFIG_ADC0_AVERAGE)
{
value=priv->buf[ch]/priv->count[ch];
value<<=15;
adc_receive(&g_adcdev,ch,value);
priv->buf[ch]=0;
priv->count[ch]=0;
}
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_adcinitialize
*
* Description:
* Initialize the adc
*
* Returned Value:
* Valid can device structure reference on succcess; a NULL on failure
*
****************************************************************************/
FAR struct adc_dev_s *up_adcinitialize( )
{
return &g_adcdev;
}
#endif

View File

@ -0,0 +1,190 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_dac.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-05 initial version
*
* This file is a part of NuttX:
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
*
* 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.
*
************************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
#include <nuttx/analog/dac.h>
#include "up_internal.h"
#include "up_arch.h"
#include "chip.h"
#include "lpc17_internal.h"
#include "lpc17_syscon.h"
#include "lpc17_pinconn.h"
#include "lpc17_dac.h"
#if defined(CONFIG_LPC17_DAC)
/****************************************************************************
* ad_private Types
****************************************************************************/
/****************************************************************************
* ad_private Function Prototypes
****************************************************************************/
/* DAC methods */
static void dac_reset(FAR struct dac_dev_s *dev);
static int dac_setup(FAR struct dac_dev_s *dev);
static void dac_shutdown(FAR struct dac_dev_s *dev);
static void dac_txint(FAR struct dac_dev_s *dev, bool enable);
static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg);
static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg);
static int dac_interrupt(int irq, void *context);
/****************************************************************************
* ad_private Data
****************************************************************************/
static const struct dac_ops_s g_dacops =
{
.ao_reset =dac_reset,
.ao_setup = dac_setup,
.ao_shutdown = dac_shutdown,
.ao_txint = dac_txint,
.ao_send = dac_send,
.ao_ioctl = dac_ioctl,
};
static struct dac_dev_s g_dacdev =
{
.ad_ops = &g_dacops,
};
/****************************************************************************
* ad_private Functions
****************************************************************************/
/* Reset the DAC device. Called early to initialize the hardware. This
* is called, before ao_setup() and on error conditions.
*/
static void dac_reset(FAR struct dac_dev_s *dev)
{
irqstate_t flags;
uint32_t regval;
flags = irqsave();
regval = getreg32(LPC17_SYSCON_PCLKSEL0);
regval &= ~SYSCON_PCLKSEL0_DAC_MASK;
regval |= (SYSCON_PCLKSEL_CCLK8 << SYSCON_PCLKSEL0_DAC_SHIFT);
putreg32(regval, LPC17_SYSCON_PCLKSEL0);
//putreg32(DAC_CTRL_DBLBUFEN,LPC17_DAC_CTRL); ?
lpc17_configgpio(GPIO_AOUT);
irqrestore(flags);
}
/* Configure the DAC. This method is called the first time that the DAC
* device is opened. This will occur when the port is first opened.
* This setup includes configuring and attaching DAC interrupts. Interrupts
* are all disabled upon return.
*/
static int dac_setup(FAR struct dac_dev_s *dev)
{
return OK;
}
/* Disable the DAC. This method is called when the DAC device is closed.
* This method reverses the operation the setup method.
*/
static void dac_shutdown(FAR struct dac_dev_s *dev)
{
}
/* Call to enable or disable TX interrupts */
static void dac_txint(FAR struct dac_dev_s *dev, bool enable)
{
}
static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg)
{
putreg32((msg->am_data>>16)&0xfffff,LPC17_DAC_CR);
dac_txdone(&g_dacdev);
return 0;
}
/* All ioctl calls will be routed through this method */
static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg)
{
dbg("Fix me:Not Implemented\n");
return 0;
}
static int dac_interrupt(int irq, void *context)
{
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_dacinitialize
*
* Description:
* Initialize the DAC
*
* Returned Value:
* Valid dac device structure reference on succcess; a NULL on failure
*
****************************************************************************/
FAR struct dac_dev_s *up_dacinitialize()
{
return &g_dacdev;
}
#endif

View File

@ -41,8 +41,13 @@ ifeq ($(CONFIG_DAC),y)
# Include the common ADC character driver
CSRCS += dac.c
# Include DAC device drivers
ifeq ($(CONFIG_DAC_AD5410),y)
CSRCS += ad5410.c
endif
endif
# Check for ADC devices

View File

@ -0,0 +1,206 @@
/************************************************************************************
* arch/drivers/analog/ad5410.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-05 initial version
*
* This file is a part of NuttX:
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
*
* 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.
*
************************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
#include <nuttx/analog/dac.h>
#include <nuttx/spi.h>
#include "lpc17_internal.h"
#if defined(CONFIG_DAC_AD5410)
#define AD5410_REG_NOP 0x00
#define AD5410_REG_WR 0x01
#define AD5410_REG_RD 0x02
#define AD5410_REG_CMD 0x55
#define AD5410_REG_RST 0x56
#define AD5410_CMD_REXT (1<<13)
#define AD5410_CMD_OUTEN (1<<12)
#define AD5410_CMD_SRCLK(x) (x<<8)
#define AD5410_CMD_SRSTEP(x) (x<<5)
#define AD5410_CMD_SREN (1<<4)
#define AD5410_CMD_DCEN (1<<3)
#define AD5410_CMD_420MA 0x05
#define AD5410_CMD_020MA 0x06
#define AD5410_CMD_024MA 0x07
/****************************************************************************
* ad_private Types
****************************************************************************/
struct up_dev_s
{
int devno;
FAR struct spi_dev_s *spi; /* Cached SPI device reference */
};
/****************************************************************************
* ad_private Function Prototypes
****************************************************************************/
/* DAC methods */
static void dac_reset(FAR struct dac_dev_s *dev);
static int dac_setup(FAR struct dac_dev_s *dev);
static void dac_shutdown(FAR struct dac_dev_s *dev);
static void dac_txint(FAR struct dac_dev_s *dev, bool enable);
static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg);
static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg);
static int dac_interrupt(int irq, void *context);
/****************************************************************************
* ad_private Data
****************************************************************************/
static const struct dac_ops_s g_dacops =
{
.ao_reset =dac_reset,
.ao_setup = dac_setup,
.ao_shutdown = dac_shutdown,
.ao_txint = dac_txint,
.ao_send = dac_send,
.ao_ioctl = dac_ioctl,
};
static struct up_dev_s g_dacpriv;
static struct dac_dev_s g_dacdev =
{
.ad_ops = &g_dacops,
.ad_priv= &g_dacpriv,
};
/****************************************************************************
* ad_private Functions
****************************************************************************/
/* Reset the DAC device. Called early to initialize the hardware. This
* is called, before ao_setup() and on error conditions.
*/
static void dac_reset(FAR struct dac_dev_s *dev)
{
}
/* Configure the DAC. This method is called the first time that the DAC
* device is opened. This will occur when the port is first opened.
* This setup includes configuring and attaching DAC interrupts. Interrupts
* are all disabled upon return.
*/
static int dac_setup(FAR struct dac_dev_s *dev)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
FAR struct spi_dev_s *spi = priv->spi;
SPI_SELECT(spi, priv->devno, true);
SPI_SEND(spi,AD5410_REG_CMD);
SPI_SEND(spi,(AD5410_CMD_OUTEN|AD5410_CMD_420MA)>>8);
SPI_SEND(spi,AD5410_CMD_OUTEN|AD5410_CMD_420MA);
SPI_SELECT(spi, priv->devno, false);
return OK;
}
/* Disable the DAC. This method is called when the DAC device is closed.
* This method reverses the operation the setup method.
*/
static void dac_shutdown(FAR struct dac_dev_s *dev)
{
}
/* Call to enable or disable TX interrupts */
static void dac_txint(FAR struct dac_dev_s *dev, bool enable)
{
}
static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
FAR struct spi_dev_s *spi = priv->spi;
SPI_SELECT(spi, priv->devno, true);
SPI_SEND(spi,AD5410_REG_WR);
SPI_SEND(spi,(uint8_t)(msg->am_data>>24));
SPI_SEND(spi,(uint8_t)(msg->am_data>>16));
SPI_SELECT(spi, priv->devno, false);
dac_txdone(&g_dacdev);
return 0;
}
/* All ioctl calls will be routed through this method */
static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg)
{
dbg("Fix me:Not Implemented\n");
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_ad5410cinitialize
*
* Description:
* Initialize the selected DAC port
*
* Input Parameter:
* Port number (for hardware that has mutiple DAC interfaces)
*
* Returned Value:
* Valid ad5410 device structure reference on succcess; a NULL on failure
*
****************************************************************************/
FAR struct dac_dev_s *up_ad5410initialize(FAR struct spi_dev_s *spi, unsigned int devno)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_dacdev.ad_priv;
priv->spi=spi;
priv->devno=devno;
return &g_dacdev;
}
#endif

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/adc/adc.c
* drivers/analog/adc.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>

View File

@ -1,9 +1,10 @@
/************************************************************************************
* arch/drivers/adc/ads1255.c
* arch/drivers/analog/ads1255.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-05 initial version
* 0.2 2011-08-25 fix bug in g_adcdev (cd_ops -> ad_ops,cd_priv -> ad_priv)
*
* This file is a part of NuttX:
*
@ -101,13 +102,13 @@
#endif
/****************************************************************************
* cd_private Types
* ad_private Types
****************************************************************************/
struct up_dev_s
{
uint8_t channel;
uint8_t sps;
uint32_t sps;
uint8_t pga;
uint8_t buf;
const uint8_t *mux;
@ -117,7 +118,7 @@ struct up_dev_s
};
/****************************************************************************
* cd_private Function Prototypes
* ad_private Function Prototypes
****************************************************************************/
/* ADC methods */
@ -130,16 +131,16 @@ static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg);
static int adc_interrupt(int irq, void *context);
/****************************************************************************
* cd_private Data
* ad_private Data
****************************************************************************/
static const struct adc_ops_s g_adcops =
{
adc_reset, /* ao_reset */
adc_setup, /* ao_setup */
adc_shutdown, /* ao_shutdown */
adc_rxint, /* ao_rxint */
adc_ioctl /* ao_read */
.ao_reset = adc_reset, /* ao_reset */
.ao_setup = adc_setup, /* ao_setup */
.ao_shutdown = adc_shutdown, /* ao_shutdown */
.ao_rxint = adc_rxint, /* ao_rxint */
.ao_ioctl = adc_ioctl /* ao_read */
};
static struct up_dev_s g_adcpriv =
@ -155,8 +156,8 @@ static struct up_dev_s g_adcpriv =
static struct adc_dev_s g_adcdev =
{
.cd_ops = &g_adcops,
.cd_priv= &g_adcpriv,
.ad_ops = &g_adcops,
.ad_priv= &g_adcpriv,
};
/****************************************************************************
@ -183,7 +184,7 @@ static uint8_t getspsreg(uint16_t sps)
}
/****************************************************************************
* cd_private Functions
* ad_private Functions
****************************************************************************/
/* Reset the ADC device. Called early to initialize the hardware. This
* is called, before ao_setup() and on error conditions.
@ -191,7 +192,7 @@ static uint8_t getspsreg(uint16_t sps)
static void adc_reset(FAR struct adc_dev_s *dev)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
FAR struct spi_dev_s *spi = priv->spi;
SPI_SETMODE(spi, SPIDEV_MODE1);
@ -213,7 +214,7 @@ static void adc_reset(FAR struct adc_dev_s *dev)
static int adc_setup(FAR struct adc_dev_s *dev)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
FAR struct spi_dev_s *spi = priv->spi;
int ret = irq_attach(priv->irq, adc_interrupt);
if (ret == OK)
@ -242,7 +243,7 @@ static int adc_setup(FAR struct adc_dev_s *dev)
static void adc_shutdown(FAR struct adc_dev_s *dev)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
up_disable_irq(priv->irq);
irq_detach(priv->irq);
}
@ -251,7 +252,7 @@ static void adc_shutdown(FAR struct adc_dev_s *dev)
static void adc_rxint(FAR struct adc_dev_s *dev, bool enable)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
if (enable)
up_enable_irq(priv->irq);
else
@ -269,7 +270,7 @@ static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
static int adc_interrupt(int irq, void *context)
{
uint32_t regval;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.ad_priv;
FAR struct spi_dev_s *spi = priv->spi;
unsigned char buf[4];
unsigned char ch;
@ -322,7 +323,7 @@ static int adc_interrupt(int irq, void *context)
FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned int devno)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.cd_priv;
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.ad_priv;
/* Driver state data */

498
nuttx/drivers/analog/dac.c Normal file
View File

@ -0,0 +1,498 @@
/****************************************************************************
* drivers/analog/dac.c
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-04 initial version
*
* Derived from drivers/can.c
*
* Copyright (C) 2008-2009Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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/fs.h>
#include <nuttx/arch.h>
#include <nuttx/analog/dac.h>
#include <arch/irq.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define HALF_SECOND_MSEC 500
#define HALF_SECOND_USEC 500000L
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int dac_open(FAR struct file *filep);
static int dac_close(FAR struct file *filep);
static ssize_t dac_read(FAR struct file *, FAR char *, size_t);
static ssize_t dac_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
static int dac_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations dac_fops =
{
dac_open,
dac_close,
dac_read,
dac_write,
0,
dac_ioctl
#ifndef CONFIG_DISABLE_POLL
, 0
#endif
};
/****************************************************************************
* Private Functions
****************************************************************************/
/************************************************************************************
* Name: dac_open
*
* Description:
* This function is called whenever the DAC device is opened.
*
************************************************************************************/
static int dac_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct dac_dev_s *dev = inode->i_private;
uint8_t tmp;
int ret = OK;
/* If the port is the middle of closing, wait until the close is finished */
if (sem_wait(&dev->ad_closesem) != OK)
{
ret = -errno;
}
else
{
/* Increment the count of references to the device. If this the first
* time that the driver has been opened for this device, then initialize
* the device.
*/
tmp = dev->ad_ocount + 1;
if (tmp == 0)
{
/* More than 255 opens; uint8_t overflows to zero */
ret = -EMFILE;
}
else
{
/* Check if this is the first time that the driver has been opened. */
if (tmp == 1)
{
/* Yes.. perform one time hardware initialization. */
irqstate_t flags = irqsave();
ret = dev->ad_ops->ao_setup(dev);
if (ret == OK)
{
/* Mark the FIFOs empty */
dev->ad_xmit.af_head = 0;
dev->ad_xmit.af_tail = 0;
/* Save the new open count on success */
dev->ad_ocount = tmp;
}
irqrestore(flags);
}
}
sem_post(&dev->ad_closesem);
}
return ret;
}
/************************************************************************************
* Name: dac_close
*
* Description:
* This routine is called when the DAC device is closed.
* It waits for the last remaining data to be sent.
*
************************************************************************************/
static int dac_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct dac_dev_s *dev = inode->i_private;
irqstate_t flags;
int ret = OK;
if (sem_wait(&dev->ad_closesem) != OK)
{
ret = -errno;
}
else
{
/* Decrement the references to the driver. If the reference count will
* decrement to 0, then uninitialize the driver.
*/
if (dev->ad_ocount > 1)
{
dev->ad_ocount--;
sem_post(&dev->ad_closesem);
}
else
{
/* There are no more references to the port */
dev->ad_ocount = 0;
/* Now we wait for the transmit FIFO to clear */
while (dev->ad_xmit.af_head != dev->ad_xmit.af_tail)
{
#ifndef CONFIG_DISABLE_SIGNALS
usleep(HALF_SECOND_USEC);
#else
up_mdelay(HALF_SECOND_MSEC);
#endif
}
/* Free the IRQ and disable the DAC device */
flags = irqsave(); /* Disable interrupts */
dev->ad_ops->ao_shutdown(dev); /* Disable the DAC */
irqrestore(flags);
sem_post(&dev->ad_closesem);
}
}
return ret;
}
/****************************************************************************
* Name: dac_read
****************************************************************************/
static ssize_t dac_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
{
return 0;
}
/************************************************************************************
* Name: dac_xmit
*
* Description:
* Send the message at the head of the ad_xmit FIFO
*
* Assumptions:
* Called with interrupts disabled
*
************************************************************************************/
static int dac_xmit(FAR struct dac_dev_s *dev)
{
bool enable = false;
int ret = OK;
/* Check if the xmit FIFO is empty */
if (dev->ad_xmit.af_head != dev->ad_xmit.af_tail)
{
/* Send the next message at the head of the FIFO */
ret = dev->ad_ops->ao_send(dev, &dev->ad_xmit.af_buffer[dev->ad_xmit.af_head]);
/* Make sure the TX done interrupts are enabled */
enable = (ret == OK ? true : false);
}
dev->ad_ops->ao_txint(dev, enable);
return ret;
}
/************************************************************************************
* Name: dac_write
************************************************************************************/
static ssize_t dac_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
{
FAR struct inode *inode = filep->f_inode;
FAR struct dac_dev_s *dev = inode->i_private;
FAR struct dac_fifo_s *fifo = &dev->ad_xmit;
FAR struct dac_msg_s *msg;
bool empty = false;
ssize_t nsent = 0;
irqstate_t flags;
int nexttail;
int msglen;
int ret = 0;
/* Interrupts must disabled throughout the following */
flags = irqsave();
/* Check if the TX FIFO was empty when we started. That is a clue that we have
* to kick off a new TX sequence.
*/
empty = (fifo->af_head == fifo->af_tail);
/* Add the messages to the FIFO. Ignore any trailing messages that are
* shorter than the minimum.
*/
if (buflen % 5 ==0 )
msglen=5;
else if (buflen % 4 ==0 )
msglen=4;
else if (buflen % 3 ==0 )
msglen=3;
else if (buflen % 2 ==0 )
msglen=2;
else if (buflen == 1)
msglen=1;
else
msglen=5;
while ((buflen - nsent) >= msglen )
{
/* Check if adding this new message would over-run the drivers ability to enqueue
* xmit data.
*/
nexttail = fifo->af_tail + 1;
if (nexttail >= CONFIG_DAC_FIFOSIZE)
{
nexttail = 0;
}
/* If the XMIT fifo becomes full, then wait for space to become available */
while (nexttail == fifo->af_head)
{
/* The transmit FIFO is full -- was non-blocking mode selected? */
if (filep->f_oflags & O_NONBLOCK)
{
if (nsent == 0)
{
ret = -EAGAIN;
}
else
{
ret = nsent;
}
goto return_with_irqdisabled;
}
/* If the FIFO was empty when we started, then we will have
* start the XMIT sequence to clear the FIFO.
*/
if (empty)
{
dac_xmit(dev);
}
/* Wait for a message to be sent */
do
{
ret = sem_wait(&fifo->af_sem);
if (ret < 0 && errno != EINTR)
{
ret = -errno;
goto return_with_irqdisabled;
}
}
while (ret < 0);
/* Re-check the FIFO state */
empty = (fifo->af_head == fifo->af_tail);
}
/* We get here if there is space at the end of the FIFO. Add the new
* CAN message at the tail of the FIFO.
*/
if(msglen==5)
{
msg = (FAR struct dac_msg_s *)&buffer[nsent];
memcpy(&fifo->af_buffer[fifo->af_tail], msg, msglen);
}
else if(msglen == 4)
{
fifo->af_buffer[fifo->af_tail].am_channel=buffer[nsent];
fifo->af_buffer[fifo->af_tail].am_data=*(uint32_t *)&buffer[nsent];
fifo->af_buffer[fifo->af_tail].am_data&=0xffffff00;
}
else if(msglen == 3)
{
fifo->af_buffer[fifo->af_tail].am_channel=buffer[nsent];
fifo->af_buffer[fifo->af_tail].am_data=(*(uint16_t *)&buffer[nsent+1]);
fifo->af_buffer[fifo->af_tail].am_data<<=16;
}
else if(msglen == 2)
{
fifo->af_buffer[fifo->af_tail].am_channel=0;
fifo->af_buffer[fifo->af_tail].am_data=(*(uint16_t *)&buffer[nsent]);
fifo->af_buffer[fifo->af_tail].am_data<<=16;
}
else if(msglen == 1)
{
fifo->af_buffer[fifo->af_tail].am_channel=0;
fifo->af_buffer[fifo->af_tail].am_data=buffer[nsent];
fifo->af_buffer[fifo->af_tail].am_data<<=24;
}
/* Increment the tail of the circular buffer */
fifo->af_tail = nexttail;
/* Increment the number of bytes that were sent */
nsent += msglen;
}
/* We get here after all messages have been added to the FIFO. Check if
* we need to kick of the XMIT sequence.
*/
if (empty)
{
dac_xmit(dev);
}
/* Return the number of bytes that were sent */
ret = nsent;
return_with_irqdisabled:
irqrestore(flags);
return ret;
}
/************************************************************************************
* Name: dac_ioctl
************************************************************************************/
static int dac_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct dac_dev_s *dev = inode->i_private;
int ret = OK;
ret = dev->ad_ops->ao_ioctl(dev, cmd, arg);
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: dac_txdone
*
* Description:
* Called from the DAC interrupt handler at the completion of a send operation.
*
* Return:
* OK on success; a negated errno on failure.
*
************************************************************************************/
int dac_txdone(FAR struct dac_dev_s *dev)
{
int ret = -ENOENT;
/* Verify that the xmit FIFO is not empty */
if (dev->ad_xmit.af_head != dev->ad_xmit.af_tail)
{
/* Remove the message at the head of the xmit FIFO */
if (++dev->ad_xmit.af_head >= CONFIG_DAC_FIFOSIZE)
{
dev->ad_xmit.af_head = 0;
}
/* Send the next message in the FIFO */
ret = dac_xmit(dev);
if (ret == OK)
{
/* Inform any waiting threads that new xmit space is available */
ret = sem_post(&dev->ad_xmit.af_sem);
}
}
return ret;
}
int dac_register(FAR const char *path, FAR struct dac_dev_s *dev)
{
/* Initialize the DAC device structure */
dev->ad_ocount = 0;
sem_init(&dev->ad_xmit.af_sem, 0, 0);
sem_init(&dev->ad_closesem, 0, 1);
dev->ad_ops->ao_reset(dev);
return register_driver(path, &dac_fops, 0555, dev);
}

View File

@ -4,6 +4,7 @@
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-04 initial version
* 0.2 remove ao_read
*
* Derived from include/nuttx/can.h
* Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
@ -120,8 +121,6 @@ struct adc_ops_s
CODE void (*ao_rxint)(FAR struct adc_dev_s *dev, bool enable);
CODE int (*ao_read)(FAR struct adc_dev_s *dev, char *buffer,int len);
/* All ioctl calls will be routed through this method */
CODE int (*ao_ioctl)(FAR struct adc_dev_s *dev, int cmd, unsigned long arg);
@ -182,6 +181,15 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data);
FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned int devno);
/************************************************************************************
* Name: up_adcinitialize
*
* Description:
* Initialize the MCU internal adc driver
*
************************************************************************************/
FAR struct adc_dev_s *up_adcinitialize();
#if defined(__cplusplus)
}
#endif

View File

@ -0,0 +1,189 @@
/************************************************************************************
* include/nuttx/analog/dac.h
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-04 initial version
*
* Derived from include/nuttx/can.h
* Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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 __NUTTX_DAC_H
#define __NUTTX_DAC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
#include <nuttx/fs.h>
#include <nuttx/spi.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Default configuration settings that may be overridden in the board configuration.
* file. The configured size is limited to 255 to fit into a uint8_t.
*/
#if !defined(CONFIG_DAC_FIFOSIZE)
# define CONFIG_DAC_FIFOSIZE 8
#elif CONFIG_DAC_FIFOSIZE > 255
# undef CONFIG_DAC_FIFOSIZE
# define CONFIG_DAC_FIFOSIZE 255
#endif
/************************************************************************************
* Public Types
************************************************************************************/
struct dac_msg_s
{
uint8_t am_channel; /* The 8-bit DAC Channel */
int32_t am_data; /* DAC convert result (4 bytes) */
};
struct dac_fifo_s
{
sem_t af_sem; /* Counting semaphore */
uint8_t af_head; /* Index to the head [IN] index in the circular buffer */
uint8_t af_tail; /* Index to the tail [OUT] index in the circular buffer */
/* Circular buffer of CAN messages */
struct dac_msg_s af_buffer[CONFIG_DAC_FIFOSIZE];
};
/* This structure defines all of the operations providd by the architecture specific
* logic. All fields must be provided with non-NULL function pointers by the
* caller of dac_register().
*/
struct dac_dev_s;
struct dac_ops_s
{
/* Reset the DAC device. Called early to initialize the hardware. This
* is called, before ao_setup() and on error conditions.
*/
CODE void (*ao_reset)(FAR struct dac_dev_s *dev);
/* Configure the DAC. This method is called the first time that the DAC
* device is opened. This will occur when the port is first opened.
* This setup includes configuring and attaching DAC interrupts. Interrupts
* are all disabled upon return.
*/
CODE int (*ao_setup)(FAR struct dac_dev_s *dev);
/* Disable the DAC. This method is called when the DAC device is closed.
* This method reverses the operation the setup method.
*/
CODE void (*ao_shutdown)(FAR struct dac_dev_s *dev);
/* Call to enable or disable TX interrupts */
CODE void (*ao_txint)(FAR struct dac_dev_s *dev, bool enable);
/* This method will send one message on the DAC */
CODE int (*ao_send)(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg);
/* All ioctl calls will be routed through this method */
CODE int (*ao_ioctl)(FAR struct dac_dev_s *dev, int cmd, unsigned long arg);
};
/* This is the device structure used by the driver. The caller of
* dac_register() must allocate and initialize this structure. The
* calling logic need only set all fields to zero except:
*
* The elements of 'ad_ops', and 'ad_priv'
*
* The common logic will initialize all semaphores.
*/
struct dac_dev_s
{
uint8_t ad_ocount; /* The number of times the device has been opened */
uint8_t ad_nchannel; /* Number of dac channel */
sem_t ad_closesem; /* Locks out new opens while close is in progress */
struct dac_fifo_s ad_xmit; /* Describes receive FIFO */
const struct dac_ops_s *ad_ops; /* Arch-specific operations */
void *ad_priv; /* Used by the arch-specific logic */
};
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/************************************************************************************
* Name: dac_register
*
* Description:
* Register a dac driver.
*
************************************************************************************/
int dac_register(FAR const char *path, FAR struct dac_dev_s *dev);
/************************************************************************************
* Name: dac_txdone
*
* Description:
* Called from the DAC interrupt handler at the completion of a send operation.
*
* Return:
* OK on success; a negated errno on failure.
*
************************************************************************************/
int dac_txdone(FAR struct dac_dev_s *dev);
FAR struct dac_dev_s *up_ad5410initialize(FAR struct spi_dev_s *spi, unsigned int devno);
FAR struct dac_dev_s *up_dacinitialize();
#if defined(__cplusplus)
}
#endif
#endif /* __NUTTX_DAC_H */

View File

@ -17,7 +17,7 @@ The syscall layer provided in this directory serves as the communication
layer from the user-mode application into the kernel-mode RTOS. The
switch from user-mode to kernel-mode is accomplished using software
interrupts (SWIs). SWIs are implemented differently and named differently
by different manufacters but all work essentially the same: A special
by different manufacturers but all work essentially the same: A special
instruction is executed in user-mode that causes a software generated
interrupt. The software generated interrrupt is caught within the kernel
and handle in kernel-mode.
@ -84,7 +84,7 @@ implemented as a simple comma-separated-value file, syscall.csv. Most
spreadsheets programs will accept this format and can be used to maintain
the syscall database.
The format of the CVS file for each line is:
The format of the CSV file for each line is:
Field 1: Function name
Field 2: The header file that contains the function prototype
@ -104,7 +104,7 @@ Each type field has a format as follows:
A similar situation exists for unions. For example, the formal
parameter type union sigval -- You cannot cast a uintptr_t to
a union sigval, but you can cast to the type of one of the union
member types when passing the actua paramter. Similarly, we
member types when passing the actual paramter. Similarly, we
cannot cast a union sigval to a uinptr_t either. Rather, we need
to cast a specific union member fieldname to uintptr_t.
@ -122,7 +122,7 @@ database. Here the following definition is used:
Stub - Another tiny bit of code that executes within the NuttX kernel
that is used to map a software interrupt received by the kernel to
a kernel function call. The stubs receive the marshalled system
a kernel function call. The stubs receive the marshaled system
call data, and perform the actually kernel function call (in
kernel-mode) on behalf of the proxy function.
@ -140,4 +140,4 @@ mksyscall
stubs and proxies is maintained in a comma separated value (CSV) file
in the syscall/ directory. The mksyscall program will accept this CVS
file as input and generate all of the required proxy or stub files as
output. See tools/README.txt for additonal information.
output. See tools/README.txt for additional information.