From 292d4db37a4080585577c43434157db335cd5158 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 25 Dec 2012 17:22:58 +0000 Subject: Add logic to serialize and marshal out-of-band keyboard commands git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5460 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/libc/misc/lib_kbddecode.c | 258 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 258 insertions(+) create mode 100644 nuttx/libc/misc/lib_kbddecode.c (limited to 'nuttx/libc/misc/lib_kbddecode.c') diff --git a/nuttx/libc/misc/lib_kbddecode.c b/nuttx/libc/misc/lib_kbddecode.c new file mode 100644 index 000000000..046d570f9 --- /dev/null +++ b/nuttx/libc/misc/lib_kbddecode.c @@ -0,0 +1,258 @@ +/******************************************************************************************** + * libc/msic/lib_kbddecode.c + * Decoding side of the Keyboard CODEC + * + * Copyright (C) 2012 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 + +/******************************************************************************************** + * Pre-Processor Definitions + ********************************************************************************************/ + +#define NDX_ESC 0 +#define NDX_BRACKET 1 +#define NDX_CODE 2 +#define NCX_SEMICOLON 3 + +#define NCH_ESC 1 +#define NCH_BRACKET 2 +#define NCH_CODE 3 +#define NCH_SEMICOLON 4 + +/******************************************************************************************** + * Private Functions + ********************************************************************************************/ + +/**************************************************************************** + * Name: kbd_reget + * + * Description: + * We have unused characters from the last, unsuccessful. Return one of + * these instead of the . + * + * Input Parameters: + * stream - An instance of lib_instream_s to do the low-level get + * operation. + * pch - The location character to save the returned value. This may be + * either a normal, "in-band" ASCII characer or a special, "out-of-band" + * command. + * state - A user provided buffer to support parsing. This structure + * should be cleared the first time that kbd_get is called. + * + * Returned Value: + * 2 - Indicates the successful receipt of a special, "out-of-band" command + * 1 - Indicates the successful receipt of normal, "in-band" ASCII data. + * 0 - Indicates end-of-file or that the stream has been closed + * EOF - An error has getting the next character (reported by the stream). + * + ****************************************************************************/ + +static int kbd_reget(FAR struct kget_getstate_s *state, FAR uint8_t *pch) +{ + /* Return the next character */ + + *pch = state->buf[state->ndx]; + state->ndx++; + state->nch--; + return KBD_NORMAL; +} + +/******************************************************************************************** + * Public Functions + ********************************************************************************************/ + +/**************************************************************************** + * Name: kbd_get + * + * Description: + * Put one byte of data or special command from the driver provided input + * buffer. + * + * Input Parameters: + * stream - An instance of lib_instream_s to do the low-level get + * operation. + * pch - The location character to save the returned value. This may be + * either a normal, "in-band" ASCII characer or a special, "out-of-band" + * command. + * state - A user provided buffer to support parsing. This structure + * should be cleared the first time that kbd_get is called. + * + * Returned Value: + * 1 - Indicates the successful receipt of a special, "out-of-band" command + * 0 - Indicates the successful receipt of normal, "in-band" ASCII data. + * EOF - An error has getting the next character (reported by the stream). + * Normally indicates the end of file. + * + ****************************************************************************/ + +int kbd_get(FAR struct lib_instream_s *stream, + FAR struct kget_getstate_s *state, FAR uint8_t *pch) +{ + int ch; + + DEBUGASSERT(stream && state && pch); + + /* Are their ungotten characters from the last, failed parse? */ + + if (state->nch > 0) + { + /* Yes, return the next ungotten character */ + + return kbd_reget(state, pch); + } + + state->ndx = 0; + + /* No, ungotten characters. Check for the beginning of an esc sequence. */ + + ch = stream->get(stream); + if (ch == EOF) + { + /* End of file/stream */ + + return KBD_ERROR; + } + else + { + state->buf[NDX_ESC] = (uint8_t)ch; + state->nch = NCH_ESC; + + if (ch != ASCII_ESC) + { + /* Not the beginning of an escape sequence. Return the character. */ + + return kbd_reget(state, pch); + } + } + + /* Check for ESC-[ */ + + ch = stream->get(stream); + if (ch == EOF) + { + /* End of file/stream. Return the escape character now. We will + * return the EOF indication next time. + */ + + return kbd_reget(state, pch); + } + else + { + state->buf[NDX_BRACKET] = ch; + state->nch = NCH_BRACKET; + + if (ch != '[') + { + /* Not the beginning of an escape sequence. Return the ESC now, + * return the following character later. + */ + + return kbd_reget(state, pch); + } + } + + /* Get and verify the special, "out-of-band" command code */ + + ch = stream->get(stream); + if (ch == EOF) + { + /* End of file/stream. Unget everything and return the ESC character. + */ + + return kbd_reget(state, pch); + } + else + { + state->buf[NDX_CODE] = (uint8_t)ch; + state->nch = NCH_CODE; + + /* Check for a valid special command code */ + + if (ch < FIRST_KEYCODE || ch > LAST_KEYCODE) + { + /* Not a special command code, return the ESC now and the next two + * characters later. + */ + + return kbd_reget(state, pch); + } + } + + /* Check for the final semicolon */ + + ch = stream->get(stream); + if (ch == EOF) + { + /* End of file/stream. Unget everything and return the ESC character. + */ + + return kbd_reget(state, pch); + } + else + { + state->buf[NCX_SEMICOLON] = (uint8_t)ch; + state->nch = NCH_SEMICOLON; + + /* Check for a valid special command code */ + + if (ch != ';') + { + /* Not a special command code, return the ESC now and the next two + * characters later. + */ + + return kbd_reget(state, pch); + } + } + + /* We have successfully parsed the the entire escape sequence. Return the + * special code in pch and the value 2. + */ + + *pch = state->buf[NDX_CODE]; + state->nch = 0; + return KBD_SPECIAL; +} + -- cgit v1.2.3 From 373e145e546cc34b6a0000d7b3f71538c05a3b1b Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 26 Dec 2012 18:54:59 +0000 Subject: Implement encoding the usbhost HID keyboard driver; configre olimex-lpc1766stk HID keyboard configuration to use the kconfig-frontends tool git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5461 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/hidkbd/hidkbd_main.c | 4 +- nuttx/ChangeLog | 6 + nuttx/Documentation/NuttxPortingGuide.html | 148 +++- nuttx/configs/olimex-lpc1766stk/README.txt | 20 +- nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig | 39 - nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig | 914 +++++++++++++---------- nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh | 4 +- nuttx/drivers/usbhost/Kconfig | 64 +- nuttx/drivers/usbhost/usbhost_hidkbd.c | 375 ++++++++-- nuttx/include/nuttx/input/kbd_codec.h | 26 +- nuttx/libc/misc/lib_kbddecode.c | 10 +- nuttx/libc/misc/lib_kbdencode.c | 3 + 12 files changed, 1080 insertions(+), 533 deletions(-) delete mode 100644 nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig (limited to 'nuttx/libc/misc/lib_kbddecode.c') diff --git a/apps/examples/hidkbd/hidkbd_main.c b/apps/examples/hidkbd/hidkbd_main.c index e744a495c..bc1eebed0 100644 --- a/apps/examples/hidkbd/hidkbd_main.c +++ b/apps/examples/hidkbd/hidkbd_main.c @@ -206,7 +206,7 @@ int hidkbd_main(int argc, char *argv[]) printf("Device %s opened\n", CONFIG_EXAMPLES_HIDKBD_DEVNAME); fflush(stdout); - /* Loop until there is a read failure */ + /* Loop until there is a read failure (or EOF?) */ do { @@ -220,7 +220,7 @@ int hidkbd_main(int argc, char *argv[]) (void)write(1, buffer, nbytes); } } - while (nbytes >= 0); + while (nbytes > 0); printf("Closing device %s: %d\n", CONFIG_EXAMPLES_HIDKBD_DEVNAME, (int)nbytes); fflush(stdout); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 80ddb56c6..7e1c538d7 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3821,3 +3821,9 @@ * libc/misc/lib_kbdencode.c and lib_kbddecode.c: Add logic to marshal and serialized "out-of-band" keyboard commands intermixed with normal ASCII data (not yet hooked into anything). + * drivers/usbhost/usbhost_hidkbd.c: If CONFIG_HIDKBD_ENCODED is + defined, this driver will now use libc/misc/lib_kbdencode.c to + encode special function keys. + * configs/olimex-lpc1766stk/hidkbd: This configuration has been + converted to use the kconfig-frontends configuration tool. + diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index 0408f82ac..ebb3eff4b 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -131,7 +131,8 @@ 6.3.12 PWM Drivers
6.3.13 CAN Drivers
6.3.14 Quadrature Encoder Drivers
- 6.3.15 Watchdog Timer Drivers + 6.3.15 Watchdog Timer Drivers
+ 6.3.16 Keyboard/Keypad Drivers
6.4 Power Management
    @@ -3620,6 +3621,151 @@ extern void up_ledoff(int led);
+

6.3.16 Keyboard/Keypad Drivers

+

+ "Out-of-Band" Commands. + Keyboards and keypads are the same device for NuttX. + A keypad is thought of as simply a keyboard with fewer keys. + In NuttX, a keyboard/keypad driver is simply a character driver that may have an (optional) encoding/decoding layer on the data returned by the character driver. + A keyboard may return simple text data (alphabetic, numeric, and punctuaction) or control characters (enter, control-C, etc.). + We can think about this the normal "in-band" keyboard data stream. + However, in addition, most keyboards support actions that cannot be represented as text data. + Such actions include things like cursor controls (home, up arrow, page down, etc.), editing functions (insert, delete, etc.), volume controls, (mute, volume up, etc.) and other special functions. + We can think about this as special, "out-of-band" keyboard commands. + In this case, some special encoding may be required to multiplex the in-band text data and out-of-band command streams. +

+

+ Encoding/Decoding Layer. + An optional encoding/decoding layer can be used with the basic character driver to encode the out-of-band commands into the text data stream. + The function interfaces that comprise that encoding/decoding layer are defined in the header file include/nuttx/input/kbd_code.h. + These functions provide an matched set of (a) driver encoding interfaces, and (b) application decoding interfaces. +

