From 711d1b558f9499fe1e5756db1c1847dabe11c618 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 30 Sep 2013 09:04:21 -0600 Subject: SAMA5: Framework for an touchscreen driver (incomplete) --- nuttx/ChangeLog | 3 + nuttx/arch/arm/src/sama5/chip/sam_adc.h | 3 + nuttx/arch/arm/src/sama5/sam_adc.c | 182 +++++- nuttx/arch/arm/src/sama5/sam_adc.h | 10 +- nuttx/arch/arm/src/sama5/sam_touchscreen.c | 965 +++++++++++++++++++++++++++++ nuttx/arch/arm/src/sama5/sam_touchscreen.h | 117 ++++ 6 files changed, 1251 insertions(+), 29 deletions(-) create mode 100644 nuttx/arch/arm/src/sama5/sam_touchscreen.c create mode 100644 nuttx/arch/arm/src/sama5/sam_touchscreen.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 7e6487bab..ffb114cb6 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -5675,4 +5675,7 @@ * arch/arm/src/sama5/sam_adc.c and .h: Framework for an ADC driver to come (just empty "skeleton" files on initial commit) (2013-9-30). + * arch/arm/src/sama5/sam_touchscreen.h and .h: Framework for a + touchscreen driver (also an empty "skeleton" file on the initial + commit) (2013-9-30). diff --git a/nuttx/arch/arm/src/sama5/chip/sam_adc.h b/nuttx/arch/arm/src/sama5/chip/sam_adc.h index 495d6c0b6..b722533c4 100644 --- a/nuttx/arch/arm/src/sama5/chip/sam_adc.h +++ b/nuttx/arch/arm/src/sama5/chip/sam_adc.h @@ -48,6 +48,9 @@ /**************************************************************************************** * Pre-processor Definitions ****************************************************************************************/ +/* General definitions ******************************************************************/ + +#define SAM_ADC_NCHANNELS 12 /* 12 ADC Channels */ /* ADC register offsets ****************************************************************/ diff --git a/nuttx/arch/arm/src/sama5/sam_adc.c b/nuttx/arch/arm/src/sama5/sam_adc.c index c34ff0ef4..4249a44ab 100644 --- a/nuttx/arch/arm/src/sama5/sam_adc.c +++ b/nuttx/arch/arm/src/sama5/sam_adc.c @@ -74,23 +74,42 @@ struct sam_adc_s { + /* Debug stuff */ + +#ifdef CONFIG_SAMA5_ADC_REGDEBUG + bool wrlast; /* Last was a write */ + uintptr_t addrlast; /* Last address */ + uint32_t vallast; /* Last value */ + int ntimes; /* Number of times */ +#endif }; /**************************************************************************** * Private Function Prototypes ****************************************************************************/ +/* Register operations ******************************************************/ + +#if defined(CONFIG_SAMA5_ADC_REGDEBUG) && defined(CONFIG_DEBUG) +static bool sam_adc_checkreg(struct sam_gmac_s *priv, bool wr, + uint32_t regval, uintptr_t address); +static uint32_t sam_adc_getreg(struct sam_gmac_s *priv, uintptr_t addr); +static void sam_adc_putreg(struct sam_gmac_s *priv, uintptr_t addr, uint32_t val); +#else +# define sam_adc_getreg(priv,addr) getreg32(addr) +# define sam_adc_putreg(priv,addr,val) putreg32(val,addr) +#endif /* ADC interrupt handling */ -static int adc_interrupt(int irq, void *context); +static int sam_adc_interrupt(int irq, void *context); /* 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 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 Data @@ -100,11 +119,11 @@ static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg); 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, + .ao_reset = sam_adc_reset, + .ao_setup = sam_adc_setup, + .ao_shutdown = sam_adc_shutdown, + .ao_rxint = sam_adc_rxint, + .ao_ioctl = sam_adc_ioctl, }; /* ADC internal state */ @@ -126,15 +145,112 @@ static struct adc_dev_s g_adcdev = ****************************************************************************/ /**************************************************************************** - * Name: adc_reset + * Name: sam_adc_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * regval - The value to be written + * address - The address of the register to write to + * + * Returned Value: + * true: This is the first register access of this type. + * flase: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_ADC_REGDEBUG +static bool sam_adc_checkreg(struct sam_gmac_s *priv, bool wr, + uint32_t regval, uintptr_t address) +{ + if (wr == priv->wrlast && /* Same kind of access? */ + regval == priv->vallast && /* Same value? */ + address == priv->addrlast) /* Same address? */ + { + /* Yes, then just keep a count of the number of times we did this. */ + + priv->ntimes++; + return false; + } + else + { + /* Did we do the previous operation more than once? */ + + if (priv->ntimes > 0) + { + /* Yes... show how many times we did it */ + + lldbg("...[Repeats %d times]...\n", priv->ntimes); + } + + /* Save information about the new access */ + + priv->wrlast = wr; + priv->vallast = regval; + priv->addrlast = address; + priv->ntimes = 0; + } + + /* Return true if this is the first time that we have done this operation */ + + return true; +} +#endif + +/**************************************************************************** + * Name: sam_adc_getreg + * + * Description: + * Read any 32-bit register using an absolute address. + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_ADC_REGDEBUG +static uint32_t sam_adc_getreg(struct sam_gmac_s *priv, uintptr_t address) +{ + uint32_t regval = getreg32(address); + + if (sam_adc_checkreg(priv, false, regval, address)) + { + lldbg("%08x->%08x\n", address, regval); + } + + return regval; +} +#endif + +/**************************************************************************** + * Name: sam_adc_putreg + * + * Description: + * Write to any 32-bit register using an absolute address. + * + ****************************************************************************/ + +#ifdef CONFIG_SAMA5_ADC_REGDEBUG +static void sam_adc_putreg(struct sam_gmac_s *priv, uintptr_t address, + uint32_t regval) +{ + if (sam_adc_checkreg(priv, true, regval, address)) + { + lldbg("%08x<-%08x\n", address, regval); + } + + putreg32(regval, address); +} +#endif + +/**************************************************************************** + * Name: sam_adc_reset * * Description: * Reset the ADC device. Called early to initialize the hardware. This - * is called, before adc_setup() and on error conditions. + * is called, before sam_adc_setup() and on error conditions. * ****************************************************************************/ -static void adc_reset(FAR struct adc_dev_s *dev) +static void sam_adc_reset(FAR struct adc_dev_s *dev) { FAR struct sam_adc_s *priv = (FAR struct sam_adc_s *)dev->ad_priv; irqstate_t flags; @@ -147,7 +263,7 @@ static void adc_reset(FAR struct adc_dev_s *dev) } /**************************************************************************** - * Name: adc_setup + * Name: sam_adc_setup * * Description: * Configure the ADC. This method is called the first time that the ADC @@ -157,14 +273,14 @@ static void adc_reset(FAR struct adc_dev_s *dev) * ****************************************************************************/ -static int adc_setup(FAR struct adc_dev_s *dev) +static int sam_adc_setup(FAR struct adc_dev_s *dev) { FAR struct sam_adc_s *priv = (FAR struct sam_adc_s *)dev->ad_priv; int ret; /* Attach the ADC interrupt */ - ret = irq_attach(SAM_IRQ_ADC, adc_interrupt); + ret = irq_attach(SAM_IRQ_ADC, sam_adc_interrupt); if (ret < 0) { adbg("ERROR: Failed to attach IRQ %d: %d\n", SAM_IRQ_ADC, ret); @@ -178,7 +294,7 @@ static int adc_setup(FAR struct adc_dev_s *dev) } /**************************************************************************** - * Name: adc_shutdown + * Name: sam_adc_shutdown * * Description: * Disable the ADC. This method is called when the ADC device is closed. @@ -186,7 +302,7 @@ static int adc_setup(FAR struct adc_dev_s *dev) * ****************************************************************************/ -static void adc_shutdown(FAR struct adc_dev_s *dev) +static void sam_adc_shutdown(FAR struct adc_dev_s *dev) { FAR struct sam_adc_s *priv = (FAR struct sam_adc_s *)dev->ad_priv; @@ -203,14 +319,14 @@ static void adc_shutdown(FAR struct adc_dev_s *dev) } /**************************************************************************** - * Name: adc_rxint + * Name: sam_adc_rxint * * Description: * Call to enable or disable RX interrupts * ****************************************************************************/ -static void adc_rxint(FAR struct adc_dev_s *dev, bool enable) +static void sam_adc_rxint(FAR struct adc_dev_s *dev, bool enable) { FAR struct sam_adc_s *priv = (FAR struct sam_adc_s *)dev->ad_priv; @@ -226,14 +342,14 @@ static void adc_rxint(FAR struct adc_dev_s *dev, bool enable) } /**************************************************************************** - * Name: adc_ioctl + * Name: sam_adc_ioctl * * Description: * All ioctl calls will be routed through this method * ****************************************************************************/ -static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) +static int sam_adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) { /* No ioctl commands supported */ @@ -241,14 +357,14 @@ static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg) } /**************************************************************************** - * Name: adc_interrupt + * Name: sam_adc_interrupt * * Description: * ADC interrupt handler * ****************************************************************************/ -static int adc_interrupt(int irq, void *context) +static int sam_adc_interrupt(int irq, void *context) { FAR struct sam_adc_s *priv = (FAR struct sam_adc_s *)g_adcdev.ad_priv; uint32_t regval; @@ -273,8 +389,22 @@ static int adc_interrupt(int irq, void *context) * ****************************************************************************/ -FAR struct adc_dev_s *sam_adcinitialize(void) +FAR struct adc_dev_s *sam_adc_initialize(void) { + /* Enable the ADC peripheral clock*/ + + sam_adc_enableclk(); + + /* Reset the ADC controller */ + + sam_adc_putreg(priv, SAM_ADC_CR, ADC_CR_SWRST); + + /* Reset Mode Register */ + + sam_adc_putreg(priv, SAM_ADC_MR, 0); + + /* Return a pointer to the device structure */ + return &g_adcdev; } diff --git a/nuttx/arch/arm/src/sama5/sam_adc.h b/nuttx/arch/arm/src/sama5/sam_adc.h index 8a8f7ca51..8309c624c 100644 --- a/nuttx/arch/arm/src/sama5/sam_adc.h +++ b/nuttx/arch/arm/src/sama5/sam_adc.h @@ -1,7 +1,6 @@ /**************************************************************************** * arch/arm/src/sama5/sam_adc.h * - * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * @@ -44,6 +43,8 @@ #include #include "chip/sam_adc.h" +#ifdef CONFIG_SAMA5_ADC + /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -81,13 +82,16 @@ extern "C" * ****************************************************************************/ -#ifdef CONFIG_LPC17_ADC FAR struct adc_dev_s *sam_adcinitialize(void); -#endif + +/**************************************************************************** + * Interfaces exported from the ADC to the touchscreen driver + ****************************************************************************/ #undef EXTERN #ifdef __cplusplus } #endif +#endif /* CONFIG_SAMA5_ADC */ #endif /* __ARCH_ARM_SRC_SAMA5_SAM_ADC_H */ diff --git a/nuttx/arch/arm/src/sama5/sam_touchscreen.c b/nuttx/arch/arm/src/sama5/sam_touchscreen.c new file mode 100644 index 000000000..3dcdac21f --- /dev/null +++ b/nuttx/arch/arm/src/sama5/sam_touchscreen.c @@ -0,0 +1,965 @@ +/**************************************************************************** + * arch/arm/src/sama5/sam_touchsreen.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * + * 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 + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include "sam_touchscreen.h" + +#if defined(CONFIG_SAMA5_ADC) && defined(CONFIG_SAMA5_TOUCHSCREEN) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Driver support ***********************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/* Poll the pen position while the pen is down at this rate (50MS): */ + +#define TSD_WDOG_DELAY ((50 + (MSEC_PER_TICK-1))/ MSEC_PER_TICK) + +/* This is a value for the threshold that guantees a big difference on the + * first pendown (but can't overflow). + */ + +#define INVALID_THRESHOLD 0x1000 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This describes the state of one contact */ + +enum sam_contact_3 +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one ADS7843E sample */ + +struct sam_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum sam_contact_e) */ + bool valid; /* True: x,y contain valid, sampled data */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ +}; + +/* This structure describes the state of one ADS7843E driver instance */ + +struct sam_dev_s +{ + uint8_t nwaiters; /* Number of threads waiting for ADS7843E data */ + uint8_t id; /* Current touch point ID */ + volatile bool penchange; /* An unreported event is buffered */ + uint16_t threshx; /* Thresholding X value */ + uint16_t threshy; /* Thresholding Y value */ + sem_t devsem; /* Manages exclusive access to this structure */ + sem_t waitsem; /* Used to wait for the availability of data */ + + struct work_s work; /* Supports the interrupt handling "bottom half" */ + struct sam_sample_s sample; /* Last sampled touch point data */ + WDOG_ID wdog; /* Poll the position while the pen is down */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Interrupt bottom half logic and data sampling */ + +static void sam_notify(FAR struct sam_dev_s *priv); +static int sam_sample(FAR struct sam_dev_s *priv, + FAR struct sam_sample_s *sample); +static int sam_waitsample(FAR struct sam_dev_s *priv, + FAR struct sam_sample_s *sample); +static void sam_bottomhalf(FAR void *arg); + +/* Character driver methods */ + +static int sam_open(FAR struct file *filep); +static int sam_close(FAR struct file *filep); +static ssize_t sam_read(FAR struct file *filep, FAR char *buffer, + size_t len); +static int sam_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int sam_poll(FAR struct file *filep, struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This the vtable that supports the character driver interface */ + +static const struct file_operations g_tsdops = +{ + sam_open, /* open */ + sam_close, /* close */ + sam_read, /* read */ + 0, /* write */ + 0, /* seek */ + sam_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , sam_poll /* poll */ +#endif +}; + +/* The driver state structure is pre-allocated. */ + +static struct sam_dev_s g_tsd; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_notify + ****************************************************************************/ + +static void sam_notify(FAR struct sam_dev_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the ADS7843E + * is no longer available. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for ADS7843E data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_SAMA5_TSD_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: sam_sample + ****************************************************************************/ + +static int sam_sample(FAR struct sam_dev_s *priv, + FAR struct sam_sample_s *sample) +{ + irqstate_t flags; + int ret = -EAGAIN; + + /* Interrupts me be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + */ + + flags = irqsave(); + + /* Is there new ADS7843E sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct sam_sample_s )); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* Next.. no contact. Increment the ID so that next contact ID + * will be unique. X/Y positions are no longer valid. + */ + + priv->sample.contact = CONTACT_NONE; + priv->sample.valid = false; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* First report -- next report will be a movement */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + irqrestore(flags); + return ret; +} + +/**************************************************************************** + * Name: sam_waitsample + ****************************************************************************/ + +static int sam_waitsample(FAR struct sam_dev_s *priv, + FAR struct sam_sample_s *sample) +{ + irqstate_t flags; + int ret; + + /* Interrupts me be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + * + * In addition, we will also disable pre-emption to prevent other threads + * from getting control while we muck with the semaphores. + */ + + sched_lock(); + flags = irqsave(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->devsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is available. + */ + + while (sam_sample(priv, sample) < 0) + { + /* Wait for a sample data */ + + ivdbg("Waiting..\n"); + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + } + + ivdbg("Sampled\n"); + + /* Re-acquire the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->devsem); + +errout: + /* Then re-enable interrupts. We might get interrupt here and there + * could be a new sample. But no new threads will run because we still + * have pre-emption disabled. + */ + + irqrestore(flags); + + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the touchscreen ADC for some reason, the + * data might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: sam_schedule + ****************************************************************************/ + +static int sam_schedule(FAR struct sam_dev_s *priv) +{ + int ret; + + /* Disable further interrupts. touchscreen ADC interrupts will be re-enabled + * after the worker thread executes. + */ +#warning "Missing logic" + + /* Disable the watchdog timer. It will be re-enabled in the worker thread + * while the pen remains down. + */ + + wd_cancel(priv->wdog); + + /* Transfer processing to the worker thread. Since touchscreen ADC interrupts are + * disabled while the work is pending, no special action should be required + * to protected the work queue. + */ + + DEBUGASSERT(priv->work.worker == NULL); + ret = work_queue(HPWORK, &priv->work, sam_bottomhalf, priv, 0); + if (ret != 0) + { + illdbg("Failed to queue work: %d\n", ret); + } + + return OK; +} + +/**************************************************************************** + * Name: sam_wdog + ****************************************************************************/ + +static void sam_wdog(int argc, uint32_t arg1, ...) +{ + FAR struct sam_dev_s *priv = (FAR struct sam_dev_s *)((uintptr_t)arg1); + (void)sam_schedule(priv); +} + +/**************************************************************************** + * Name: sam_bottomhalf + ****************************************************************************/ + +static void sam_bottomhalf(FAR void *arg) +{ + FAR struct sam_dev_s *priv = (FAR struct sam_dev_s *)arg; + uint16_t x; + uint16_t y; + uint16_t xdiff; + uint16_t ydiff; + bool pendown; + int ret; + + ASSERT(priv != NULL); + + /* Disable the watchdog timer. This is safe because it is started only + * by this function and this function is serialized on the worker thread. + */ + + wd_cancel(priv->wdog); + + /* Get exclusive access to the driver data structure */ + + do + { + ret = sem_wait(&priv->devsem); + + /* This should only fail if the wait was canceled by an signal + * (and the worker thread will receive a lot of signals). + */ + + DEBUGASSERT(ret == OK || errno == EINTR); + } + while (ret < 0); + + /* Check for pen up or down by reading the PENIRQ GPIO. */ +#warning Missing logic + + /* Handle the change from pen down to pen up */ + + if (!pendown) + { + /* The pen is up.. reset thresholding variables. */ + + priv->threshx = INVALID_THRESHOLD; + priv->threshy = INVALID_THRESHOLD; + + /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up + * and already reported; CONTACT_UP == pen up, but not reported) + */ + + if (priv->sample.contact == CONTACT_NONE || + priv->sample.contact == CONTACT_UP) + + { + goto ignored; + } + + /* The pen is up. NOTE: We know from a previous test, that this is a + * loss of contact condition. This will be changed to CONTACT_NONE + * after the loss of contact is sampled. + */ + + priv->sample.contact = CONTACT_UP; + } + + /* It is a pen down event. If the last loss-of-contact event has not been + * processed yet, then we have to ignore the pen down event (or else it will + * look like a drag event) + */ + + else if (priv->sample.contact == CONTACT_UP) + { + /* If we have not yet processed the last pen up event, then we + * cannot handle this pen down event. We will have to discard it. That + * should be okay because we will set the timer to to sample again + * later. + */ + + wd_start(priv->wdog, TSD_WDOG_DELAY, sam_wdog, 1, (uint32_t)priv); + goto ignored; + } + else + { + /* Handle pen down events. First, sample positional values. */ +#warning Missing logic + + /* Perform a thresholding operation so that the results will be more stable. + * If the difference from the last sample is small, then ignore the event. + * REVISIT: Should a large change in pressure also generate a event? + */ + + xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x); + ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y); + + /* Continue to sample the position while the pen is down */ + + wd_start(priv->wdog, TSD_WDOG_DELAY, sam_wdog, 1, (uint32_t)priv); + + /* Check the thresholds. Bail if there is no significant difference */ + + if (xdiff < CONFIG_SAMA5_TSD_THRESHX && ydiff < CONFIG_SAMA5_TSD_THRESHY) + { + /* Little or no change in either direction ... don't report anything. */ + + goto ignored; + } + + /* When we see a big difference, snap to the new x/y thresholds */ + + priv->threshx = x; + priv->threshy = y; + + /* Update the x/y position in the sample data */ + + priv->sample.x = priv->threshx; + priv->sample.y = priv->threshy; + + /* The X/Y positional data is now valid */ + + priv->sample.valid = true; + + /* If this is the first (acknowledged) pen down report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + } + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that new ADS7843E data is available */ + + sam_notify(priv); + + /* Exit, re-enabling ADS7843E interrupts */ + +ignored: + + /* Re-enable the PENIRQ interrupts */ +#warning Missing logic + + /* Re-enable the PENIRQ interrupt at the MCU's interrupt controller */ +#warning Missing logic + + /* Release our lock on the state structure */ + + sem_post(&priv->devsem); +} + +/**************************************************************************** + * Name: sam_open + ****************************************************************************/ + +static int sam_open(FAR struct file *filep) +{ + ivdbg("Opening\n"); + return OK; +} + +/**************************************************************************** + * Name: sam_close + ****************************************************************************/ + +static int sam_close(FAR struct file *filep) +{ + ivdbg("Closing\n"); + return OK; +} + +/**************************************************************************** + * Name: sam_read + ****************************************************************************/ + +static ssize_t sam_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct sam_dev_s *priv; + FAR struct touch_sample_s *report; + struct sam_sample_s sample; + int ret; + + ivdbg("buffer:%p len:%d\n", buffer, len); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct sam_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + idbg("Unsupported read size: %d\n", len); + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = sam_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + ivdbg("Sample data is not available\n"); + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = sam_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + idbg("sam_waitsample: %d\n", ret); + goto errout; + } + } + + /* In any event, we now have sampled ADS7843E data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = sample.id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up. Is the positional data valid? This is important to + * know because the release will be sent to the window based on its + * last positional data. + */ + + if (sample.valid) + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + } + else if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + + ivdbg(" id: %d\n", report->point[0].id); + ivdbg(" flags: %02x\n", report->point[0].flags); + ivdbg(" x: %d\n", report->point[0].x); + ivdbg(" y: %d\n", report->point[0].y); + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->devsem); + ivdbg("Returning: %d\n", ret); + return ret; +} + +/**************************************************************************** + * Name:sam_ioctl + ****************************************************************************/ + +static int sam_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct sam_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct sam_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: sam_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int sam_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct sam_dev_s *priv; + int ret = OK; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct sam_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_SAMA5_TSD_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_SAMA5_TSD_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + sam_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->devsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_tsd_register + * + * Description: + * Configure the SAMA5 touchscreen. This will register the driver as + * /dev/inputN where N is the minor device number + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int sam_tsd_register(int minor) +{ + FAR struct sam_dev_s *priv = &g_tsd; + char devname[DEV_NAMELEN]; + int ret; + + ivdbg("minor: %d\n", minor); + + /* Debug-only sanity checks */ + + DEBUGASSERT(minor >= 0 && minor < 100); + + /* Initialize the touchscreen device driver instance */ + + memset(priv, 0, sizeof(struct sam_dev_s)); + priv->wdog = wd_create(); /* Create a watchdog timer */ + priv->threshx = INVALID_THRESHOLD; /* Initialize thresholding logic */ + priv->threshy = INVALID_THRESHOLD; /* Initialize thresholding logic */ + + sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ + sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ + + /* Make sure that interrupts are disabled and clear any pending interrupts */ +#warning Missing logic + + /* Attach the interrupt handler */ +#warning Missing logic + + /* Enable the PEN IRQ */ +#warning Missing logic + + /* Register the device as an input device */ + + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ivdbg("Registering %s\n", devname); + + ret = register_driver(devname, &g_tsdops, 0666, priv); + if (ret < 0) + { + idbg("register_driver() failed: %d\n", ret); + goto errout_with_priv; + } + + /* Schedule work to perform the initial sampling and to set the data + * availability conditions. + */ + + ret = work_queue(HPWORK, &priv->work, sam_bottomhalf, priv, 0); + if (ret != 0) + { + idbg("Failed to queue work: %d\n", ret); + goto errout_with_priv; + } + + /* And return success */ + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); + sem_destroy(&priv->waitsem); + return ret; +} + +/**************************************************************************** + * Name: sam_tsd_interrupt + * + * Description: + * Handles ADC interrupts associated with touchscreen channels + * + * Input parmeters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tsd_interrupt(void) +{ + FAR struct sam_dev_s *priv = &g_tsd; + int ret; + + /* Schedule sampling to occur on the worker thread */ + + ret = sam_schedule(priv); + + /* Clear any pending interrupts and return success */ +#warning Missing logic + return ret; +} + +#endif /* CONFIG_SAMA5_ADC && CONFIG_SAMA5_TOUCHSCREEN */ diff --git a/nuttx/arch/arm/src/sama5/sam_touchscreen.h b/nuttx/arch/arm/src/sama5/sam_touchscreen.h new file mode 100644 index 000000000..8a68f2206 --- /dev/null +++ b/nuttx/arch/arm/src/sama5/sam_touchscreen.h @@ -0,0 +1,117 @@ +/**************************************************************************** + * arch/arm/src/sama5/sam_adc.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_SAMA5_SAM_ADC_H +#define __ARCH_ARM_SRC_SAMA5_SAM_ADC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "chip/sam_adc.h" + +#if defined(CONFIG_SAMA5_ADC) && defined(CONFIG_SAMA5_TOUCHSCREEN) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_tsd_register + * + * Description: + * Configure the SAMA5 touchscreen. This will register the driver as + * /dev/inputN where N is the minor device number + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int sam_tsd_register(int minor); + +/**************************************************************************** + * Interfaces exported from the touchscreen to the ADC driver + ****************************************************************************/ +/**************************************************************************** + * Name: sam_tsd_interrupt + * + * Description: + * Handles ADC interrupts associated with touchscreen channels + * + * Input parmeters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tsd_interrupt(void); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_SAMA5_ADC && CONFIG_SAMA5_TOUCHSCREEN */ +#endif /* __ARCH_ARM_SRC_SAMA5_SAM_ADC_H */ -- cgit v1.2.3