From 105f5fbfcbbf411deefddac8039ccb3b03477609 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 10 Feb 2014 10:14:22 -0600 Subject: Add a mouse interface that is similar to the touchscreen interface except that it can handle multple buttons and continuously reports positional data so that it can control a cursor --- apps/ChangeLog.txt | 3 +- apps/examples/README.txt | 14 +- apps/examples/touchscreen/Kconfig | 7 + apps/examples/touchscreen/tc.h | 14 +- apps/examples/touchscreen/tc_main.c | 51 +- nuttx/ChangeLog | 6 + nuttx/TODO | 24 +- nuttx/configs/olimex-lpc1766stk/hidmouse/defconfig | 2 + nuttx/configs/olimex-lpc1766stk/hidmouse/setenv.sh | 7 +- nuttx/drivers/usbhost/Kconfig | 20 + nuttx/drivers/usbhost/usbhost_hidmouse.c | 583 +++++++++++++-------- nuttx/include/nuttx/input/mouse.h | 102 ++++ nuttx/include/nuttx/input/touchscreen.h | 2 +- nuttx/include/nuttx/usb/hid.h | 1 + 14 files changed, 588 insertions(+), 248 deletions(-) create mode 100644 nuttx/include/nuttx/input/mouse.h diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 8e5cb03a8..db1afab2c 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -818,4 +818,5 @@ an option and can be replaces with the EMACX-like CLE (about 2KB) (2014-02-02). * Several changes to restore Windows native build (2014-2-7) - + * apps/examples/touchscreen: Can not be configured to work with a mouse + interface as well (2014-2-10). diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 78b6d1bbf..c64e62da0 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -1621,13 +1621,15 @@ examples/touchscreen corresponds to touchscreen device /dev/inputN. Note this value must with CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH. Default 0. CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH - The path to the touchscreen - device. This must be consistent with CONFIG_EXAMPLES_TOUCHSCREEN_MINOR. - Default: "/dev/input0" + device. This must be consistent with CONFIG_EXAMPLES_TOUCHSCREEN_MINOR. + Default: "/dev/input0" CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES - If CONFIG_NSH_BUILTIN_APPS - is defined, then the number of samples is provided on the command line - and this value is ignored. Otherwise, this number of samples is - collected and the program terminates. Default: Samples are collected - indefinitely. + is defined, then the number of samples is provided on the command line + and this value is ignored. Otherwise, this number of samples is + collected and the program terminates. Default: Samples are collected + indefinitely. + CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE - The touchscreen test can also be + configured to work with a mouse driver by setting this option. The following additional configurations must be set in the NuttX configuration file: diff --git a/apps/examples/touchscreen/Kconfig b/apps/examples/touchscreen/Kconfig index f493ea893..5e7739c35 100644 --- a/apps/examples/touchscreen/Kconfig +++ b/apps/examples/touchscreen/Kconfig @@ -36,4 +36,11 @@ config EXAMPLES_TOUCHSCREEN_NSAMPLES Otherwise, this number of samples is collected and the program terminates. Default: Zero (Samples are collected indefinitely). +config EXAMPLES_TOUCHSCREEN_MOUSE + bool "Mouse interface" + default n + ---help--- + The touchscreen test can also be configured to work with a mouse + driver by setting this option. + endif diff --git a/apps/examples/touchscreen/tc.h b/apps/examples/touchscreen/tc.h index 1757fe0c8..2a8dde203 100644 --- a/apps/examples/touchscreen/tc.h +++ b/apps/examples/touchscreen/tc.h @@ -59,6 +59,8 @@ * and this value is ignored. Otherwise, this number of samples is * collected and the program terminates. Default: Zero (Samples are collected * indefinitely). + * CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE - The touchscreen test can also be + * configured to work with a mouse driver by setting this option. */ #ifndef CONFIG_INPUT @@ -68,13 +70,21 @@ #ifndef CONFIG_EXAMPLES_TOUCHSCREEN_MINOR # undef CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH # define CONFIG_EXAMPLES_TOUCHSCREEN_MINOR 0 -# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/input0" +# ifdef CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE +# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/mouse0" +# else +# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/input0" +# endif #endif #ifndef CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH # undef CONFIG_EXAMPLES_TOUCHSCREEN_MINOR # define CONFIG_EXAMPLES_TOUCHSCREEN_MINOR 0 -# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/input0" +# ifdef CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE +# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/mouse0" +# else +# define CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH "/dev/input0" +# endif #endif #ifndef CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES diff --git a/apps/examples/touchscreen/tc_main.c b/apps/examples/touchscreen/tc_main.c index d786a6775..13a192a0d 100644 --- a/apps/examples/touchscreen/tc_main.c +++ b/apps/examples/touchscreen/tc_main.c @@ -1,7 +1,7 @@ /**************************************************************************** * examples/touchscreen/tc_main.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -48,6 +48,10 @@ #include #include +#ifdef CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE +# include +#endif + #include #include "tc.h" @@ -86,7 +90,11 @@ int tc_main(int argc, char *argv[]) { +#ifdef CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE + struct mouse_report_s sample; +#else struct touch_sample_s sample; +#endif ssize_t nbytes; #if defined(CONFIG_NSH_BUILTIN_APPS) || CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES > 0 long nsamples; @@ -153,6 +161,44 @@ int tc_main(int argc, char *argv[]) msgflush(); +#ifdef CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE + /* Read one sample */ + + ivdbg("Reading...\n"); + nbytes = read(fd, &sample, sizeof(struct mouse_report_s)); + ivdbg("Bytes read: %d\n", nbytes); + + /* Handle unexpected return values */ + + if (nbytes < 0) + { + errval = errno; + if (errval != EINTR) + { + message("tc_main: read %s failed: %d\n", + CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH, errval); + errval = 3; + goto errout_with_dev; + } + + message("tc_main: Interrupted read...\n"); + } + else if (nbytes != sizeof(struct mouse_report_s)) + { + message("tc_main: Unexpected read size=%d, expected=%d, Ignoring\n", + nbytes, sizeof(struct mouse_report_s)); + } + + /* Print the sample data on successful return */ + + else + { + message("Sample :\n"); + message(" buttons : %02x\n", sample.buttons); + message(" x : %d\n", sample.x); + message(" y : %d\n", sample.y); + } +#else /* Read one sample */ ivdbg("Reading...\n"); @@ -177,7 +223,7 @@ int tc_main(int argc, char *argv[]) else if (nbytes != sizeof(struct touch_sample_s)) { message("tc_main: Unexpected read size=%d, expected=%d, Ignoring\n", - nbytes, sizeof(struct touch_sample_s)); + nbytes, sizeof(struct touch_sample_s)); } /* Print the sample data on successful return */ @@ -195,6 +241,7 @@ int tc_main(int argc, char *argv[]) message(" w : %d\n", sample.point[0].w); message(" pressure : %d\n", sample.point[0].pressure); } +#endif } errout_with_dev: diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 20dd214c6..41a32ca61 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -6558,3 +6558,9 @@ mouse with no cursor? The HID mouse currently emulates a touchscreen driver. That would work in the long run for several reasons (see the top-level TODO list for details) (2014-2-9). + * include/nuttx/input/mouse.h and drivers/usbhost/usbhost_hidmouse.c: + Defined a mouse interface that is very similar to a touchscreen + interface, but allows reporting of all mouse buttons. Also, unlike + touchscreen drivers, mouse drivers need to report positional data + with no button is pressed so that the mouse position can drive a + cursor (2014-2-10). diff --git a/nuttx/TODO b/nuttx/TODO index 95374c190..b780cca39 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 14, 2014) +NuttX TODO List (Last updated January 10, 2014) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -16,7 +16,7 @@ nuttx/ (4) C++ Support (6) Binary loaders (binfmt/) (17) Network (net/, drivers/net) - (5) USB (drivers/usbdev, drivers/usbhost) + (4) USB (drivers/usbdev, drivers/usbhost) (11) Libraries (libc/, ) (12) File system/Generic drivers (fs/, drivers/) (5) Graphics subystem (graphics/) @@ -1025,26 +1025,6 @@ o USB (drivers/usbdev, drivers/usbhost) Status: Open Priority: Low/Unknown. This is a feature enhancement. - Title: USB HID MOUSE LOGIC INCOMPLETE - Description: There is a working USB HID mouse driver at drivers/usbhost/usbhost_hidmouse.c. - Although the driver works, it is not useful. Currently it - emulates a touchscreen and uses the touchscreen interface. - The problems are: - - - With no hardware cursor, a mouse is not usable because - you cannot tell where the mouse is positioned. - - Since it uses the touchscreen interface, there is no way - to report left or center button activity or to report - the wheel position. - - And, for the same reason, positional data is not reported - when the left button is not pressed (i.e., like touching - the screen). Data would have to be reported when no - buttons are pressed in order to driver a hardware cursor. - - There is a test configuration at configs/olimex-lpc1766stk/hidmouse. - Status: Open - Priority: Low, unless you need a usable HID mouse now. - o Libraries (libc/) ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/configs/olimex-lpc1766stk/hidmouse/defconfig b/nuttx/configs/olimex-lpc1766stk/hidmouse/defconfig index 4f8e2cb7a..a5e376f5e 100644 --- a/nuttx/configs/olimex-lpc1766stk/hidmouse/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/hidmouse/defconfig @@ -407,6 +407,7 @@ CONFIG_USBHOST_NPREALLOC=4 # CONFIG_USBHOST_MSC is not set # CONFIG_USBHOST_HIDKBD is not set CONFIG_USBHOST_HIDMOUSE=y +# CONFIG_HIDMOUSE_TSCIF is not set CONFIG_HIDMOUSE_DEFPRIO=50 CONFIG_HIDMOUSE_STACKSIZE=1024 CONFIG_HIDMOUSE_BUFSIZE=64 @@ -646,6 +647,7 @@ CONFIG_EXAMPLES_NSH=y CONFIG_EXAMPLES_TOUCHSCREEN=y CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0 CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/mouse0" +CONFIG_EXAMPLES_TOUCHSCREEN_MOUSE=y # CONFIG_EXAMPLES_UDP is not set # CONFIG_EXAMPLES_DISCOVER is not set # CONFIG_EXAMPLES_UIP is not set diff --git a/nuttx/configs/olimex-lpc1766stk/hidmouse/setenv.sh b/nuttx/configs/olimex-lpc1766stk/hidmouse/setenv.sh index fa406ecce..623201670 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidmouse/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/hidmouse/setenv.sh @@ -57,7 +57,10 @@ export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_Code # toolchain. #export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -# Add the path to the toolchain to the PATH varialble -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" +# The Olimex-lpc1766stk/tools directory +export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" + +# Add the path to the toolchain and tools directory to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}" echo "PATH : ${PATH}" diff --git a/nuttx/drivers/usbhost/Kconfig b/nuttx/drivers/usbhost/Kconfig index 080109ea2..5fe08bdc8 100644 --- a/nuttx/drivers/usbhost/Kconfig +++ b/nuttx/drivers/usbhost/Kconfig @@ -126,6 +126,22 @@ config USBHOST_HIDMOUSE if USBHOST_HIDMOUSE +config HIDMOUSE_TSCIF + bool "Touchscreen Emulation" + default n + ---help--- + Normally, the HID mouse driver uses the mouse report structure + defined in include/nuttx/input/mouse.h. The mouse driver can, + however, be configured to use the touchscreen interface defined in + include/nuttx/input/touchcreen.h. If the touch screen interface is + used, only support for the left button will be provided. + + NOTE: Unlike touchscreen drivers, mouse drivers will report + position data even when the "pen is up", i.e., when no buttons are + pressed. This behavior is necessary to provide the positional data + would would be needed to drive a cursor. Without a cursor of some + kind, the mouse is not very useful. So this option may not be useful. + config HIDMOUSE_DEFPRIO int "Polling Thread Priority" default 50 @@ -211,6 +227,8 @@ config HIDMOUSE_XTHRESH ---help--- New mouse positions will only be reported when the X or Y data changes by these thresholds. This trades reduces data rate for some loss in dragging accuracy. + Both X and Y axis thresholding can be disabled by setting this value to zero. + Default: 12 config HIDMOUSE_THRESHY @@ -219,6 +237,8 @@ config HIDMOUSE_THRESHY ---help--- New touch positions will only be reported when the X or Y data changes by these thresholds. This trades reduces data rate for some loss in dragging accuracy. + Both X and Y axis thresholding can be disabled by setting this value to zero. + Default: 12 endif diff --git a/nuttx/drivers/usbhost/usbhost_hidmouse.c b/nuttx/drivers/usbhost/usbhost_hidmouse.c index 2a37ced22..2ceccccac 100644 --- a/nuttx/drivers/usbhost/usbhost_hidmouse.c +++ b/nuttx/drivers/usbhost/usbhost_hidmouse.c @@ -63,7 +63,11 @@ #include #include -#include +#ifdef CONFIG_HIDMOUSE_TSCIF +# include +#else +# include +#endif /* Don't compile if prerequisites are not met */ @@ -146,8 +150,13 @@ * defined here so that it will be used consistently in all places. */ -#define DEV_FORMAT "/dev/mouse%d" -#define DEV_NAMELEN 13 +#ifdef CONFIG_HIDMOUSE_TSCIF +# define DEV_FORMAT "/dev/input%d" +# define DEV_NAMELEN 13 +#else +# define DEV_FORMAT "/dev/mouse%d" +# define DEV_NAMELEN 13 +#endif /* Used in usbhost_cfgdesc() */ @@ -178,6 +187,7 @@ * Private Types ****************************************************************************/ +#ifdef CONFIG_HIDMOUSE_TSCIF /* This describes the state of one event */ enum mouse_button_e @@ -201,6 +211,17 @@ struct mouse_sample_s uint16_t y; /* Measured Y position */ }; +#else +/* This structure summarizes the mouse report */ + +struct mouse_sample_s +{ + uint8_t buttons; /* Button state (see MOUSE_BUTTON_* definitions) */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ +}; +#endif + /* This structure contains the internal, private state of the USB host * mouse storage class. */ @@ -223,7 +244,11 @@ struct usbhost_state_s volatile bool valid; /* TRUE: New sample data is available */ uint8_t devno; /* Minor number in the /dev/mouse[n] device */ uint8_t nwaiters; /* Number of threads waiting for mouse data */ +#ifdef CONFIG_HIDMOUSE_TSCIF uint8_t id; /* Current "touch" point ID */ +#else + uint8_t buttons; /* Current state of the mouse buttons */ +#endif int16_t crefs; /* Reference count on the driver instance */ sem_t exclsem; /* Used to maintain mutual exclusive access */ sem_t waitsem; /* Used to wait for mouse data */ @@ -280,6 +305,14 @@ static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *dev static void usbhost_destroy(FAR void *arg); static void usbhost_notify(FAR struct usbhost_state_s *priv); +static void usbhost_position(FAR struct usbhost_state_s *priv, + FAR struct usbhid_mousereport_s *rpt); +#ifdef CONFIG_HIDMOUSE_TSCIF +static bool usbhost_touchscreen(FAR struct usbhost_state_s *priv, + FAR struct usbhid_mousereport_s *rpt); +#endif +static bool usbhost_threshold(FAR struct usbhost_state_s *priv, + b16_t xpos, b16_t ypos); static int usbhost_mouse_poll(int argc, char *argv[]); static int usbhost_sample(FAR struct usbhost_state_s *priv, FAR struct mouse_sample_s *sample); @@ -647,6 +680,275 @@ static void usbhost_notify(FAR struct usbhost_state_s *priv) #endif } +/**************************************************************************** + * Name: usbhost_position + * + * Description: + * Integrate the current mouse displacement to get the updated mouse + * position. + * + * Input Parameters: + * priv - A reference to the mouse state structure. + * rpt - The new mouse report data. + * + * Returned Value: + * None. + * + ****************************************************************************/ + +static void usbhost_position(FAR struct usbhost_state_s *priv, + FAR struct usbhid_mousereport_s *rpt) +{ + int32_t xdisp; + int32_t ydisp; + b16_t xpos; + b16_t ypos; + + /* The following logic performs an constant integration of the mouse X/Y + * displacement data in order to keep the X/Y positional data current. + */ + + /* Sign extend the mouse X position. We do this manually because some + * architectures do not support signed character types and some compilers + * may be configured to treat all characters as unsigned. + */ + +#ifdef CONFIG_HIDMOUSE_SWAPXY + xdisp = rpt->ydisp; + if ((rpt->ydisp & 0x80) != 0) + { + xdisp |= 0xffffff00; + } +#else + xdisp = rpt->xdisp; + if ((rpt->xdisp & 0x80) != 0) + { + xdisp |= 0xffffff00; + } +#endif + + /* Scale the X displacement and determine the new X position */ + + xpos = priv->xaccum + CONFIG_HIDMOUSE_XSCALE * xdisp; + + /* Make sure that the scaled X position does not become negative or exceed + * the maximum. + */ + + if (xpos > HIDMOUSE_XMAX_B16) + { + xpos = HIDMOUSE_XMAX_B16; + } + else if (xpos < 0) + { + xpos = 0; + } + + /* Save the updated X position */ + + priv->xaccum = xpos; + + /* Do the same for the Y position */ + +#ifdef CONFIG_HIDMOUSE_SWAPXY + ydisp = rpt->xdisp; + if ((rpt->xdisp & 0x80) != 0) + { + ydisp |= 0xffffff00; + } +#else + ydisp = rpt->ydisp; + if ((rpt->ydisp & 0x80) != 0) + { + ydisp |= 0xffffff00; + } +#endif + + ypos = priv->yaccum + CONFIG_HIDMOUSE_YSCALE * ydisp; + + if (ypos > HIDMOUSE_YMAX_B16) + { + ypos = HIDMOUSE_YMAX_B16; + } + else if (ypos < 0) + { + ypos = 0; + } + + priv->yaccum = ypos; +} + +/**************************************************************************** + * Name: usbhost_touchscreen + * + * Description: + * Execute the (emulated) touchscreen press/drag/release state machine. + * + * Input Parameters: + * priv - A reference to the mouse state structure. + * rpt - The new mouse report data. + * + * Returned Value: + * False if the mouse data should not be reported. + * + ****************************************************************************/ + +#ifdef CONFIG_HIDMOUSE_TSCIF +static bool usbhost_touchscreen(FAR struct usbhost_state_s *priv, + FAR struct usbhid_mousereport_s *rpt) +{ + /* Check if the left button is pressed */ + + if ((rpt->buttons & USBHID_MOUSEIN_BUTTON1) == 0) + { + /* The left button is not pressed.. reset thresholding variables. */ + + priv->xlast = INVALID_POSITION_B16; + priv->ylast = INVALID_POSITION_B16; + + /* Ignore the report if the button was not pressed last time + * (BUTTON_NONE == button released and already reported; + * BUTTON_RELEASED == button released, but not yet reported) + */ + + if (priv->sample.event == BUTTON_NONE || + priv->sample.event == BUTTON_RELEASED) + { + return false; + } + + /* The left button has just been released. NOTE: We know from a + * previous test, that this is a button release condition. This will + * be changed to BUTTON_NONE after the button release has been + * reported. + */ + + priv->sample.event = BUTTON_RELEASED; + } + + /* It is a left button press event. If the last button release event has + * not been processed yet, then we have to ignore the button press event + * (or else it will look like a drag event) + */ + + else if (priv->sample.event == BUTTON_RELEASED) + { + /* If we have not yet processed the button release event, then we + * cannot handle this button press event. We will have to discard the + * data and wait for the next sample. + */ + + return false; + } + + /* Handle left-button down events */ + + else + { + /* If this is the first left button press report, then report that + * event. If event == BUTTON_PRESSED, it will be set to set to + * BUTTON_MOVE after the button press is first sampled. + */ + + if (priv->sample.event != BUTTON_MOVE) + { + /* First button press */ + + priv->sample.event = BUTTON_PRESSED; + } + + /* Otherwise, 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. + */ + + else if (!usbhost_threshold(priv, priv->xaccum, priv->yaccum)) + { + return false; + } + } + + /* We get here: + * + * (1) When the left button is just release, + * (2) When the left button is first pressed, or + * (3) When the left button is held and some significant 'dragging' + * has occurred. + */ + + return true; +} +#endif + +/**************************************************************************** + * Name: usbhost_threshold + * + * Description: + * Check if the current mouse position differs from the previous mouse + * position by a threshold amount. + * + * Input Parameters: + * priv - A reference to the mouse state structure. + * xpos - The current mouse X position + * ypos - The current mouse Y position + * + * Returned Value: + * True if the mouse position is significantly different from the last + * reported mouse position. + * + ****************************************************************************/ + +static bool usbhost_threshold(FAR struct usbhost_state_s *priv, + b16_t xpos, b16_t ypos) +{ +#if CONFIG_HIDMOUSE_XTHRESH > 0 && CONFIG_HIDMOUSE_YTHRESH > 0 + b16_t xdiff; + b16_t ydiff; + + /* Get the difference in the X position from the last report */ + + if (xpos > priv->xlast) + { + xdiff = xpos - priv->xlast; + } + else + { + xdiff = priv->xlast - xpos; + } + + /* Check if the X difference exceeds the report threshold */ + + if (xdiff >= HIDMOUSE_XTHRESH_B16) + { + return true; + } + + /* Little or no change in the X direction, check the Y direction. */ + + if (ypos > priv->ylast) + { + ydiff = ypos - priv->ylast; + } + else + { + ydiff = priv->ylast - ypos; + } + + if (ydiff >= HIDMOUSE_YTHRESH_B16) + { + return true; + } + + /* Little or no change in either direction... don't report anything. */ + + return false; +#else + /* No thresholding */ + + return true; +#endif +} + /**************************************************************************** * Name: usbhost_mouse_poll * @@ -664,17 +966,15 @@ static void usbhost_notify(FAR struct usbhost_state_s *priv) static int usbhost_mouse_poll(int argc, char *argv[]) { FAR struct usbhost_state_s *priv; - int32_t xdisp; - int32_t ydisp; - b16_t xpos; - b16_t ypos; - b16_t xdiff; - b16_t ydiff; + FAR struct usbhid_mousereport_s *rpt; +#ifndef CONFIG_HIDMOUSE_TSCIF + uint8_t buttons; +#endif #if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE) - unsigned int npolls = 0; + unsigned int npolls = 0; #endif - unsigned int nerrors = 0; - int ret; + unsigned int nerrors = 0; + int ret; uvdbg("Started\n"); @@ -731,233 +1031,73 @@ static int usbhost_mouse_poll(int argc, char *argv[]) else if (priv->open) { - FAR struct usbhid_mousereport_s *rpt; - /* Get exclusive access to the mouse state data */ usbhost_takesem(&priv->exclsem); /* Get the HID mouse report */ - rpt = (struct usbhid_mousereport_s *)priv->tbuffer; + rpt = (FAR struct usbhid_mousereport_s *)priv->tbuffer; - /* The following logic performs an constant integration of the - * mouse X/Y displacement data in order to keep the X/Y positional - * data current. - */ + /* Get the updated mouse position */ - /* Sign extend the mouse X position. We do this manually because - * some architectures do not support signed character types and - * some compilers may be configured to treat all characters as - * unsigned. - */ + usbhost_position(priv, rpt); -#ifdef CONFIG_HIDMOUSE_SWAPXY - xdisp = rpt->ydisp; - if ((rpt->ydisp & 0x80) != 0) - { - xdisp |= 0xffffff00; - } -#else - xdisp = rpt->xdisp; - if ((rpt->xdisp & 0x80) != 0) - { - xdisp |= 0xffffff00; - } -#endif - - /* Scale the X displacement and determine the new X position */ - - xpos = priv->xaccum + CONFIG_HIDMOUSE_XSCALE * xdisp; +#ifdef CONFIG_HIDMOUSE_TSCIF + /* Execute the touchscreen state machine */ - /* Make sure that the scaled X position does not become negative - * or exceed the maximum. + if (usbhost_touchscreen(priv, rpt)) +#else + /* Check if any buttons have changed. If so, then report the + * new mouse data. + * + * If not, then 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. */ - if (xpos > HIDMOUSE_XMAX_B16) - { - xpos = HIDMOUSE_XMAX_B16; - } - else if (xpos < 0) - { - xpos = 0; - } - - /* Save the updated X position */ - - priv->xaccum = xpos; - - /* Do the same for the Y position */ - -#ifdef CONFIG_HIDMOUSE_SWAPXY - ydisp = rpt->xdisp; - if ((rpt->xdisp & 0x80) != 0) - { - ydisp |= 0xffffff00; - } -#else - ydisp = rpt->ydisp; - if ((rpt->ydisp & 0x80) != 0) - { - ydisp |= 0xffffff00; - } + buttons = rpt->buttons & USBHID_MOUSEIN_BUTTON_MASK; + if (buttons != priv->buttons || + usbhost_threshold(priv, priv->xaccum, priv->yaccum)) #endif - ypos = priv->yaccum + CONFIG_HIDMOUSE_YSCALE * ydisp; - - if (ypos > HIDMOUSE_YMAX_B16) - { - ypos = HIDMOUSE_YMAX_B16; - } - else if (ypos < 0) { - ypos = 0; - } - - priv->yaccum = ypos; - - /* Check if the left button is pressed */ - - if ((rpt->buttons & USBHID_MOUSEIN_BUTTON1) == 0) - { - /* The left button is not pressed.. reset thresholding - * variables. - */ - - priv->xlast = INVALID_POSITION_B16; - priv->ylast = INVALID_POSITION_B16; - - /* Ignore the report if the button was not pressed last - * time (BUTTON_NONE == button released and already - * reported; BUTTON_RELEASED == button released, but not - * yet reported) - */ - - if (priv->sample.event == BUTTON_NONE || - priv->sample.event == BUTTON_RELEASED) - - { - goto ignored; - } - - /* The left button has just been released. NOTE: We know from - * a previous test, that this is a button release condition. - * This will be changed to BUTTON_NONE after the button release - * has been reported. + /* We get here when either there is a meaning button change + * and/or a significant movement of the mouse. We are going + * to report the mouse event. + * + * Snap to the new x/y position for subsequent thresholding */ - priv->sample.event = BUTTON_RELEASED; - } - - /* It is a left button press event. If the last button release - * event has not been processed yet, then we have to ignore the - * button press event (or else it will look like a drag event) - */ + priv->xlast = priv->xaccum; + priv->ylast = priv->yaccum; - else if (priv->sample.event == BUTTON_RELEASED) - { - /* If we have not yet processed the button release event, then - * we cannot handle this button press event. We will have to - * discard the data and wait for the next sample. - */ + /* Update the sample X/Y positions */ - goto ignored; - } + priv->sample.x = b16toi(priv->xaccum); + priv->sample.y = b16toi(priv->yaccum); - /* Handle left-button down events */ +#ifdef CONFIG_HIDMOUSE_TSCIF + /* The X/Y positional data is now valid */ - else - { - /* If this is the first left button press report, then - * report that event. If event == BUTTON_PRESSED, it will - * be set to set to BUTTON_MOVE after the button press is - * first sampled. - */ + priv->sample.valid = true; - if (priv->sample.event != BUTTON_MOVE) - { - /* First button press */ + /* Indicate the availability of new sample data for this ID */ - priv->sample.event = BUTTON_PRESSED; - } + priv->sample.id = priv->id; +#else + /* Report and remember the new button state */ - /* Otherwise, 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. - */ + priv->sample.buttons = buttons; + priv->buttons = buttons; +#endif + priv->valid = true; - else - { - if (xpos > priv->xlast) - { - xdiff = xpos - priv->xlast; - } - else - { - xdiff = priv->xlast - xpos; - } - - if (xdiff < HIDMOUSE_XTHRESH_B16) - { - /* Little or no change in the X diretion, check the - * Y direction. - */ - - if (ypos > priv->ylast) - { - ydiff = ypos - priv->ylast; - } - else - { - ydiff = priv->ylast - ypos; - } - - if (ydiff < HIDMOUSE_YTHRESH_B16) - { - /* Little or no change in either direction... don't - * report anything. - */ - - goto ignored; - } - } - } - - /* We get here when the left button is first pressed, or when - * it has been held and dragged for a distance exceeding a - * threshold. - * - * Snap to the new x/y position for subsequent thresholding */ + /* Notify any waiters that new HIDMOUSE data is available */ - priv->xlast = xpos; - priv->ylast = ypos; + usbhost_notify(priv); } - - /* We get here when either the left button is released, pressed - * or dragged. We are going to report the mouse event. Update the - * sample X/Y positions (the sample event state was set by the - * above logic. - */ - - priv->sample.x = b16toi(xpos); - priv->sample.y = b16toi(ypos); - - /* The X/Y positional data is now valid */ - - priv->sample.valid = true; - - /* Indicate the availability of new sample data for this ID */ - - priv->sample.id = priv->id; - priv->valid = true; - - /* Notify any waiters that new HIDMOUSE data is available */ - - usbhost_notify(priv); } - /* This mouse event will not be reported */ - -ignored: /* Release our lock on the state structure */ usbhost_givesem(&priv->exclsem); @@ -1038,6 +1178,7 @@ static int usbhost_sample(FAR struct usbhost_state_s *priv, memcpy(sample, &priv->sample, sizeof(struct mouse_sample_s )); +#ifdef CONFIG_HIDMOUSE_TSCIF /* Now manage state transitions */ if (sample->event == BUTTON_RELEASED) @@ -1047,8 +1188,8 @@ static int usbhost_sample(FAR struct usbhost_state_s *priv, */ priv->sample.event = BUTTON_NONE; - priv->sample.valid = false; priv->id++; + priv->sample.valid = false; } else if (sample->event == BUTTON_PRESSED) { @@ -1056,6 +1197,9 @@ static int usbhost_sample(FAR struct usbhost_state_s *priv, priv->sample.event = BUTTON_MOVE; } +#endif + + /* The sample has been reported and is no longer valid */ priv->valid = false; ret = OK; @@ -1999,7 +2143,11 @@ static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len { FAR struct inode *inode; FAR struct usbhost_state_s *priv; +#ifdef CONFIG_HIDMOUSE_TSCIF FAR struct touch_sample_s *report; +#else + FAR struct mouse_report_s *report; +#endif struct mouse_sample_s sample; int ret; @@ -2060,6 +2208,7 @@ static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len /* We now have sampled HIDMOUSE data that we can report to the caller. */ +#ifdef CONFIG_HIDMOUSE_TSCIF report = (FAR struct touch_sample_s *)buffer; memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); @@ -2105,6 +2254,16 @@ static ssize_t usbhost_read(FAR struct file *filep, FAR char *buffer, size_t len ivdbg(" y: %d\n", report->point[0].y); ret = SIZEOF_TOUCH_SAMPLE_S(1); +#else + report = (FAR struct mouse_report_s *)buffer; + memset(report, 0, sizeof(struct mouse_report_s)); + + report->buttons = sample.buttons; + report->x = sample.x; + report->y = sample.y; + + ret = sizeof(struct mouse_report_s); +#endif errout: usbhost_givesem(&priv->exclsem); diff --git a/nuttx/include/nuttx/input/mouse.h b/nuttx/include/nuttx/input/mouse.h new file mode 100644 index 000000000..f0907175b --- /dev/null +++ b/nuttx/include/nuttx/input/mouse.h @@ -0,0 +1,102 @@ +/************************************************************************************ + * include/nuttx/input/mouse.h + * + * Copyright (C) 2014 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 mouse driver exports a standard character driver interface. By + * convention, the mouse driver is registers as an input device at + * /dev/mouseN where N uniquely identifies the driver instance. + * + * This header file documents the generic interface that all NuttX + * mouse devices must conform. It adds standards and conventions on + * top of the standard character driver interface. + */ + +#ifndef __INCLUDE_NUTTX_INPUT_MOUSE_H +#define __INCLUDE_NUTTX_INPUT_MOUSE_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-Processor Definitions + ************************************************************************************/ +/* These definitions provide the meaning of all of the bits that may be + * reported in the struct mouse_report_s buttons. + */ + +#define MOUSE_BUTTON_1 (1 << 0) /* True: Left mouse button pressed */ +#define MOUSE_BUTTON_2 (1 << 1) /* True: Middle mouse button pressed */ +#define MOUSE_BUTTON_3 (1 << 2) /* True: Right mouse button pressed */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* This structure contains information about the current mouse button states and + * mouse position. Positional units are device specific and determined by mouse + * configuration settings. + */ + +struct mouse_report_s +{ + uint8_t buttons; /* See TOUCH_* definitions above */ + int16_t x; /* X coordinate of the mouse position */ + int16_t y; /* Y coordinate of the mouse position */ +}; + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __INCLUDE_NUTTX_INPUT_MOUSE_H */ diff --git a/nuttx/include/nuttx/input/touchscreen.h b/nuttx/include/nuttx/input/touchscreen.h index 04fc13dd7..f4dd2a691 100644 --- a/nuttx/include/nuttx/input/touchscreen.h +++ b/nuttx/include/nuttx/input/touchscreen.h @@ -64,7 +64,7 @@ #define TSIOC_SETFREQUENCY _TSIOC(0x0003) /* arg: Pointer to uint32_t frequency value */ #define TSIOC_GETFREQUENCY _TSIOC(0x0004) /* arg: Pointer to uint32_t frequency value */ -/* Specific touchscreen drivers may support additional, device specific ioctal +/* Specific touchscreen drivers may support additional, device specific ioctl * commands, beginning with this value: */ diff --git a/nuttx/include/nuttx/usb/hid.h b/nuttx/include/nuttx/usb/hid.h index 877203a9c..99229da63 100644 --- a/nuttx/include/nuttx/usb/hid.h +++ b/nuttx/include/nuttx/usb/hid.h @@ -288,6 +288,7 @@ #define USBHID_MOUSEIN_BUTTON1 (1 << 0) #define USBHID_MOUSEIN_BUTTON2 (1 << 1) #define USBHID_MOUSEIN_BUTTON3 (1 << 2) +#define USBHID_MOUSEIN_BUTTON_MASK (7) /* Joystick input report (4 bytes) (HID D.1) */ -- cgit v1.2.3