From 695f514e3e873873984ab83e1193bc9d0b4e4985 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 31 Jul 2011 14:53:57 +0000 Subject: Forgot to add file in last checkin git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3832 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/drivers/input/tsc2007.c | 24 +++--- nuttx/include/nuttx/input/touchscreen.h | 136 ++++++++++++++++++++++++++++++++ nuttx/include/nuttx/input/tsc2007.h | 4 +- 3 files changed, 153 insertions(+), 11 deletions(-) create mode 100644 nuttx/include/nuttx/input/touchscreen.h (limited to 'nuttx') diff --git a/nuttx/drivers/input/tsc2007.c b/nuttx/drivers/input/tsc2007.c index e79bb3568..4a5082f08 100644 --- a/nuttx/drivers/input/tsc2007.c +++ b/nuttx/drivers/input/tsc2007.c @@ -84,7 +84,7 @@ #undef CONFIG_TSC2007_REFCNT /* Driver support ***********************************************************/ -/* This format is used to construct the /dev/skel[n] device driver path. It +/* 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. */ @@ -99,16 +99,17 @@ enum tsc2007_contact_3 { - CONTACT_NONE = 0, /* No contact */ - CONTACT_DOWN, /* First contact */ - CONTACT_MOVE, /* Same contact, possibly different position */ - CONTACT_UP, /* Contact lost */ + 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 TSC2007 sample */ struct tsc2007_sample_s { + uint8_t id; /* Sampled touch point ID */ uint8_t contact; /* Contact state (see enum tsc2007_contact_e) */ uint16_t x; /* Measured X position */ uint16_t y; /* Measured Y position */ @@ -279,7 +280,7 @@ static int tsc2007_sample(FAR struct tsc2007_dev_s *priv, if (sample->contact == CONTACT_UP) { - /* Next.. no contract. Increment the ID so that next contact will be unique */ + /* Next.. no contract. Increment the ID so that next contact ID will be unique */ priv->sample.contact = CONTACT_NONE; priv->id++; @@ -621,7 +622,10 @@ static void tsc2007_worker(FAR void *arg) priv->sample.contact = CONTACT_UP; } - + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; priv->penchange = true; /* Notify any waiters that nes TSC2007 data is available */ @@ -871,19 +875,19 @@ static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer, size_t len { /* Pen is now up */ - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID |TOUCH_PRESSURE_VALID; + 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 |TOUCH_PRESSURE_VALID; + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; } else /* if (sample->contact == CONTACT_MOVE) */ { /* Movement of the same contact */ - report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID |TOUCH_PRESSURE_VALID; + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; } ret = SIZEOF_TOUCH_SAMPLE_S(1); diff --git a/nuttx/include/nuttx/input/touchscreen.h b/nuttx/include/nuttx/input/touchscreen.h new file mode 100644 index 000000000..cd5e96bae --- /dev/null +++ b/nuttx/include/nuttx/input/touchscreen.h @@ -0,0 +1,136 @@ +/************************************************************************************ + * include/nuttx/input/touchscreen.h + * + * Copyright (C) 2011 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. + * + ************************************************************************************/ + +/* The TOUCHSCREEN driver exports a standard character driver interface. By + * convention, the touchscreen driver is registers as an input device at + * /dev/inputN where N uniquely identifies the driver instance. + * + * This header file documents the generic interface that all NuttX + * touchscreen devices must conform. It adds standards and conventions on + * top of the standard character driver interface. + */ + +#ifndef __INCLUDE_NUTTX_INPUT_TOUCHSCREEN_H +#define __INCLUDE_NUTTX_INPUT_TOUCHSCREEN_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#ifdef CONFIG_INPUT + +/************************************************************************************ + * Pre-Processor Definitions + ************************************************************************************/ +/* IOCTL Commands *******************************************************************/ + +#define TSIOC_SETCALIB _TSIOC(0x0001) /* arg: Pointer to int calibration value */ +#define TSIOC_GETCALIB _TSIOC(0x0002) /* arg: Pointer to int calibration value */ +#define TSIOC_SETFREQUENCY _TSIOC(0x0003) /* arg: Pointer to uint32_t frequency value */ +#define TSIOC_GETFREQUENCY _TSIOC(0x0004) /* arg: Pointer to uint32_t frequency value */ + +/* These definitions provide the meaning of all of the bits that may be + * reported in the struct touch_point_s flags. + */ + +#define TOUCH_DOWN (1 << 0) /* A new touch contact is establed */ +#define TOUCH_MOVE (1 << 1) /* Movement occurred with previously reported contact */ +#define TOUCH_UP (1 << 2) /* The touch contact was lost */ +#define TOUCH_ID_VALID (1 << 3) /* Touch ID is uncertain */ +#define TOUCH_POS_VALID (1 << 4) /* Hardware provided a valid X/Y position */ +#define TOUCH_PRESSURE_VALID (1 << 5) /* Hardware provided a valid pressure */ +#define TOUCH_SIZE_VALID (1 << 6) /* Hardware provided a valid H/W contact size */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* This structure contains information about a single touch point. + * Positional units are device specific. + */ + +struct touch_point_s +{ + uint8_t id; /* Unique identifies contact; Same in all reports for the contact */ + uint8_t flags; /* See TOUCH_* definitions above */ + int16_t x; /* X coordinate of the touch point (uncalibrated) */ + int16_t y; /* Y coordinate of the touch point (uncalibrated) */ + int16_t h; /* Height of touch point (uncalibrated) */ + int16_t w; /* Width of touch point (uncalibrated) */ + uint16_t pressure; /* Touch pressure */ +}; + +/* The typical touchscreen driver is a read-only, input character device driver. + * the driver write() method is not supported and any attempt to open the + * driver in any mode other than read-only will fail. + * + * Data read from the touchscreen device consists only of touch events and + * touch sample data. This is reflected by struct touch_sample_s. This + * structure is returned by either the driver read method. + * + * On some devices, multiple touchpoints may be supported. So this top level + * data structure is a struct touch_sample_s that "contains" a set of touch + * points. Each touch point is managed individually using an ID that identifies + * a touch from first contact until the end of the contact. + */ + +struct touch_sample_s +{ + int npoints; /* The number of touch points in point[] */ + struct touch_point_s point[1]; /* Actual dimension is npoints */ +}; +#define SIZEOF_TOUCH_SAMPLE_S(n) (sizeof(struct touch_sample_s) + ((n)-1)*sizeof(struct touch_point_s)) + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_INPUT */ +#endif /* __INCLUDE_NUTTX_INPUT_TOUCHSCREEN_H */ diff --git a/nuttx/include/nuttx/input/tsc2007.h b/nuttx/include/nuttx/input/tsc2007.h index 449b46b22..d5699c435 100644 --- a/nuttx/include/nuttx/input/tsc2007.h +++ b/nuttx/include/nuttx/input/tsc2007.h @@ -113,7 +113,9 @@ struct tsc2007_config_s /* IRQ/GPIO access callbacks. These operations all hidden behind * callbacks to isolate the TSC2007 driver from differences in GPIO - * interrupt handling by varying boards and MCUs. + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. * * attach - Attach the TSC2007 interrupt handler to the GPIO interrupt * enable - Enable or disable the GPIO interrupt -- cgit v1.2.3