+
    +
  1. +

    + Driver Encoding Interfaces. +

    +
      +
    • +

      + kbd_puttext() +

      +

      Function Prototype:

      +
        +#include <nuttx/streams.h>
        +#include <nuttx/input/kbd_codec.h>
        +void kbd_puttext(int ch, FAR struct lib_outstream_s *stream);
        +
      +

      Description:

      +
        + Put one byte of normal, "in-band" ASCII data into the output stream. +
      +

      Input Pameters:

      +
        +
      • + ch: The character to be added to the output stream. +
      • +
      • + stream: An instance of lib_outstream_s to perform the actual low-level put operation. +
      • +
      +

      Returned Value:

      +
        + None. +
      +
    • +
    • +

      + kbd_putspecial() +

      +

      Function Prototype:

      +
        +#include <nuttx/streams.h>
        +#include <nuttx/input/kbd_codec.h>
        +void kbd_putspecial(enum kbd_keycode_e keycode, FAR struct lib_outstream_s *stream);
        +
      +

      Description:

      +
        + Put one special, "out-of-band" command into the output stream. +
      +

      Input Pameters:

      +
        +
      • + keycode: The command to be added to the output stream. + The enumeration enum kbd_keycode_e keycode identifies all commands known to the system. +
      • +
      • + stream: An instance of lib_outstream_s to perform the actual low-level put operation. +
      • +
      +

      Returned Value:

      +
        + None. +
      +
    • +
    +
  2. +
  3. +

    + Application Decoding Interfaces. +

    +
      +
    • +

      + kbd_get() +

      +

      Function Prototype:

      +
        +#include <nuttx/streams.h>
        +#include <nuttx/input/kbd_codec.h>
        +int kbd_get(FAR struct lib_instream_s *stream, FAR struct kbd_getstate_s *state, FAR uint8_t *pch);
        +
      +

      Description:

      +
        + Get one byte of data or special command from the driver provided input buffer. +
      +

      Input Pameters:

      +
        +
      • + stream: An instance of lib_instream_s to perform the actual low-level get operation. +
      • +
      • + pch: The location character to save the returned value. + This may be either a normal, "in-band" ASCII characer or a special, "out-of-band" command (i.e., a value from enum kbd_getstate_s. +
      • +
      • + state: A user provided buffer to support parsing. + This structure should be cleared the first time that kbd_get is called. +
      • +
      +

      Returned Value:

      +
        +
      • + 1: + Indicates the successful receipt of a special, "out-of-band" command. + The returned value in pch is a value from enum kbd_getstate_s. +
      • +
      • + 0: + Indicates the successful receipt of normal, "in-band" ASCII data. + The returned value in pch is a simple byte of text or control data. +
      • +
      • + EOF: + An error has getting the next character (reported by the stream). + Normally indicates the end of file. +
      • +
      +
    • +
    +
  4. +
+

+ I/O Streams. + Notice the use of the abstract I/O streams in these interfaces. + These stream interfaces are defined in include/nuttx/streams.h. +

+

6.4 Power Management

6.4.1 Overview

diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt index ec7ddd42d..e2c940bac 100644 --- a/nuttx/configs/olimex-lpc1766stk/README.txt +++ b/nuttx/configs/olimex-lpc1766stk/README.txt @@ -899,7 +899,25 @@ Where is one of the following: This configuration directory, performs a simple test of the USB host HID keyboard class driver using the test logic in apps/examples/hidkbd. - nettest: + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the mconf tool. See nuttx/README.txt and + misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. Default platform/toolchain: This is how the build is configured by + be default. These options can easily be re-confured, however. + + CONFIG_HOST_WINDOWS=y : Windows + CONFIG_WINDOWS_CYGWIN=y : Cygwin environment on Windows + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + + nettest: This configuration directory may be used to enable networking using the LPC17xx's Ethernet controller. It uses apps/examples/nettest to excercise the TCP/IP network. diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig deleted file mode 100644 index 79a7c50ab..000000000 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig +++ /dev/null @@ -1,39 +0,0 @@ -############################################################################ -# configs/olimex-lpc1766stk/hidkbd/appconfig -# -# 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/hidkbd - diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig index 9a4c37fb4..78e411560 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig @@ -1,506 +1,604 @@ -############################################################################ -# configs/olimex-lpc1766stk/hidkbd/defconfig -# -# Copyright (C) 2011-2012 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. -# -############################################################################ -# -# Architecture Selection # -CONFIG_ARCH="arm" +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +# CONFIG_RAW_BINARY is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM3S is not set +CONFIG_ARCH_CHIP_LPC17XX=y +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +# CONFIG_ARCH_CHIP_STM32 is not set +# CONFIG_ARCH_CHIP_STR71X is not set CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="lpc17xx" -CONFIG_ARCH_CHIP_LPC17XX=y -CONFIG_ARCH_CHIP_LPC1766=y -CONFIG_ARCH_BOARD="olimex-lpc1766stk" -CONFIG_ARCH_BOARD_LPC1766STK=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set CONFIG_BOARD_LOOPSPERMSEC=8111 -CONFIG_DRAM_SIZE=32768 -CONFIG_DRAM_START=0x10000000 -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_INTERRUPTSTACK=0 -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=y -CONFIG_ARCH_BUTTONS=n -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=n +# CONFIG_ARCH_CALIBRATION is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set +CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y +# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI is not set +# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set # -# Identify toolchain and linker options +# LPC17xx Configuration Options # -CONFIG_LPC17_CODESOURCERYW=n -CONFIG_LPC17_CODESOURCERYL=n -CONFIG_LPC17_DEVKITARM=n -CONFIG_LPC17_BUILDROOT=y +# CONFIG_ARCH_CHIP_LPC1751 is not set +# CONFIG_ARCH_CHIP_LPC1752 is not set +# CONFIG_ARCH_CHIP_LPC1754 is not set +# CONFIG_ARCH_CHIP_LPC1756 is not set +# CONFIG_ARCH_CHIP_LPC1758 is not set +# CONFIG_ARCH_CHIP_LPC1759 is not set +# CONFIG_ARCH_CHIP_LPC1764 is not set +# CONFIG_ARCH_CHIP_LPC1765 is not set +CONFIG_ARCH_CHIP_LPC1766=y +# CONFIG_ARCH_CHIP_LPC1767 is not set +# CONFIG_ARCH_CHIP_LPC1768 is not set +# CONFIG_ARCH_CHIP_LPC1769 is not set +CONFIG_ARCH_FAMILY_LPC176X=y # -# Individual subsystems can be enabled: +# LPC17xx Peripheral Support # -CONFIG_LPC17_ETHERNET=n +CONFIG_LPC17_MAINOSC=y +CONFIG_LPC17_PLL0=y +# CONFIG_LPC17_PLL1 is not set +# CONFIG_LPC17_ETHERNET is not set CONFIG_LPC17_USBHOST=y -CONFIG_LPC17_USBOTG=n -CONFIG_LPC17_USBDEV=n +# CONFIG_LPC17_USBDEV is not set CONFIG_LPC17_UART0=y -CONFIG_LPC17_UART1=n -CONFIG_LPC17_UART2=n -CONFIG_LPC17_UART3=n -CONFIG_LPC17_CAN1=n -CONFIG_LPC17_CAN2=n -CONFIG_LPC17_SPI=n -CONFIG_LPC17_SSP0=n -CONFIG_LPC17_SSP1=n -CONFIG_LPC17_I2C0=n -CONFIG_LPC17_I2C1=n -CONFIG_LPC17_I2S=n -CONFIG_LPC17_TMR0=n -CONFIG_LPC17_TMR1=n -CONFIG_LPC17_TMR2=n -CONFIG_LPC17_TMR3=n -CONFIG_LPC17_RIT=n -CONFIG_LPC17_PWM=n -CONFIG_LPC17_MCPWM=n -CONFIG_LPC17_QEI=n -CONFIG_LPC17_RTC=n -CONFIG_LPC17_WDT=n -CONFIG_LPC17_ADC=n -CONFIG_LPC17_DAC=n -CONFIG_LPC17_GPDMA=n - -# -# LPC17xx Button interrupt support -# -CONFIG_GPIO_IRQ=n -CONFIG_ARCH_IRQBUTTONS=n - -# -# LPC17xx specific serial device driver settings +# CONFIG_LPC17_UART1 is not set +# CONFIG_LPC17_UART2 is not set +# CONFIG_LPC17_UART3 is not set +# CONFIG_LPC17_CAN1 is not set +# CONFIG_LPC17_CAN2 is not set +# CONFIG_LPC17_SPI is not set +# CONFIG_LPC17_SSP0 is not set +# CONFIG_LPC17_SSP1 is not set +# CONFIG_LPC17_I2C0 is not set +# CONFIG_LPC17_I2C1 is not set +# CONFIG_LPC17_I2C2 is not set +# CONFIG_LPC17_I2S is not set +# CONFIG_LPC17_TMR0 is not set +# CONFIG_LPC17_TMR1 is not set +# CONFIG_LPC17_TMR2 is not set +# CONFIG_LPC17_TMR3 is not set +# CONFIG_LPC17_RIT is not set +# CONFIG_LPC17_PWM is not set +# CONFIG_LPC17_MCPWM is not set +# CONFIG_LPC17_QEI is not set +# CONFIG_LPC17_RTC is not set +# CONFIG_LPC17_WDT is not set +# CONFIG_LPC17_ADC is not set +# CONFIG_LPC17_DAC is not set +# CONFIG_LPC17_GPDMA is not set +# CONFIG_LPC17_FLASH is not set + # -CONFIG_UART0_SERIAL_CONSOLE=y -CONFIG_UART1_SERIAL_CONSOLE=n -CONFIG_UART2_SERIAL_CONSOLE=n -CONFIG_UART3_SERIAL_CONSOLE=n +# Serial driver options +# +# CONFIG_SERIAL_TERMIOS is not set +# CONFIG_UART0_FLOWCONTROL is not set -CONFIG_UART0_TXBUFSIZE=256 -CONFIG_UART1_TXBUFSIZE=256 -CONFIG_UART2_TXBUFSIZE=256 -CONFIG_UART3_TXBUFSIZE=256 +# +# ADC driver options +# -CONFIG_UART0_RXBUFSIZE=256 -CONFIG_UART1_RXBUFSIZE=256 -CONFIG_UART2_RXBUFSIZE=256 -CONFIG_UART3_RXBUFSIZE=256 +# +# CAN driver options +# +# CONFIG_GPIO_IRQ is not set -CONFIG_UART0_BAUD=57600 -CONFIG_UART2_BAUD=57600 -CONFIG_UART3_BAUD=57600 -CONFIG_UART1_BAUD=57600 +# +# I2C driver options +# -CONFIG_UART0_BITS=8 -CONFIG_UART1_BITS=8 -CONFIG_UART2_BITS=8 -CONFIG_UART3_BITS=8 +# +# Ethernet driver options +# -CONFIG_UART0_PARITY=0 -CONFIG_UART1_PARITY=0 -CONFIG_UART2_PARITY=0 -CONFIG_UART3_PARITY=0 +# +# USB device driver options +# -CONFIG_UART0_2STOP=0 -CONFIG_UART1_2STOP=0 -CONFIG_UART2_2STOP=0 -CONFIG_UART3_2STOP=0 +# +# USB host driver options +# +CONFIG_USBHOST_OHCIRAM_SIZE=1536 +CONFIG_USBHOST_NEDS=2 +CONFIG_USBHOST_NTDS=3 +CONFIG_USBHOST_TDBUFFERS=3 +CONFIG_USBHOST_TDBUFSIZE=128 +CONFIG_USBHOST_IOBUFSIZE=512 +CONFIG_USBHOST_BULK_DISABLE=y +# CONFIG_USBHOST_INT_DISABLE is not set +CONFIG_USBHOST_ISOC_DISABLE=y +# CONFIG_SDIO_DMA is not set +# CONFIG_SDIO_WIDTH_D1_ONLY is not set # -# LPC17xx specific PHY/Ethernet device driver settings +# Architecture Options # -CONFIG_PHY_KS8721=y -CONFIG_PHY_AUTONEG=y -CONFIG_PHY_SPEED100=n -CONFIG_PHY_FDUPLEX=y -CONFIG_NET_EMACRAM_SIZE=8192 -CONFIG_NET_NTXDESC=7 -CONFIG_NET_NRXDESC=7 -CONFIG_NET_REGDEBUG=n +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set # -# General build options +# Board Settings # -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=y -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=n +CONFIG_DRAM_START=0x10000000 +CONFIG_DRAM_SIZE=32768 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 # -# General OS setup +# Boot options # -CONFIG_USER_ENTRYPOINT="hidkbd_main" -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=n -CONFIG_DEBUG_USB=n -CONFIG_MM_REGIONS=2 -CONFIG_ARCH_LOWPUTC=y +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_LPC1766STK=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="olimex-lpc1766stk" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +# CONFIG_ARCH_BUTTONS is not set +CONFIG_ARCH_HAVE_IRQBUTTONS=y + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=200 -CONFIG_SCHED_INSTRUMENTATION=n +# CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2010 CONFIG_START_MONTH=11 CONFIG_START_DAY=10 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y -CONFIG_NXFLAT=n CONFIG_SCHED_WORKQUEUE=y CONFIG_SCHED_WORKPRIORITY=192 CONFIG_SCHED_WORKPERIOD=50000 CONFIG_SCHED_WORKSTACKSIZE=1024 CONFIG_SIG_SIGWORK=4 +# CONFIG_SCHED_LPWORK is not set +# CONFIG_SCHED_WAITPID is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="hidkbd_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_POLL is not set + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +# CONFIG_SPI is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_HAVECARDDETECT is not set +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SPICLOCK=12500000 +CONFIG_MMCSD_SDIO=y +# CONFIG_SDIO_MUXBUS is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART0=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_CONFIG_SERIAL_NPOLLWAITERS=2 +CONFIG_UART0_SERIAL_CONSOLE=y +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# UART0 Configuration +# +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART0_BAUD=57600 +CONFIG_UART0_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART0_2STOP=0 +# CONFIG_USBDEV is not set +CONFIG_USBHOST=y +CONFIG_USBHOST_NPREALLOC=0 +# CONFIG_USBHOST_MSC is not set +CONFIG_USBHOST_HIDKBD=y +CONFIG_HIDKBD_POLLUSEC=100000 +CONFIG_HIDKBD_DEFPRIO=50 +CONFIG_HIDKBD_STACKSIZE=1024 +CONFIG_HIDKBD_BUFSIZE=64 +CONFIG_HIDKBD_NPOLLWAITERS=2 +# CONFIG_HIDKBD_RAWSCANCODES is not set +# CONFIG_HIDKBD_ENCODED is not set +# CONFIG_HIDKBD_ALLSCANCODES is not set +# CONFIG_HIDKBD_NODEBOUNCE is not set +# CONFIG_WIRELESS is not set # -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. +# System Logging Device Options # -# There are certain dependency relationships in these -# features. + # -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. +# System Logging # -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n -CONFIG_DISABLE_POLL=n +# CONFIG_RAMLOG is not set # -# Misc libc settings +# Networking Support # -CONFIG_NOPRINTF_FIELDWIDTH=n +# CONFIG_NET is not set # -# Allow for architecture optimized implementations +# File Systems # -# The architecture can provide optimized versions of the -# following to improve system performance + +# +# File system configuration # -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n +# CONFIG_FS_FAT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set # -# Sizes of configurable things (0 disables) +# System Logging +# +# CONFIG_SYSLOG is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines # -CONFIG_MAX_TASKS=16 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=4 -CONFIG_NFILE_DESCRIPTORS=8 -CONFIG_NFILE_STREAMS=8 -CONFIG_NAME_MAX=32 CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=4 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_PREALLOC_WDOGS=4 -CONFIG_PREALLOC_TIMERS=4 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set # -# Filesystem configuration +# Basic CXX Support # -CONFIG_FS_FAT=n -CONFIG_FAT_LCNAMES=n -CONFIG_FAT_LFN=n -CONFIG_FAT_MAXFNAME=32 -CONFIG_FS_NXFFS=n -CONFIG_FS_ROMFS=n +# CONFIG_C99_BOOL8 is not set +# CONFIG_HAVE_CXX is not set # -# Maintain legacy build behavior (revisit) +# Application Configuration # -CONFIG_MMCSD=y -CONFIG_MMCSD_SPI=y -CONFIG_MMCSD_SDIO=y +# +# Built-In Applications +# +# CONFIG_BUILTIN is not set # -# SPI-based MMC/SD driver +# Examples # -CONFIG_MMCSD_NSLOTS=1 -CONFIG_MMCSD_READONLY=n -CONFIG_MMCSD_SPICLOCK=12500000 +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +CONFIG_EXAMPLES_HIDKBD=y +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_NETTEST is not set +# CONFIG_EXAMPLES_NSH is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WLAN is not set # -# Block driver buffering +# Interpreters # -CONFIG_FS_READAHEAD=n -CONFIG_FS_WRITEBUFFER=n # -# SDIO-based MMC/SD driver +# Interpreters # -CONFIG_SDIO_DMA=n -CONFIG_MMCSD_MMCSUPPORT=n -CONFIG_MMCSD_HAVECARDDETECT=n +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set # -# TCP/IP and UDP support via uIP +# Network Utilities # -CONFIG_NET=n -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=8 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=562 -CONFIG_NET_TCP=y -CONFIG_NET_TCP_CONNS=8 -CONFIG_NET_NTCP_READAHEAD_BUFFERS=16 -CONFIG_NET_TCPBACKLOG=n -CONFIG_NET_MAX_LISTENPORTS=8 -CONFIG_NET_UDP=y -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=8 -CONFIG_NET_ICMP=y -CONFIG_NET_ICMP_PING=y -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n # -# UIP Network Utilities +# Networking Utilities # -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set # -# USB Device Configuration +# ModBus # -CONFIG_USBDEV=n -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -CONFIG_USBDEV_MAXPOWER=100 -CONFIG_USBDEV_TRACE=n -CONFIG_USBDEV_TRACE_NRECORDS=128 # -# USB Host Configuration +# FreeModbus # -CONFIG_USBHOST=y -CONFIG_USBHOST_NPREALLOC=0 -CONFIG_USBHOST_BULK_DISABLE=y -CONFIG_USBHOST_INT_DISABLE=n -CONFIG_USBHOST_ISOC_DISABLE=y +# CONFIG_MODBUS is not set # -# LPC17xx USB Device Configuration +# NSH Library # -CONFIG_LPC17_USBDEV_FRAME_INTERRUPT=n -CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT=n -CONFIG_LPC17_USBDEV_DMA=n -CONFIG_LPC17_USBDEV_NDMADESCRIPTORS=0 -CONFIG_LPC17_USBDEV_DMAINTMASK=0 +# CONFIG_NSH_LIBRARY is not set # -# LPC17xx USB Host Configuration +# NxWidgets/NxWM # -# OHCI RAM layout: + +# +# System NSH Add-Ons # -CONFIG_USBHOST_OHCIRAM_SIZE=1536 -CONFIG_USBHOST_NEDS=2 -CONFIG_USBHOST_NTDS=3 -CONFIG_USBHOST_TDBUFFERS=3 -CONFIG_USBHOST_TDBUFSIZE=128 -CONFIG_USBHOST_IOBUFSIZE=512 # -# USB Serial Device Configuration -# -CONFIG_PL2303=n -CONFIG_PL2303_EPINTIN=1 -CONFIG_PL2303_EPBULKOUT=2 -CONFIG_PL2303_EPBULKIN=5 -CONFIG_PL2303_NWRREQS=4 -CONFIG_PL2303_NRDREQS=4 -CONFIG_PL2303_VENDORID=0x067b -CONFIG_PL2303_PRODUCTID=0x2303 -CONFIG_PL2303_VENDORSTR="Nuttx" -CONFIG_PL2303_PRODUCTSTR="USBdev Serial" -CONFIG_PL2303_RXBUFSIZE=512 -CONFIG_PL2303_TXBUFSIZE=512 - -# -# USB Storage Device Configuration -# -CONFIG_USBMSC=n -CONFIG_USBMSC_EP0MAXPACKET=64 -CONFIG_USBMSC_EPBULKOUT=2 -CONFIG_USBMSC_EPBULKIN=5 -CONFIG_USBMSC_NRDREQS=2 -CONFIG_USBMSC_NWRREQS=2 -CONFIG_USBMSC_BULKINREQLEN=256 -CONFIG_USBMSC_BULKOUTREQLEN=256 -CONFIG_USBMSC_VENDORID=0x584e -CONFIG_USBMSC_VENDORSTR="NuttX" -CONFIG_USBMSC_PRODUCTID=0x5342 -CONFIG_USBMSC_PRODUCTSTR="USBdev Storage" -CONFIG_USBMSC_VERSIONNO=0x0399 -CONFIG_USBMSC_REMOVABLE=y - -# -# Settings for examples/uip -# -CONFIG_EXAMPLES_UIP_IPADDR=0x0a000002 -CONFIG_EXAMPLES_UIP_DRIPADDR=0x0a000001 -CONFIG_EXAMPLES_UIP_NETMASK=0xffffff00 -CONFIG_EXAMPLES_UIP_DHCPC=n - -# -# Settings for examples/nettest -# -CONFIG_EXAMPLES_NETTEST_SERVER=n -CONFIG_EXAMPLES_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLES_NETTEST_NOMAC=y -CONFIG_EXAMPLES_NETTEST_IPADDR=0x0a000002 -CONFIG_EXAMPLES_NETTEST_DRIPADDR=0x0a000001 -CONFIG_EXAMPLES_NETTEST_NETMASK=0xffffff00 -CONFIG_EXAMPLES_NETTEST_CLIENTIP=0x0a000001 - -# -# Settings for examples/ostest -# -CONFIG_EXAMPLES_OSTEST_LOOPS=1 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048 -CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3 - -# -# Settings for examples/buttons -# -CONFIG_EXAMPLES_BUTTONS_MIN=0 -CONFIG_EXAMPLES_BUTTONS_MAX=7 -CONFIG_EXAMPLES_IRQBUTTONS_MIN=0 -CONFIG_EXAMPLES_IRQBUTTONS_MAX=7 -CONFIG_EXAMPLES_BUTTONS_NAME0="BUT1" -CONFIG_EXAMPLES_BUTTONS_NAME1="BUT2" -CONFIG_EXAMPLES_BUTTONS_NAME2="WAKE-UP" -CONFIG_EXAMPLES_BUTTONS_NAME3="CENTER" -CONFIG_EXAMPLES_BUTTONS_NAME4="UP" -CONFIG_EXAMPLES_BUTTONS_NAME5="DOWN" -CONFIG_EXAMPLES_BUTTONS_NAME6="LEFT" -CONFIG_EXAMPLES_BUTTONS_NAME7="RIGHT" - -# -# Settings for apps/nshlib -# -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=y -CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=y -CONFIG_NSH_IPADDR=0x0a000002 -CONFIG_NSH_DRIPADDR=0x0a000001 -CONFIG_NSH_NETMASK=0xffffff00 -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" - -# -# Architecture-specific NSH options -# -CONFIG_NSH_MMCSDSPIPORTNO=1 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 - -# -# Settings for examples/usbserial -# -CONFIG_EXAMPLES_USBSERIAL_INONLY=n -CONFIG_EXAMPLES_USBSERIAL_OUTONLY=n -CONFIG_EXAMPLES_USBSERIAL_ONLYSMALL=n -CONFIG_EXAMPLES_USBSERIAL_ONLYBIG=n - -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set # -# Stack and heap information +# I2C tool # -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=1024 -CONFIG_USERMAIN_STACKSIZE=2048 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +# CONFIG_SYSTEM_READLINE is not set + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh index af4a2589e..6b51c10de 100755 --- a/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh +++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/setenv.sh @@ -50,7 +50,7 @@ fi # This is the Cygwin path to the location where I installed the CodeSourcery # toolchain under windows. You will also have to edit this if you install # the CodeSourcery toolchain in any other location -# export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" # These are the Cygwin paths to the locations where I installed the Atollic # toolchain under windows. You will also have to edit this if you install @@ -62,7 +62,7 @@ fi # This is the Cygwin path to the location where I build the buildroot # toolchain. -export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" +# export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" # The Olimex-lpc1766stk/tools directory export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools" diff --git a/nuttx/drivers/usbhost/Kconfig b/nuttx/drivers/usbhost/Kconfig index 35695d750..de8469b41 100644 --- a/nuttx/drivers/usbhost/Kconfig +++ b/nuttx/drivers/usbhost/Kconfig @@ -2,6 +2,7 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + config USBHOST_NPREALLOC int "Number of pre-allocated class instances" default 4 @@ -29,64 +30,85 @@ config USBHOST_ISOC_DISABLE On some architectures, selecting this setting will reduce driver size by disabling isochronous endpoint support +config USBHOST_MSC + bool "Mass Storage Class Support" + default n + depends on !BULK_DISABLE + ---help--- + Enable support for the keyboard class driver. This also depends on + NFILE_DESCRIPTORS > 0 && SCHED_WORKQUEUE=y + config USBHOST_HIDKBD - bool "HID keyboad class support" + bool "HID Keyboard Class Support" default n - depends on !USBHOST_INT_DISABLE && SCHED_WORKQUEUE && !DISABLE_SIGNALS + depends on !INT_DISABLE + ---help--- + Enable support for the keyboard class driver. This also depends on + SCHED_WORKQUEUE && !DISABLE_SIGNALS if USBHOST_HIDKBD config HIDKBD_POLLUSEC - bool "" - default n + int "Keyboard Poll Rate (MSEC)" + default 100000 ---help--- - Device poll rate in microseconds. Default: 100 milliseconds. + Device poll rate in microseconds. Default: 100,000 microseconds. config HIDKBD_DEFPRIO - bool "" - default n + int "Polling Thread Priority" + default 50 ---help--- Priority of the polling thread. Default: 50. config HIDKBD_STACKSIZE - bool "" - default n + int "Polling thread stack size" + default 1024 ---help--- Stack size for polling thread. Default: 1024 config HIDKBD_BUFSIZE - bool "" - default n + int "Scancode Buffer Size" + default 64 ---help--- Scancode buffer size. Default: 64. config HIDKBD_NPOLLWAITERS - bool "" - default n + int "Max Number of Waiters for Poll Event" + default 2 + depends on !DISABLE_POLL ---help--- If the poll() method is enabled, this defines the maximum number of threads that can be waiting for keyboard events. Default: 2. config HIDKBD_RAWSCANCODES - bool "" + bool "Use Raw Scan Codes" + default n + ---help--- + If set to y no conversions will be made on the raw keyboard scan + codes. This option is useful during testing. Default: ASCII conversion. + +config HIDKBD_ENCODED + bool "Enocode Special Keys" default n + depends on !HIDKBD_RAWSCANCODES ---help--- - If set to y no conversion will be made on the raw keyboard scan - codes. Default: ASCII conversion. + Encode special key press events in the user buffer. In this case, + the use end must decode the encoded special key values using the + interfaces defined in include/nuttx/input/kbd_codec.h. These + special keys include such things as up/down arrows, home and end + keys, etc. If this not defined, only 7-bit print-able and control + ASCII characters will be provided to the user. config HIDKBD_ALLSCANCODES - bool "" + bool "Use All Scancodes" default n ---help--- If set to y all 231 possible scancodes will be converted to something. Default: 104 key US keyboard. config HIDKBD_NODEBOUNCE - bool "" + bool "Disable Debounce" default n ---help--- If set to y normal debouncing is disabled. Default: Debounce enabled (No repeat keys). - USB host mass storage class driver. Requires USBHOST=y, - config USBHOST_BULK_DISABLE=n, NFILE_DESCRIPTORS > 0, - and SCHED_WORKQUEUE=y endif diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c index e69d68e7b..e0c4680eb 100644 --- a/nuttx/drivers/usbhost/usbhost_hidkbd.c +++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/usbhost/usbhost_hidkbd.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -62,6 +62,11 @@ #include #include +#ifdef CONFIG_HIDKBD_ENCODED +# include +# include +#endif + /* Don't compile if prerequisites are not met */ #if defined(CONFIG_USBHOST) && !defined(CONFIG_USBHOST_INT_DISABLE) && CONFIG_NFILE_DESCRIPTORS > 0 @@ -126,6 +131,14 @@ # endif #endif +/* If we are using raw scancodes, then we cannot support encoding of + * special characters either. + */ + +#ifdef CONFIG_HIDKBD_RAWSCANCODES +# undef CONFIG_HIDKBD_ENCODED +#endif + /* Driver support ***********************************************************/ /* This format is used to construct the /dev/kbd[n] device driver path. It * defined here so that it will be used consistently in all places. @@ -144,6 +157,23 @@ #define USBHOST_MAX_CREFS 0x7fff +/* Debug ********************************************************************/ +/* Both CONFIG_DEBUG_INPUT and CONFIG_DEBUG_USB could apply to this file. + * We assume here that CONFIG_DEBUG_INPUT might be enabled separately, but + * CONFIG_DEBUG_USB implies both. + */ + +#ifndef CONFIG_DEBUG_INPUT +# undef idbg +# define idbg udbg +# undef illdbg +# define illdbg ulldbg +# undef ivdbg +# define ivdbg uvdbg +# undef illvdbg +# define illvdbg ullvdbg +#endif + /**************************************************************************** * Private Types ****************************************************************************/ @@ -209,6 +239,16 @@ struct usbhost_state_s uint8_t kbdbuffer[CONFIG_HIDKBD_BUFSIZE]; }; +/* This type is used for encoding special characters */ + +#ifdef CONFIG_HIDKBD_ENCODED +struct usbhost_outstream_s +{ + struct lib_outstream_s stream; + FAR struct usbhost_state_s *priv; +}; +#endif + /**************************************************************************** * Private Function Prototypes ****************************************************************************/ @@ -240,7 +280,15 @@ static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *dev /* Keyboard polling thread */ static void usbhost_destroy(FAR void *arg); +static void usbhost_putbuffer(FAR struct usbhost_state_s *priv, uint8_t keycode); +#ifdef CONFIG_HIDKBD_ENCODED +static void usbhost_putstream(FAR struct lib_outstream_s *this, int ch); +#endif static inline uint8_t usbhost_mapscancode(uint8_t scancode, uint8_t modifier); +#ifdef CONFIG_HIDKBD_ENCODED +static inline void usbhost_encodescancode(FAR struct usbhost_state_s *priv, + uint8_t scancode, uint8_t modifier); +#endif static int usbhost_kbdpoll(int argc, char *argv[]); /* Helpers for usbhost_connect() */ @@ -346,6 +394,121 @@ static struct usbhost_state_s *g_priv; /* Data passed to thread */ */ #ifndef CONFIG_HIDKBD_RAWSCANCODES +#ifdef CONFIG_HIDKBD_ENCODED + +/* The first and last scancode values with encode-able values */ + +#define FIRST_ENCODING USBHID_KBDUSE_ENTER /* 0x28 Keyboard Return (ENTER) */ +#ifdef CONFIG_HIDKBD_ALLSCANCODES +# define LAST_ENCODING USBHID_KBDUSE_POWER /* 0x66 Keyboard Power */ +#else +#define LAST_ENCODING USBHID_KBDUSE_KPDHEXADECIMAL /* 0xdd Keypad Hexadecimal */ +#endif + +#define USBHID_NUMENCODINGS (LAST_ENCODING - FIRST_ENCODING + 1) + +static const uint8_t encoding[USBHID_NUMENCODINGS] = +{ + /* 0x28-0x2f: Enter,escape,del,back-tab,space,_,+,{ */ + + KEYCODE_ENTER, 0, KEYCODE_FWDDEL, KEYCODE_BACKDEL, 0, 0, 0, 0, + + /* 0x30-0x37: },|,Non-US tilde,:,",grave tidle,<,> */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0x38-0x3f: /,CapsLock,F1,F2,F3,F4,F5,F6 */ + + 0, KEYCODE_CAPSLOCK, KEYCODE_F1, KEYCODE_F2, KEYCODE_F3, KEYCODE_F4, KEYCODE_F5, KEYCODE_F6, + + /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */ + + KEYCODE_F7, KEYCODE_F8, KEYCODE_F9, KEYCODE_F10, KEYCODE_F11, KEYCODE_F12, KEYCODE_PRTSCRN, KEYCODE_SCROLLLOCK, + + /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */ + + KEYCODE_PAUSE, KEYCODE_INSERT, KEYCODE_HOME, KEYCODE_PAGEUP, KEYCODE_FWDDEL, KEYCODE_END, KEYCODE_PAGEDOWN, KEYCODE_RIGHT, + + /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */ + + KEYCODE_LEFT, KEYCODE_DOWN, KEYCODE_UP, KEYCODE_NUMLOCK, 0, 0, 0, 0, + + /* 0x58-0x5f: Enter,1-7 */ + + KEYCODE_ENTER, 0, 0, 0, 0, 0, 0, 0, + + /* 0x60-0x66: 8-9,0,.,Non-US \,Application,Power */ + + 0, 0, 0, 0, 0, 0, KEYCODE_POWER, + +#ifdef CONFIG_HIDKBD_ALLSCANCODES + + 0, /* 0x67 = */ + + /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */ + + KEYCODE_F13, KEYCODE_F14, KEYCODE_F15, KEYCODE_F16, KEYCODE_F17, KEYCODE_F18, KEYCODE_F19, KEYCODE_F20, + + /* 0x70-0x77: F21,F22,F23,F24,Execute,Help,Menu,Select */ + + KEYCODE_F21, KEYCODE_F22, KEYCODE_F23, KEYCODE_F24, KEYCODE_EXECUTE, KEYCODE_HELP, KEYCODE_MENU, KEYCODE_SELECT, + + /* 0x78-0x7f: Stop,Again,Undo,Cut,Copy,Paste,Find,Mute */ + + KEYCODE_STOP, KEYCODE_AGAIN, KEYCODE_UNDO, KEYCODE_CUT, KEYCODE_COPY, KEYCODE_PASTE, KEYCODE_FIND, KEYCODE_MUTE, + + /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */ + + KEYCODE_VOLUP, KEYCODE_VOLDOWN, KEYCODE_LCAPSLOCK, KEYCODE_LNUMLOCK, KEYCODE_LSCROLLLOCK, 0, 0, 0, + + /* 0x88-0x8f: International 2-9 */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0x90-0x97: LAN 1-8 */ + + KEYCODE_LANG1, KEYCODE_LANG2, KEYCODE_LANG3, KEYCODE_LANG4, KEYCODE_LANG5, KEYCODE_LANG6, KEYCODE_LANG7, KEYCODE_LANG8, + + /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */ + + 0, 0, KEYCODE_SYSREQ, KEYCODE_CANCEL, KEYCODE_CLEAR, 0, KEYCODE_ENTER, 0, + + /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0xa8-0xaf: (reserved) */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0xb8-0xbf: {,},tab,backspace,A-D */ + + 0, 0, 0, KEYCODE_BACKDEL, 0, 0, 0, 0, + + /* 0xc0-0xc7: E-F,XOR,^,%,<,>,& */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0xc8-0xcf: &&,|,||,:,#, ,@,! */ + + 0, 0, 0, 0, 0, 0, 0, 0, + + /* 0xd0-0xd7: Memory Store,Recall,Clear,Add,Subtract,Muliply,Divide,+/- */ + + KEYCODE_MEMSTORE, KEYCODE_MEMRECALL, KEYCODE_MEMCLEAR, KEYCODE_MEMADD, KEYCODE_MEMSUB, KEYCODE_MEMMUL, KEYCODE_MEMDIV, KEYCODE_NEGATE, + + /* 0xd8-0xdd: Clear,ClearEntry,Binary,Octal,Decimal,Hexadecimal */ + + KEYCODE_CLEAR, KEYCODE_CLEARENTRY, KEYCODE_BINARY, KEYCODE_OCTAL, KEYCODE_DECIMAL, KEYCODE_HEXADECIMAL +#endif +}; + +#endif + static const uint8_t ucmap[USBHID_NUMSCANCODES] = { 0, 0, 0, 0, 'A', 'B', 'C', 'D', /* 0x00-0x07: Reserved, errors, A-D */ @@ -356,7 +519,7 @@ static const uint8_t ucmap[USBHID_NUMSCANCODES] = '\n', '\033', '\177', 0, ' ', '_', '+', '{', /* 0x28-0x2f: Enter,escape,del,back-tab,space,_,+,{ */ '}', '|', 0, ':', '"', 0, '<', '>', /* 0x30-0x37: },|,Non-US tilde,:,",grave tidle,<,> */ '?', 0, 0, 0, 0, 0, 0, 0, /* 0x38-0x3f: /,CapsLock,F1,F2,F3,F4,F5,F6 */ - 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,sScrollLock */ + 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */ 0, 0, 0, 0, '/', '*', '-', '+', /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */ '\n', '1', '2', '3', '4', '4', '6', '7', /* 0x58-0x5f: Enter,1-7 */ @@ -368,7 +531,7 @@ static const uint8_t ucmap[USBHID_NUMSCANCODES] = 0, 0, 0, 0, 0, ',', 0, 0, /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x88-0x8f: International 2-9 */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x90-0x97: LAN 1-8 */ - 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Ease,SysReq,Cancel,Clear,Prior,Return,Separator */ + 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xa8-0xaf: (reserved) */ 0, 0, 0, 0, 0, 0, '(', ')', /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */ @@ -403,7 +566,7 @@ static const uint8_t lcmap[USBHID_NUMSCANCODES] = 0, 0, 0, 0, 0, ',', 0, 0, /* 0x80-0x87: VolUp,VolDown,LCapsLock,lNumLock,LScrollLock,,,=,International1 */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x88-0x8f: International 2-9 */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x90-0x97: LAN 1-8 */ - 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Ease,SysReq,Cancel,Clear,Prior,Return,Separator */ + 0, 0, 0, 0, 0, 0, '\n', 0, /* 0x98-0x9f: LAN 9,Erase,SysReq,Cancel,Clear,Prior,Return,Separator */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xa0-0xa7: Out,Oper,Clear,CrSel,Excel,(reserved) */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0xa8-0xaf: (reserved) */ 0, 0, 0, 0, 0, 0, '(', ')', /* 0xb0-0xb7: 00,000,ThouSeparator,DecSeparator,CurrencyUnit,SubUnit,(,) */ @@ -637,6 +800,88 @@ static void usbhost_destroy(FAR void *arg) usbhost_freeclass(priv); } +/**************************************************************************** + * Name: usbhost_putbuffer + * + * Description: + * Add one character to the user buffer. + * + * Input Parameters: + * priv - Driver internal state + * keycode - The value to add to the user buffer + * + * Returned Values: + * None + * + ****************************************************************************/ + +static void usbhost_putbuffer(FAR struct usbhost_state_s *priv, + uint8_t keycode) +{ + register unsigned int head; + register unsigned int tail; + + /* Copy the next keyboard character into the user buffer. */ + + head = priv->headndx; + priv->kbdbuffer[head] = keycode; + + /* Increment the head index */ + + if (++head >= CONFIG_HIDKBD_BUFSIZE) + { + head = 0; + } + + /* If the buffer is full, then increment the tail index to make space. Is + * it better to lose old keystrokes or new? + */ + + tail = priv->tailndx; + if (tail == head) + { + if (++tail >= CONFIG_HIDKBD_BUFSIZE) + { + tail = 0; + } + + /* Save the updated tail index */ + + priv->tailndx = tail; + } + + /* Save the updated head index */ + + priv->headndx = head; +} + +/**************************************************************************** + * Name: usbhost_putstream + * + * Description: + * A wrapper for usbhost_putc that is compatibile with the lib_outstream_s + * putc methos. + * + * Input Parameters: + * stream - The struct lib_outstream_s reference + * ch - The character to add to the user buffer + * + * Returned Values: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_HIDKBD_ENCODED +static void usbhost_putstream(FAR struct lib_outstream_s *stream, int ch) +{ + FAR struct usbhost_outstream_s *privstream = (FAR struct lib_outstream_s *)stream; + + DEBUGASSERT(privstream && privstream->priv); + usbhost_putbuffer(privstream->priv), (uint8_t)ch); + stream->nput++; +} +#endif + /**************************************************************************** * Name: usbhost_mapscancode * @@ -679,6 +924,58 @@ static inline uint8_t usbhost_mapscancode(uint8_t scancode, uint8_t modifier) #endif } +/**************************************************************************** + * Name: usbhost_encodescancode + * + * Description: + * Check if the key has a special function encoding and, if it does, add + * the encoded value to the user buffer. + * + * Input Parameters: + * priv - Driver internal state + * scancode - Scan code to be mapped. + * modifier - Ctrl,Alt,Shift,GUI modifier bits + * + * Returned Values: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_HIDKBD_ENCODED +static inline void usbhost_encodescancode(FAR struct usbhost_state_s *priv, + uint8_t scancode, uint8_t modifier) +{ + struct usbhost_outstream_s stream; + uint8_t encoded; + + /* Check if the raw scancode is in a valid range */ + + if (scancode >= FIRST_ENCODING && scancode <= LAST_ENCODING) + { + /* Yes the value is within range */ + + encoded = encoding(scancode - FIRST_ENCODING); + ivdbg(" scancode: %02x modifier: %02x encoded: %d\n", + scancode, modifier, encoded); + + if (encoded) + { + struct usbhost_outstream_s usbstream; + + /* And it does correspond to a special function key */ + + usbstream->stream.put = usbhost_putstream; + usbstream->stream.nput = 0; + usbstream->priv = priv; + + /* Add the special function value to the user buffer */ + + kbd_putspecial((enum kbd_keycode_e)encoded, &usbstream); + } + } +} +#endif + /**************************************************************************** * Name: usbhost_kbdpoll * @@ -704,6 +1001,8 @@ static int usbhost_kbdpoll(int argc, char *argv[]) unsigned int npolls = 0; #endif unsigned int nerrors = 0; + bool empty = true; + bool newstate; int ret; uvdbg("Started\n"); @@ -717,13 +1016,13 @@ static int usbhost_kbdpoll(int argc, char *argv[]) * running. */ - priv = g_priv; - DEBUGASSERT(priv != NULL); + priv = g_priv; + DEBUGASSERT(priv != NULL); - priv->polling = true; - priv->crefs++; - usbhost_givesem(&g_syncsem); - sleep(1); + priv->polling = true; + priv->crefs++; + usbhost_givesem(&g_syncsem); + sleep(1); /* Loop here until the device is disconnected */ @@ -784,17 +1083,12 @@ static int usbhost_kbdpoll(int argc, char *argv[]) else if (priv->open) { struct usbhid_kbdreport_s *rpt = (struct usbhid_kbdreport_s *)priv->tbuffer; - unsigned int head; - unsigned int tail; - uint8_t ascii; + uint8_t keycode; int i; /* Add the newly received keystrokes to our internal buffer */ usbhost_takesem(&priv->exclsem); - head = priv->headndx; - tail = priv->tailndx; - for (i = 0; i < 6; i++) { /* Is this key pressed? But not pressed last time? @@ -828,15 +1122,15 @@ static int usbhost_kbdpoll(int argc, char *argv[]) * or cursor controls in this version of the driver. */ - ascii = usbhost_mapscancode(rpt->key[i], rpt->modifier); - uvdbg("Key %d: %02x ASCII:%c modifier: %02x\n", - i, rpt->key[i], ascii ? ascii : ' ', rpt->modifier); + keycode = usbhost_mapscancode(rpt->key[i], rpt->modifier); + ivdbg("Key %d: %02x keycode:%c modifier: %02x\n", + i, rpt->key[i], keycode ? keycode : ' ', rpt->modifier); /* Zero at this point means that the key does not map to a * printable character. */ - if (ascii != 0) + if (keycode != 0) { /* Handle control characters. Zero after this means * a valid, NUL character. @@ -844,36 +1138,28 @@ static int usbhost_kbdpoll(int argc, char *argv[]) if ((rpt->modifier & (USBHID_MODIFER_LCTRL|USBHID_MODIFER_RCTRL)) != 0) { - ascii &= 0x1f; + keycode &= 0x1f; } /* Copy the next keyboard character into the user * buffer. */ - priv->kbdbuffer[head] = ascii; - - /* Increment the head index */ - - if (++head >= CONFIG_HIDKBD_BUFSIZE) - { - head = 0; - } + usbhost_putbuffer(priv, keycode); + } - /* If the buffer is full, then increment the tail - * index to make space. Is it better to lose old - * keystrokes or new? - */ + /* The zero might, however, map to a special keyboard action (such as a + * cursor movement or function key). Attempt to encode the special key. + */ - if (tail == head) - { - if (++tail >= CONFIG_HIDKBD_BUFSIZE) - { - tail = 0; - } - } +#ifdef CONFIG_HIDKBD_ENCODED + else + { + usbhost_encodescancode(priv, rpt->key[i], rpt->modifier)); } +#endif } + /* Save the scancode (or lack thereof) for key debouncing on * next keyboard report. */ @@ -885,7 +1171,8 @@ static int usbhost_kbdpoll(int argc, char *argv[]) /* Did we just transition from no data available to data available? */ - if (head != tail && priv->headndx == priv->tailndx) + newstate = (priv->headndx == priv->tailndx); + if (empty && !newstate) { /* Yes.. Is there a thread waiting for keyboard data now? */ @@ -902,10 +1189,7 @@ static int usbhost_kbdpoll(int argc, char *argv[]) usbhost_pollnotify(priv); } - /* Update the head/tail indices */ - - priv->headndx = head; - priv->tailndx = tail; + empty = newstate; usbhost_givesem(&priv->exclsem); } @@ -958,6 +1242,7 @@ static int usbhost_kbdpoll(int argc, char *argv[]) usbhost_givesem(&priv->exclsem); } + return 0; } diff --git a/nuttx/include/nuttx/input/kbd_codec.h b/nuttx/include/nuttx/input/kbd_codec.h index b103d544e..d374ed8d3 100644 --- a/nuttx/include/nuttx/input/kbd_codec.h +++ b/nuttx/include/nuttx/input/kbd_codec.h @@ -113,7 +113,7 @@ enum kbd_keycode_e KEYCODE_PAUSE, /* Pause */ KEYCODE_BREAK, /* Break */ KEYCODE_CANCEL, /* Cancel */ - KEYCODE_PRINTSCN, /* PrintScreen */ + KEYCODE_PRTSCRN, /* PrintScreen */ KEYCODE_SYSREQ, /* SysReq/Attention */ /* Audio */ @@ -131,14 +131,15 @@ enum kbd_keycode_e KEYCODE_CLEAR, /* Clear */ KEYCODE_CLEARENTRY, /* Clear entry */ + KEYCODE_NEGATE, /* +/- */ - KEYCODE_MEMSET, /* Memory set */ + KEYCODE_MEMSTORE, /* Memory store */ KEYCODE_MEMCLEAR, /* Memory clear */ KEYCODE_MEMRECALL, /* Memory recall */ KEYCODE_MEMADD, /* Memory add */ - KEYCODE_MEMSUBTRACT, /* Memory substract */ - KEYCODE_MEMMULTIPY, /* Memory multiply */ - KEYCODE_MEMDIVIDE, /* Memory divide */ + KEYCODE_MEMSUB, /* Memory substract */ + KEYCODE_MEMMUL, /* Memory multiply */ + KEYCODE_MEMDIV, /* Memory divide */ KEYCODE_BINARY, /* Binary mode */ KEYCODE_OCTAL, /* Octal mode */ @@ -197,7 +198,7 @@ enum kbd_keycode_e * Public Types ****************************************************************************/ -struct kget_getstate_s +struct kbd_getstate_s { uint8_t nch; /* Number of characters in the buffer */ uint8_t ndx; /* Index to next character in the buffer */ @@ -225,7 +226,7 @@ extern "C" * Put one byte of normal, "in-band" ASCII data into the output stream. * * Input Parameters: - * ch - The character to be into the output stream. + * ch - The character to be added to the output stream. * stream - An instance of lib_outstream_s to do the low-level put * operation. * @@ -243,6 +244,9 @@ extern "C" * Put one special, "out-of-band" command into the output stream. * * Input Parameters: + * keycode - The command to be added to the output stream. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. * * Returned Value: * None @@ -261,7 +265,7 @@ void kbd_putspecial(enum kbd_keycode_e keycode, * Name: kbd_get * * Description: - * Put one byte of data or special command from the driver provided input + * Get one byte of data or special command from the driver provided input * buffer. * * Input Parameters: @@ -274,15 +278,17 @@ void kbd_putspecial(enum kbd_keycode_e keycode, * should be cleared the first time that kbd_get is called. * * Returned Value: - * 1 - Indicates the successful receipt of a special, "out-of-band" command + * 1 - Indicates the successful receipt of a special, "out-of-band" command. + * The returned value in pch is a value from enum kbd_getstate_s. * 0 - Indicates the successful receipt of normal, "in-band" ASCII data. + * The returned value in pch is a simple byte of text or control data. * EOF - An error has getting the next character (reported by the stream). * Normally indicates the end of file. * ****************************************************************************/ int kbd_get(FAR struct lib_instream_s *stream, - FAR struct kget_getstate_s *state, FAR uint8_t *pch); + FAR struct kbd_getstate_s *state, FAR uint8_t *pch); #ifdef __cplusplus } diff --git a/nuttx/libc/misc/lib_kbddecode.c b/nuttx/libc/misc/lib_kbddecode.c index 046d570f9..cb57b5215 100644 --- a/nuttx/libc/misc/lib_kbddecode.c +++ b/nuttx/libc/misc/lib_kbddecode.c @@ -89,7 +89,7 @@ * ****************************************************************************/ -static int kbd_reget(FAR struct kget_getstate_s *state, FAR uint8_t *pch) +static int kbd_reget(FAR struct kbd_getstate_s *state, FAR uint8_t *pch) { /* Return the next character */ @@ -107,7 +107,7 @@ static int kbd_reget(FAR struct kget_getstate_s *state, FAR uint8_t *pch) * Name: kbd_get * * Description: - * Put one byte of data or special command from the driver provided input + * Get one byte of data or special command from the driver provided input * buffer. * * Input Parameters: @@ -120,15 +120,17 @@ static int kbd_reget(FAR struct kget_getstate_s *state, FAR uint8_t *pch) * should be cleared the first time that kbd_get is called. * * Returned Value: - * 1 - Indicates the successful receipt of a special, "out-of-band" command + * 1 - Indicates the successful receipt of a special, "out-of-band" command. + * The returned value in pch is a value from enum kbd_getstate_s. * 0 - Indicates the successful receipt of normal, "in-band" ASCII data. + * The returned value in pch is a simple byte of text or control data. * EOF - An error has getting the next character (reported by the stream). * Normally indicates the end of file. * ****************************************************************************/ int kbd_get(FAR struct lib_instream_s *stream, - FAR struct kget_getstate_s *state, FAR uint8_t *pch) + FAR struct kbd_getstate_s *state, FAR uint8_t *pch) { int ch; diff --git a/nuttx/libc/misc/lib_kbdencode.c b/nuttx/libc/misc/lib_kbdencode.c index 80bf14777..40a8805b1 100644 --- a/nuttx/libc/misc/lib_kbdencode.c +++ b/nuttx/libc/misc/lib_kbdencode.c @@ -62,6 +62,9 @@ * Put one special, "out-of-band" command into the output stream. * * Input Parameters: + * keycode - The command to be added to the output stream. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. * * Returned Value: * None -- cgit v1.2.3 From 954529e8c571cd7c2cc5963259d7eef46f6f5429 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Dec 2012 14:01:59 +0000 Subject: Add support for key release events git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5464 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 5 +- apps/examples/hidkbd/hidkbd_main.c | 33 +++++-- nuttx/ChangeLog | 4 + nuttx/Documentation/NuttxPortingGuide.html | 138 +++++++++++++++++++++++------ nuttx/drivers/usbhost/usbhost_hidkbd.c | 8 +- nuttx/include/nuttx/input/kbd_codec.h | 100 +++++++++++++++------ nuttx/libc/misc/lib_kbddecode.c | 99 +++++++++++---------- nuttx/libc/misc/lib_kbdencode.c | 101 +++++++++++++++++---- 8 files changed, 356 insertions(+), 132 deletions(-) (limited to 'nuttx/libc/misc/lib_kbddecode.c') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index d156b1065..d6a2f9d90 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -455,4 +455,7 @@ this build phase. * apps/examples/hidbkd: Now supports decoding of encoded special keys if CONFIG_EXAMPLES_HIDKBD_ENCODED is defined. - + * apps/examples/hidbkd: Add support for decoding key release events + as well. However, the USB HID keyboard drier has not yet been + updated to detect key release events. That is kind of tricky in + the USB HID keyboard report data. diff --git a/apps/examples/hidkbd/hidkbd_main.c b/apps/examples/hidkbd/hidkbd_main.c index 8a632bab7..d7e79b121 100644 --- a/apps/examples/hidkbd/hidkbd_main.c +++ b/apps/examples/hidkbd/hidkbd_main.c @@ -176,7 +176,7 @@ static void hidkbd_decode(FAR char *buffer, ssize_t nbytes) { /* Decode the next thing from the buffer */ - ret = kbd_get((FAR struct lib_instream_s *)&kbdstream, &state, &ch); + ret = kbd_decode((FAR struct lib_instream_s *)&kbdstream, &state, &ch); if (ret == KBD_ERROR) { break; @@ -184,14 +184,31 @@ static void hidkbd_decode(FAR char *buffer, ssize_t nbytes) /* Normal data? Or special key? */ - if (ret == KBD_NORMAL) + switch (ret) { - printf("Data: %c [%02x]\n", isprint(ch) ? ch : '.', ch); - } - else - { - DEBUGASSERT(ret == KBD_SPECIAL); - printf("Special: %d\n", ch); + case KBD_PRESS: /* Key press event */ + printf("Normal Press: %c [%02x]\n", isprint(ch) ? ch : '.', ch); + break; + + case KBD_RELEASE: /* Key release event */ + printf("Normal Release: %c [%02x]\n", isprint(ch) ? ch : '.', ch); + break; + + case KBD_SPECPRESS: /* Special key press event */ + printf("Special Press: %d\n", ch); + break; + + case KBD_SPECREL: /* Special key release event */ + printf("Special Release: %d\n", ch); + break; + + case KBD_ERROR: /* Error or end-of-file */ + printf("EOF: %d\n", ret); + break; + + default: + printf("Unexpected: %d\n", ret); + break; } } } diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index a7087656a..2e114af8c 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3832,4 +3832,8 @@ UG-2864HSWEG01 OLED for the STM32F4Discovery board. * drivers/usbhost/usbhost_hidkbd.c: Correct a logic error in how tasks waiting for read data are awakened. + * libc/misc/lib_kbdencode.c and lib_kbddecode.c: Now handles keypress + events too. However, the USB HID keyboard drier has not yet been + updated to detect key release events. That is kind of tricky in + the USB HID keyboard report data. diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index ebb3eff4b..e626bf7a5 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -3623,20 +3623,27 @@ extern void up_ledoff(int led);

6.3.16 Keyboard/Keypad Drivers

- "Out-of-Band" Commands. - Keyboards and keypads are the same device for NuttX. + Keypads vs. Keyboards + Keyboards and keypads are really the same devices for NuttX. A keypad is thought of as simply a keyboard with fewer keys. +

+

+ Special Commands. In NuttX, a keyboard/keypad driver is simply a character driver that may have an (optional) encoding/decoding layer on the data returned by the character driver. - A keyboard may return simple text data (alphabetic, numeric, and punctuaction) or control characters (enter, control-C, etc.). - We can think about this the normal "in-band" keyboard data stream. - However, in addition, most keyboards support actions that cannot be represented as text data. + A keyboard may return simple text data (alphabetic, numeric, and punctuaction) or control characters (enter, control-C, etc.) when a key is pressed. + We can think about this the "normal" keyboard data stream. + However, in addition, most keyboards support actions that cannot be represented as text or control data. Such actions include things like cursor controls (home, up arrow, page down, etc.), editing functions (insert, delete, etc.), volume controls, (mute, volume up, etc.) and other special functions. - We can think about this as special, "out-of-band" keyboard commands. - In this case, some special encoding may be required to multiplex the in-band text data and out-of-band command streams. + In this case, some special encoding may be required to multiplex the normal text data and special command key press data streams. +

+

+ Key Press and Release Events + Sometimes the time that a key is released is needed by applications as well. + Thus, in addition to normal and special key press events, it may also be necessary to encode normal and special key release events.

Encoding/Decoding Layer. - An optional encoding/decoding layer can be used with the basic character driver to encode the out-of-band commands into the text data stream. + An optional encoding/decoding layer can be used with the basic character driver to encode the keyboard events into the text data stream. The function interfaces that comprise that encoding/decoding layer are defined in the header file include/nuttx/input/kbd_code.h. These functions provide an matched set of (a) driver encoding interfaces, and (b) application decoding interfaces.

@@ -3644,21 +3651,23 @@ extern void up_ledoff(int led);
  • Driver Encoding Interfaces. + These are interfaces used by the keyboard/keypad driver to encode keyboard events and data.

    • - kbd_puttext() + kbd_press()

      Function Prototype:

         #include <nuttx/streams.h>
         #include <nuttx/input/kbd_codec.h>
        -void kbd_puttext(int ch, FAR struct lib_outstream_s *stream);
        +void kbd_press(int ch, FAR struct lib_outstream_s *stream);
         

      Description:

        - Put one byte of normal, "in-band" ASCII data into the output stream. + Indicates a normal key press event. + Put one byte of normal keyboard data into the output stream.

      Input Pameters:

        @@ -3676,18 +3685,77 @@ void kbd_puttext(int ch, FAR struct lib_outstream_s *stream);
      • - kbd_putspecial() + kbd_release() +

        +

        Function Prototype:

        +
          +#include <nuttx/streams.h>
          +#include <nuttx/input/kbd_codec.h>
          +void kbd_release(uint8_t ch, FAR struct lib_outstream_s *stream);
          +
        +

        Description:

        +
          + Encode the release of a normal key. +
        +

        Input Pameters:

        +
          +
        • + ch: The character associated with the key that was releared. +
        • +
        • + stream: An instance of lib_outstream_s to perform the actual low-level put operation. +
        • +
        +

        Returned Value:

        +
          + None. +
        +
      • +
      • +

        + kbd_specpress()

        Function Prototype:

           #include <nuttx/streams.h>
           #include <nuttx/input/kbd_codec.h>
          -void kbd_putspecial(enum kbd_keycode_e keycode, FAR struct lib_outstream_s *stream);
          +void kbd_specpress(enum kbd_keycode_e keycode, FAR struct lib_outstream_s *stream);
           

        Description:

          - Put one special, "out-of-band" command into the output stream. + Denotes a special key press event. + Put one special keyboard command into the output stream. +
        +

        Input Pameters:

        +
          +
        • + keycode: The command to be added to the output stream. + The enumeration enum kbd_keycode_e keycode identifies all commands known to the system. +
        • +
        • + stream: An instance of lib_outstream_s to perform the actual low-level put operation. +
        +

        Returned Value:

        +
          + None. +
        +
      • +
      • +

        + kbd_specrel() +

        +

        Function Prototype:

        +
          +#include <nuttx/streams.h>
          +#include <nuttx/input/kbd_codec.h>
          +void kbd_specrel(enum kbd_keycode_e keycode, FAR struct lib_outstream_s *stream);
          +
        +

        Description:

        +
          + Denotes a special key release event. + Put one special keyboard command into the output stream. +

        Input Pameters:

        • @@ -3708,17 +3776,18 @@ void kbd_putspecial(enum kbd_keycode_e keycode, FAR struct lib_outstream_s *stre
        • Application Decoding Interfaces. -

          + These are user interfaces to decode the values returned by the keyboard/keypad driver. +

          • - kbd_get() + kbd_decode()

            Function Prototype:

               #include <nuttx/streams.h>
               #include <nuttx/input/kbd_codec.h>
              -int kbd_get(FAR struct lib_instream_s *stream, FAR struct kbd_getstate_s *state, FAR uint8_t *pch);
              +int kbd_decode(FAR struct lib_instream_s *stream, FAR struct kbd_getstate_s *state, FAR uint8_t *pch);
               

            Description:

              @@ -3730,30 +3799,41 @@ int kbd_get(FAR struct lib_instream_s *stream, FAR struct kbd_getstate_s *state, stream: An instance of lib_instream_s to perform the actual low-level get operation.
            • - pch: The location character to save the returned value. - This may be either a normal, "in-band" ASCII characer or a special, "out-of-band" command (i.e., a value from enum kbd_getstate_s. + pch: The location to save the returned value. + This may be either a normal, character code or a special command (i.e., a value from enum kbd_getstate_s.
            • state: A user provided buffer to support parsing. - This structure should be cleared the first time that kbd_get is called. + This structure should be cleared the first time that kbd_decode() is called.

            Returned Value:

            • - 1: - Indicates the successful receipt of a special, "out-of-band" command. - The returned value in pch is a value from enum kbd_getstate_s. + KBD_PRESS (0): + Indicates the successful receipt of normal, keyboard data. + This corresponds to a keypress event. + The returned value in pch is a simple byte of text or control data.
            • - 0: - Indicates the successful receipt of normal, "in-band" ASCII data. - The returned value in pch is a simple byte of text or control data. + KBD_RELEASE (1): + Indicates a key release event. + The returned value in pch is the byte of text or control data corresponding to the released key. +
            • +
            • + KBD_SPECPRESS (2): + Indicates the successful receipt of a special keyboard command. + The returned value in pch is a value from enum kbd_getstate_s. +
            • +
            • + KBD_SPECREL (3): + Indicates a special command key release event. + The returned value in pch is a value from enum kbd_getstate_s.
            • - EOF: - An error has getting the next character (reported by the stream). - Normally indicates the end of file. + KBD_ERROR (EOF): + An error has getting the next character (reported by the stream). + Normally indicates the end of file.
          • diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c index 917ebfa3f..0bab89c28 100644 --- a/nuttx/drivers/usbhost/usbhost_hidkbd.c +++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c @@ -530,7 +530,7 @@ static const uint8_t ucmap[USBHID_NUMSCANCODES] = 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */ 0, 0, 0, 0, '/', '*', '-', '+', /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */ - '\n', '1', '2', '3', '4', '4', '6', '7', /* 0x58-0x5f: Enter,1-7 */ + '\n', '1', '2', '3', '4', '5', '6', '7', /* 0x58-0x5f: Enter,1-7 */ '8', '9', '0', '.', 0, 0, 0, '=', /* 0x60-0x67: 8-9,0,.,Non-US \,Application,Power,= */ #ifdef CONFIG_HIDKBD_ALLSCANCODES 0, 0, 0, 0, 0, 0, 0, 0, /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */ @@ -565,7 +565,7 @@ static const uint8_t lcmap[USBHID_NUMSCANCODES] = 0, 0, 0, 0, 0, 0, 0, 0, /* 0x40-0x47: F7,F8,F9,F10,F11,F12,PrtScn,ScrollLock */ 0, 0, 0, 0, 0, 0, 0, 0, /* 0x48-0x4f: Pause,Insert,Home,PageUp,DeleteForward,End,PageDown,RightArrow */ 0, 0, 0, 0, '/', '*', '-', '+', /* 0x50-0x57: LeftArrow,DownArrow,UpArrow,Num Lock,/,*,-,+ */ - '\n', '1', '2', '3', '4', '4', '6', '7', /* 0x58-0x5f: Enter,1-7 */ + '\n', '1', '2', '3', '4', '5', '6', '7', /* 0x58-0x5f: Enter,1-7 */ '8', '9', '0', '.', 0, 0, 0, '=', /* 0x60-0x67: 8-9,0,.,Non-US \,Application,Power,= */ #ifdef CONFIG_HIDKBD_ALLSCANCODES 0, 0, 0, 0, 0, 0, 0, 0, /* 0x68-0x6f: F13,F14,F15,F16,F17,F18,F19,F20 */ @@ -977,8 +977,8 @@ static inline void usbhost_encodescancode(FAR struct usbhost_state_s *priv, /* Add the special function value to the user buffer */ - kbd_putspecial((enum kbd_keycode_e)encoded, - (FAR struct lib_outstream_s *)&usbstream); + kbd_specpress((enum kbd_keycode_e)encoded, + (FAR struct lib_outstream_s *)&usbstream); } } } diff --git a/nuttx/include/nuttx/input/kbd_codec.h b/nuttx/include/nuttx/input/kbd_codec.h index 0a3a54d2d..9a7c7c8e6 100644 --- a/nuttx/include/nuttx/input/kbd_codec.h +++ b/nuttx/include/nuttx/input/kbd_codec.h @@ -1,6 +1,6 @@ /************************************************************************************ * include/nuttx/input/kbd_codec.h - * Serialize and marshaling out-of-band keyboard data + * Serialize and marshaling keyboard data and events * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -54,9 +54,7 @@ * Public Types ****************************************************************************/ -/* These are the special, "out-of-band" keyboard commands recognized by the - * CODEC. - */ +/* These are the special keyboard commands recognized by the CODEC. */ enum kbd_keycode_e { @@ -190,11 +188,13 @@ enum kbd_keycode_e #define FIRST_KEYCODE KEYCODE_FWDDEL #define LAST_KEYCODE KEYCODE_F24 -/* kbd_get return values */ +/* kbd_decode() return values */ -#define KBD_NORMAL 0 -#define KBD_SPECIAL 1 -#define KBD_ERROR EOF +#define KBD_PRESS 0 /* Key press event */ +#define KBD_RELEASE 1 /* Key release event */ +#define KBD_SPECPRESS 2 /* Special key press event */ +#define KBD_SPECREL 3 /* Special key release event */ +#define KBD_ERROR EOF /* Error or end-of-file */ /**************************************************************************** * Public Types @@ -222,10 +222,11 @@ extern "C" ****************************************************************************/ /**************************************************************************** - * Name: kbd_puttext + * Name: kbd_press * * Description: - * Put one byte of normal, "in-band" ASCII data into the output stream. + * Indicates a normal key press event. Put one byte of normal keyboard + * data into the output stream. * * Input Parameters: * ch - The character to be added to the output stream. @@ -237,13 +238,52 @@ extern "C" * ****************************************************************************/ -#define kbd_puttext(ch, stream) (stream)->put((stream), (int)(ch)) +#define kbd_press(ch, stream) (stream)->put((stream), (int)(ch)) /**************************************************************************** - * Name: kbd_putspecial + * Name: kbd_release * * Description: - * Put one special, "out-of-band" command into the output stream. + * Encode the release of a normal key. + * + * Input Parameters: + * ch - The character associated with the key that was releared. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void kbd_release(uint8_t ch, FAR struct lib_outstream_s *stream); + +/**************************************************************************** + * Name: kbd_specpress + * + * Description: + * Denotes a special key press event. Put one special keyboard command + * into the output stream. + * + * Input Parameters: + * keycode - The command to be added to the output stream. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void kbd_specpress(enum kbd_keycode_e keycode, + FAR struct lib_outstream_s *stream); + +/**************************************************************************** + * Name: kbd_specrel + * + * Description: + * Denotes a special key release event. Put one special keyboard + * command into the output stream. * * Input Parameters: * keycode - The command to be added to the output stream. @@ -255,8 +295,8 @@ extern "C" * ****************************************************************************/ -void kbd_putspecial(enum kbd_keycode_e keycode, - FAR struct lib_outstream_s *stream); +void kbd_specrel(enum kbd_keycode_e keycode, + FAR struct lib_outstream_s *stream); /**************************************************************************** * The following functions are intended for use by "consumer" applications @@ -264,7 +304,7 @@ void kbd_putspecial(enum kbd_keycode_e keycode, ****************************************************************************/ /**************************************************************************** - * Name: kbd_get + * Name: kbd_decode * * Description: * Get one byte of data or special command from the driver provided input @@ -273,24 +313,30 @@ void kbd_putspecial(enum kbd_keycode_e keycode, * Input Parameters: * stream - An instance of lib_instream_s to do the low-level get * operation. - * pch - The location character to save the returned value. This may be - * either a normal, "in-band" ASCII characer or a special, "out-of-band" - * command. + * pch - The location to save the returned value. This may be + * either a normal, character code or a special command from enum + * kbd_keycode_e * state - A user provided buffer to support parsing. This structure - * should be cleared the first time that kbd_get is called. + * should be cleared the first time that kbd_decode is called. * * Returned Value: - * 1 - Indicates the successful receipt of a special, "out-of-band" command. - * The returned value in pch is a value from enum kbd_getstate_s. - * 0 - Indicates the successful receipt of normal, "in-band" ASCII data. - * The returned value in pch is a simple byte of text or control data. + * + * KBD_PRESS - Indicates the successful receipt of normal, keyboard data. + * This corresponds to a keypress event. The returned value in pch is a + * simple byte of text or control data corresponding to the pressed key. + * KBD_RELEASE - Indicates a key release event. The returned value in pch + * is the byte of text or control data corresponding to the released key. + * KBD_SPECPRESS - Indicates the successful receipt of a special keyboard + * command. The returned value in pch is a value from enum kbd_getstate_s. + * KBD_SPECREL - Indicates a special key release event. The returned value + * in pch is a value from enum kbd_getstate_s. * EOF - An error has getting the next character (reported by the stream). - * Normally indicates the end of file. + * Normally indicates the end of file. * ****************************************************************************/ -int kbd_get(FAR struct lib_instream_s *stream, - FAR struct kbd_getstate_s *state, FAR uint8_t *pch); +int kbd_decode(FAR struct lib_instream_s *stream, + FAR struct kbd_getstate_s *state, FAR uint8_t *pch); #ifdef __cplusplus } diff --git a/nuttx/libc/misc/lib_kbddecode.c b/nuttx/libc/misc/lib_kbddecode.c index cb57b5215..62554902c 100644 --- a/nuttx/libc/misc/lib_kbddecode.c +++ b/nuttx/libc/misc/lib_kbddecode.c @@ -1,4 +1,4 @@ -/******************************************************************************************** +/**************************************************************************** * libc/msic/lib_kbddecode.c * Decoding side of the Keyboard CODEC * @@ -32,38 +32,43 @@ * 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 -/******************************************************************************************** +/**************************************************************************** * Pre-Processor Definitions - ********************************************************************************************/ + ****************************************************************************/ -#define NDX_ESC 0 -#define NDX_BRACKET 1 -#define NDX_CODE 2 -#define NCX_SEMICOLON 3 +#define NDX_ESC 0 +#define NDX_BRACKET 1 +#define NDX_CODE 2 +#define NDX_TERMINATOR 3 -#define NCH_ESC 1 -#define NCH_BRACKET 2 -#define NCH_CODE 3 -#define NCH_SEMICOLON 4 +#define NCH_ESC 1 +#define NCH_BRACKET 2 +#define NCH_CODE 3 +#define NCH_TERMINATOR 4 -/******************************************************************************************** +#define TERM_MIN ('a' + KBD_RELEASE) +#define TERM_MAX ('a' + KBD_SPECREL) +#define TERM_RETURN(a) ((a) - 'a') + +/**************************************************************************** * Private Functions - ********************************************************************************************/ + ****************************************************************************/ /**************************************************************************** * Name: kbd_reget @@ -76,16 +81,11 @@ * stream - An instance of lib_instream_s to do the low-level get * operation. * pch - The location character to save the returned value. This may be - * either a normal, "in-band" ASCII characer or a special, "out-of-band" - * command. - * state - A user provided buffer to support parsing. This structure - * should be cleared the first time that kbd_get is called. + * either a normal, character code or a special command from enum + * kbd_keycode_e * * Returned Value: - * 2 - Indicates the successful receipt of a special, "out-of-band" command - * 1 - Indicates the successful receipt of normal, "in-band" ASCII data. - * 0 - Indicates end-of-file or that the stream has been closed - * EOF - An error has getting the next character (reported by the stream). + * KBD_PRESS - Indicates the successful receipt of norma keyboard data. * ****************************************************************************/ @@ -96,15 +96,15 @@ static int kbd_reget(FAR struct kbd_getstate_s *state, FAR uint8_t *pch) *pch = state->buf[state->ndx]; state->ndx++; state->nch--; - return KBD_NORMAL; + return KBD_PRESS; } -/******************************************************************************************** +/**************************************************************************** * Public Functions - ********************************************************************************************/ + ****************************************************************************/ /**************************************************************************** - * Name: kbd_get + * Name: kbd_decode * * Description: * Get one byte of data or special command from the driver provided input @@ -113,24 +113,30 @@ static int kbd_reget(FAR struct kbd_getstate_s *state, FAR uint8_t *pch) * Input Parameters: * stream - An instance of lib_instream_s to do the low-level get * operation. - * pch - The location character to save the returned value. This may be - * either a normal, "in-band" ASCII characer or a special, "out-of-band" - * command. + * pch - The location to save the returned value. This may be + * either a normal, character code or a special command from enum + * kbd_keycode_e * state - A user provided buffer to support parsing. This structure - * should be cleared the first time that kbd_get is called. + * should be cleared the first time that kbd_decode is called. * * Returned Value: - * 1 - Indicates the successful receipt of a special, "out-of-band" command. - * The returned value in pch is a value from enum kbd_getstate_s. - * 0 - Indicates the successful receipt of normal, "in-band" ASCII data. - * The returned value in pch is a simple byte of text or control data. + * + * KBD_PRESS - Indicates the successful receipt of normal, keyboard data. + * This corresponds to a keypress event. The returned value in pch is a + * simple byte of text or control data corresponding to the pressed key. + * KBD_RELEASE - Indicates a key release event. The returned value in pch + * is the byte of text or control data corresponding to the released key. + * KBD_SPECPRESS - Indicates the successful receipt of a special keyboard + * command. The returned value in pch is a value from enum kbd_getstate_s. + * KBD_SPECREL - Indicates a special key release event. The returned value + * in pch is a value from enum kbd_getstate_s. * EOF - An error has getting the next character (reported by the stream). - * Normally indicates the end of file. + * Normally indicates the end of file. * ****************************************************************************/ -int kbd_get(FAR struct lib_instream_s *stream, - FAR struct kbd_getstate_s *state, FAR uint8_t *pch) +int kbd_decode(FAR struct lib_instream_s *stream, + FAR struct kbd_getstate_s *state, FAR uint8_t *pch) { int ch; @@ -147,7 +153,7 @@ int kbd_get(FAR struct lib_instream_s *stream, state->ndx = 0; - /* No, ungotten characters. Check for the beginning of an esc sequence. */ + /* No, ungotten characters. Check for the beginning of an ESC sequence. */ ch = stream->get(stream); if (ch == EOF) @@ -195,7 +201,7 @@ int kbd_get(FAR struct lib_instream_s *stream, } } - /* Get and verify the special, "out-of-band" command code */ + /* Get and verify the special keyboard data to decode */ ch = stream->get(stream); if (ch == EOF) @@ -234,12 +240,12 @@ int kbd_get(FAR struct lib_instream_s *stream, } else { - state->buf[NCX_SEMICOLON] = (uint8_t)ch; - state->nch = NCH_SEMICOLON; + state->buf[NDX_TERMINATOR] = (uint8_t)ch; + state->nch = NCH_TERMINATOR; /* Check for a valid special command code */ - if (ch != ';') + if (ch < TERM_MIN || ch > TERM_MAX) { /* Not a special command code, return the ESC now and the next two * characters later. @@ -250,11 +256,12 @@ int kbd_get(FAR struct lib_instream_s *stream, } /* We have successfully parsed the the entire escape sequence. Return the - * special code in pch and the value 2. + * keyboard value in pch and the value an indication determined by the + * terminating character. */ *pch = state->buf[NDX_CODE]; state->nch = 0; - return KBD_SPECIAL; + return TERM_RETURN(state->buf[NDX_TERMINATOR]); } diff --git a/nuttx/libc/misc/lib_kbdencode.c b/nuttx/libc/misc/lib_kbdencode.c index 40a8805b1..80138ca80 100644 --- a/nuttx/libc/misc/lib_kbdencode.c +++ b/nuttx/libc/misc/lib_kbdencode.c @@ -1,4 +1,4 @@ -/******************************************************************************************** +/**************************************************************************** * libc/msic/lib_kbdencode.c * Encoding side of the Keyboard CODEC * @@ -32,11 +32,11 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ********************************************************************************************/ + ****************************************************************************/ -/******************************************************************************************** +/**************************************************************************** * Included Files - ********************************************************************************************/ + ****************************************************************************/ #include @@ -47,38 +47,105 @@ #include #include -/******************************************************************************************** +/**************************************************************************** * Pre-Processor Definitions - ********************************************************************************************/ - -/******************************************************************************************** - * Public Functions - ********************************************************************************************/ + ****************************************************************************/ /**************************************************************************** - * Name: kbd_putspecial + * Name: kbd_encode * * Description: - * Put one special, "out-of-band" command into the output stream. + * Encode one special special sequence command into the output stream. * * Input Parameters: * keycode - The command to be added to the output stream. * stream - An instance of lib_outstream_s to do the low-level put * operation. + * terminator - Escape sequence terminating character. * * Returned Value: * None * ****************************************************************************/ -void kbd_putspecial(enum kbd_keycode_e keycode, - FAR struct lib_outstream_s *stream) +static void kbd_encode(uint8_t keycode, FAR struct lib_outstream_s *stream, + uint8_t terminator) { - DEBUGASSERT(stream && keycode >= KEYCODE_FWDDEL && keycode <= LAST_KEYCODE); - stream->put(stream, ASCII_ESC); stream->put(stream, '['); stream->put(stream, (int)keycode); - stream->put(stream, ';'); + stream->put(stream, terminator); } +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: kbd_release + * + * Description: + * Encode the release of a normal key. + * + * Input Parameters: + * ch - The character associated with the key that was releared. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void kbd_release(uint8_t ch, FAR struct lib_outstream_s *stream) +{ + kbd_encode(ch, stream, ('a' + KBD_RELEASE)); +} + +/**************************************************************************** + * Name: kbd_specpress + * + * Description: + * Denotes a special key press event. Put one special keyboard command + * into the output stream. + * + * Input Parameters: + * keycode - The command to be added to the output stream. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void kbd_specpress(enum kbd_keycode_e keycode, + FAR struct lib_outstream_s *stream) +{ + DEBUGASSERT(stream && keycode >= KEYCODE_FWDDEL && keycode <= LAST_KEYCODE); + kbd_encode((uint8_t)keycode, stream, ('a' + KBD_SPECPRESS)); +} + +/**************************************************************************** + * Name: kbd_specrel + * + * Description: + * Denotes a special key release event. Put one special keyboard + * command into the output stream. + * + * Input Parameters: + * keycode - The command to be added to the output stream. + * stream - An instance of lib_outstream_s to do the low-level put + * operation. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void kbd_specrel(enum kbd_keycode_e keycode, + FAR struct lib_outstream_s *stream) +{ + DEBUGASSERT(stream && keycode >= KEYCODE_FWDDEL && keycode <= LAST_KEYCODE); + kbd_encode((uint8_t)keycode, stream, ('a' + KBD_SPECREL)); +} -- cgit v1.2.3