summaryrefslogtreecommitdiff
path: root/nuttx/graphics/nxconsole
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-20 15:01:50 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-20 15:01:50 -0600
commitc9dc40dc7348d137fa260c05395ad0c5f396d441 (patch)
tree9a3de167a5d1be1a9edbc11da5c05322eb6b65ae /nuttx/graphics/nxconsole
parent53287415d45ecb9402fe7d838e040c9309120a68 (diff)
downloadpx4-nuttx-c9dc40dc7348d137fa260c05395ad0c5f396d441.tar.gz
px4-nuttx-c9dc40dc7348d137fa260c05395ad0c5f396d441.tar.bz2
px4-nuttx-c9dc40dc7348d137fa260c05395ad0c5f396d441.zip
Change all occurrences of NxConsole to NxTerm
Diffstat (limited to 'nuttx/graphics/nxconsole')
-rw-r--r--nuttx/graphics/nxconsole/Make.defs48
-rw-r--r--nuttx/graphics/nxconsole/nx_register.c193
-rw-r--r--nuttx/graphics/nxconsole/nxcon_driver.c257
-rw-r--r--nuttx/graphics/nxconsole/nxcon_font.c651
-rw-r--r--nuttx/graphics/nxconsole/nxcon_internal.h254
-rw-r--r--nuttx/graphics/nxconsole/nxcon_kbdin.c489
-rw-r--r--nuttx/graphics/nxconsole/nxcon_putc.c203
-rw-r--r--nuttx/graphics/nxconsole/nxcon_redraw.c153
-rw-r--r--nuttx/graphics/nxconsole/nxcon_register.c160
-rw-r--r--nuttx/graphics/nxconsole/nxcon_scroll.c253
-rw-r--r--nuttx/graphics/nxconsole/nxcon_sem.c129
-rw-r--r--nuttx/graphics/nxconsole/nxcon_unregister.c123
-rw-r--r--nuttx/graphics/nxconsole/nxcon_vt100.c289
-rw-r--r--nuttx/graphics/nxconsole/nxtk_register.c192
-rw-r--r--nuttx/graphics/nxconsole/nxtool_register.c195
15 files changed, 0 insertions, 3589 deletions
diff --git a/nuttx/graphics/nxconsole/Make.defs b/nuttx/graphics/nxconsole/Make.defs
deleted file mode 100644
index 3dc9c79a1..000000000
--- a/nuttx/graphics/nxconsole/Make.defs
+++ /dev/null
@@ -1,48 +0,0 @@
-############################################################################
-# graphics/nxconsole/Make.defs
-#
-# Copyright (C) 2012 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# 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.
-#
-############################################################################
-
-NXCON_ASRCS =
-NXCON_CSRCS = nx_register.c nxcon_driver.c nxcon_font.c nxcon_putc.c
-NXCON_CSRCS += nxcon_redraw.c nxcon_register.c nxcon_scroll.c
-NXCON_CSRCS += nxcon_vt100.c nxcon_unregister.c nxtk_register.c
-NXCON_CSRCS += nxtool_register.c
-
-ifeq ($(CONFIG_NXTERM_NXKBDIN),y)
-NXCON_CSRCS += nxcon_kbdin.c
-endif
-
-ifeq ($(CONFIG_DEBUG),y)
-NXCON_CSRCS += nxcon_sem.c
-endif
diff --git a/nuttx/graphics/nxconsole/nx_register.c b/nuttx/graphics/nxconsole/nx_register.c
deleted file mode 100644
index 64eb878d9..000000000
--- a/nuttx/graphics/nxconsole/nx_register.c
+++ /dev/null
@@ -1,193 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nx_register.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <nuttx/nx/nx.h>
-#include <nuttx/nx/nxconsole.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int nxcon_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES]);
-#ifndef CONFIG_NX_WRITEONLY
-static int nxcon_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset);
-#endif
-static int nxcon_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const struct nxcon_operations_s g_nxops =
-{
- nxcon_fill,
-#ifndef CONFIG_NX_WRITEONLY
- nxcon_move,
-#endif
- nxcon_bitmap
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_fill
- *
- * Description:
- * Fill the specified rectangle in the window with the specified color
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - The location to be filled
- * color - The color to use in the fill
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxcon_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES])
-{
- return nx_fill((NXWINDOW)priv->handle, rect, wcolor);
-}
-
-/****************************************************************************
- * Name: nxcon_move
- *
- * Description:
- * Move a rectangular region within the window
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - Describes the rectangular region to move
- * offset - The offset to move the region. The rectangular region will be
- * moved so that the origin is translated by this amount.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-#ifndef CONFIG_NX_WRITEONLY
-static int nxcon_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset)
-{
- return nx_move((NXWINDOW)priv->handle, rect, offset);
-}
-#endif
-
-/****************************************************************************
- * Name: nxcon_bitmap
- *
- * Description:
- * Copy a rectangular region of a larger image into the rectangle in the
- * specified window.
- *
- * Input Parameters:
- * priv - The driver state structure.
- * dest - Describes the rectangular region on the display that will
- * receive the bit map.
- * src - The start of the source image. This is an array source
- * images of size CONFIG_NX_NPLANES.
- * origin - The origin of the upper, left-most corner of the full bitmap.
- * Both dest and origin are in window coordinates, however, origin
- * may lie outside of the display.
- * stride - The width of the full source image in bytes.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxcon_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride)
-{
- return nx_bitmap((NXWINDOW)priv->handle, dest, src, origin, stride);
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nx_register
- *
- * Description:
- * Register a console device on a raw NX window. The device will be
- * registered at /dev/nxconN where N is the provided minor number.
- *
- * Input Parameters:
- * hwnd - A handle that will be used to access the window. The window must
- * persist and this handle must be valid for the life of the NX console.
- * wndo - Describes the window and font to be used
- * minor - The device minor number
- *
- * Return:
- * A non-NULL handle is returned on success.
- *
- ****************************************************************************/
-
-NXCONSOLE nx_register(NXWINDOW hwnd, FAR struct nxcon_window_s *wndo, int minor)
-{
- return nxcon_register((NXCONSOLE)hwnd, wndo, &g_nxops, minor);
-}
-
diff --git a/nuttx/graphics/nxconsole/nxcon_driver.c b/nuttx/graphics/nxconsole/nxcon_driver.c
deleted file mode 100644
index 0fa6f7400..000000000
--- a/nuttx/graphics/nxconsole/nxcon_driver.c
+++ /dev/null
@@ -1,257 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_driver.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdbool.h>
-#include <string.h>
-#include <fcntl.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int nxcon_open(FAR struct file *filep);
-static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
- size_t buflen);
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-/* This is the common NX driver file operations */
-
-#ifdef CONFIG_NXTERM_NXKBDIN
-
-const struct file_operations g_nxcon_drvrops =
-{
- nxcon_open, /* open */
- 0, /* close */
- nxcon_read, /* read */
- nxcon_write, /* write */
- 0, /* seek */
- 0 /* ioctl */
-#ifndef CONFIG_DISABLE_POLL
- ,
- nxcon_poll /* poll */
-#endif
-};
-
-#else /* CONFIG_NXTERM_NXKBDIN */
-
-const struct file_operations g_nxcon_drvrops =
-{
- nxcon_open, /* open */
- 0, /* close */
- 0, /* read */
- nxcon_write, /* write */
- 0, /* seek */
- 0 /* ioctl */
-#ifndef CONFIG_DISABLE_POLL
- ,
- 0 /* poll */
-#endif
-};
-
-#endif /* CONFIG_NXTERM_NXKBDIN */
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_open
- ****************************************************************************/
-
-static int nxcon_open(FAR struct file *filep)
-{
- FAR struct inode *inode = filep->f_inode;
- FAR struct nxcon_state_s *priv = inode->i_private;
-
- DEBUGASSERT(filep && filep->f_inode);
-
- /* Get the driver structure from the inode */
-
- inode = filep->f_inode;
- priv = (FAR struct nxcon_state_s *)inode->i_private;
- DEBUGASSERT(priv);
-
- /* Verify that the driver is opened for write-only access */
-
-#ifndef CONFIG_NXTERM_NXKBDIN
- if ((filep->f_oflags & O_RDOK) != 0)
- {
- gdbg("ERROR: Attempted open with read access\n");
- return -EACCES;
- }
-#endif
-
- /* Assign the driver structure to the file */
-
- filep->f_priv = priv;
- return OK;
-}
-
-/****************************************************************************
- * Name: nxcon_write
- ****************************************************************************/
-
-static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
- size_t buflen)
-{
- FAR struct nxcon_state_s *priv;
- enum nxcon_vt100state_e state;
- ssize_t remaining;
- char ch;
- int ret;
-
- /* Recover our private state structure */
-
- DEBUGASSERT(filep && filep->f_priv);
- priv = (FAR struct nxcon_state_s *)filep->f_priv;
-
- /* Get exclusive access */
-
- ret = nxcon_semwait(priv);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Hide the cursor while we update the display */
-
- nxcon_hidecursor(priv);
-
- /* Loop writing each character to the display */
-
- for (remaining = (ssize_t)buflen; remaining > 0; remaining--)
- {
- /* Get the next character from the user buffer */
-
- ch = *buffer++;
-
- /* Check if this character is part of a VT100 escape sequence */
-
- do
- {
- /* Is the character part of a VT100 escape sequnce? */
-
- state = nxcon_vt100(priv, ch);
- switch (state)
- {
- /* Character is not part of a VT100 escape sequence (and no
- * characters are buffer.
- */
-
- default:
- case VT100_NOT_CONSUMED:
- {
- /* We can output the character to the window */
-
- nxcon_putc(priv, (uint8_t)ch);
- }
- break;
-
- /* The full VT100 escape sequence was processed (and the new
- * character was consumed)
- */
-
- case VT100_PROCESSED:
-
- /* Character was consumed as part of the VT100 escape processing
- * (but the escape sequence is still incomplete.
- */
-
- case VT100_CONSUMED:
- {
- /* Do nothing... the VT100 logic owns the character */
- }
- break;
-
- /* Invalid/unsupported character in escape sequence */
-
- case VT100_ABORT:
- {
- int i;
-
- /* Add the first unhandled character to the window */
-
- nxcon_putc(priv, (uint8_t)priv->seq[0]);
-
- /* Move all buffer characters down one */
-
- for (i = 1; i < priv->nseq; i++)
- {
- priv->seq[i-1] = priv->seq[i];
- }
- priv->nseq--;
-
- /* Then loop again and check if what remains is part of a
- * VT100 escape sequence. We could speed this up by
- * checking if priv->seq[0] == ASCII_ESC.
- */
- }
- break;
- }
- }
- while (state == VT100_ABORT);
- }
-
- /* Show the cursor at its new position */
-
- nxcon_showcursor(priv);
- nxcon_sempost(priv);
- return (ssize_t)buflen;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
diff --git a/nuttx/graphics/nxconsole/nxcon_font.c b/nuttx/graphics/nxconsole/nxcon_font.c
deleted file mode 100644
index 5d44af36a..000000000
--- a/nuttx/graphics/nxconsole/nxcon_font.c
+++ /dev/null
@@ -1,651 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_font.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* Select renderer -- Some additional logic would be required to support
- * pixel depths that are not directly addressable (1,2,4, and 24).
- */
-
-#if CONFIG_NXTERM_BPP == 1
-# define RENDERER nxf_convert_1bpp
-#elif CONFIG_NXTERM_BPP == 2
-# define RENDERER nxf_convert_2bpp
-#elif CONFIG_NXTERM_BPP == 4
-# define RENDERER nxf_convert_4bpp
-#elif CONFIG_NXTERM_BPP == 8
-# define RENDERER nxf_convert_8bpp
-#elif CONFIG_NXTERM_BPP == 16
-# define RENDERER nxf_convert_16bpp
-#elif CONFIG_NXTERM_BPP == 24
-# define RENDERER nxf_convert_24bpp
-#elif CONFIG_NXTERM_BPP == 32
-# define RENDERER nxf_convert_32bpp
-#else
-# error "Unsupported CONFIG_NXTERM_BPP"
-#endif
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_freeglyph
- ****************************************************************************/
-
-static void nxcon_freeglyph(FAR struct nxcon_glyph_s *glyph)
-{
- if (glyph->bitmap)
- {
- kmm_free(glyph->bitmap);
- }
- memset(glyph, 0, sizeof(struct nxcon_glyph_s));
-}
-
-/****************************************************************************
- * Name: nxcon_allocglyph
- ****************************************************************************/
-
-static inline FAR struct nxcon_glyph_s *
-nxcon_allocglyph(FAR struct nxcon_state_s *priv)
-{
- FAR struct nxcon_glyph_s *glyph = NULL;
- FAR struct nxcon_glyph_s *luglyph = NULL;
- uint8_t luusecnt;
- int i;
-
- /* Search through the glyph cache looking for an unused glyph. Also, keep
- * track of the least used glyph as well. We need that if we have to replace
- * a glyph in the cache.
- */
-
- for (i = 0; i < priv->maxglyphs; i++)
- {
- /* Is this glyph in use? */
-
- glyph = &priv->glyph[i];
- if (!glyph->usecnt)
- {
- /* No.. return this glyph with a use count of one */
-
- glyph->usecnt = 1;
- return glyph;
- }
-
- /* Yes.. check for the least recently used */
-
- if (!luglyph || glyph->usecnt < luglyph->usecnt)
- {
- luglyph = glyph;
- }
- }
-
- /* If we get here, the glyph cache is full. We replace the least used
- * glyph with the one we need now. (luglyph can't be NULL).
- */
-
- luusecnt = luglyph->usecnt;
- nxcon_freeglyph(luglyph);
-
- /* But lets decrement all of the usecnts so that the new one one be so
- * far behind in the counts as the older ones.
- */
-
- if (luusecnt > 1)
- {
- uint8_t decr = luusecnt - 1;
-
- for (i = 0; i < priv->maxglyphs; i++)
- {
- /* Is this glyph in use? */
-
- glyph = &priv->glyph[i];
- if (glyph->usecnt > decr)
- {
- glyph->usecnt -= decr;
- }
- }
- }
-
- /* Then return the least used glyph */
-
- luglyph->usecnt = 1;
- return luglyph;
-}
-
-/****************************************************************************
- * Name: nxcon_findglyph
- ****************************************************************************/
-
-static FAR struct nxcon_glyph_s *
-nxcon_findglyph(FAR struct nxcon_state_s *priv, uint8_t ch)
-{
- int i;
-
- /* First, try to find the glyph in the cache of pre-rendered glyphs */
-
- for (i = 0; i < priv->maxglyphs; i++)
- {
- FAR struct nxcon_glyph_s *glyph = &priv->glyph[i];
- if (glyph->usecnt > 0 && glyph->code == ch)
- {
- /* Increment the use count (unless it is already at the max) */
-
- if (glyph->usecnt < MAX_USECNT)
- {
- glyph->usecnt++;
- }
-
- /* And return the glyph that we found */
-
- return glyph;
- }
- }
- return NULL;
-}
-
-/****************************************************************************
- * Name: nxcon_renderglyph
- ****************************************************************************/
-
-static inline FAR struct nxcon_glyph_s *
-nxcon_renderglyph(FAR struct nxcon_state_s *priv,
- FAR const struct nx_fontbitmap_s *fbm, uint8_t ch)
-{
- FAR struct nxcon_glyph_s *glyph = NULL;
- FAR nxgl_mxpixel_t *ptr;
-#if CONFIG_NXTERM_BPP < 8
- nxgl_mxpixel_t pixel;
-#endif
- int bmsize;
- int row;
- int col;
- int ret;
-
- /* Allocate the glyph (always succeeds) */
-
- glyph = nxcon_allocglyph(priv);
- glyph->code = ch;
-
- /* Get the dimensions of the glyph */
-
- glyph->width = fbm->metric.width + fbm->metric.xoffset;
- glyph->height = fbm->metric.height + fbm->metric.yoffset;
-
- /* Get the physical width of the glyph in bytes */
-
- glyph->stride = (glyph->width * CONFIG_NXTERM_BPP + 7) / 8;
-
- /* Allocate memory to hold the glyph with its offsets */
-
- bmsize = glyph->stride * glyph->height;
- glyph->bitmap = (FAR uint8_t *)kmm_malloc(bmsize);
-
- if (glyph->bitmap)
- {
- /* Initialize the glyph memory to the background color using the
- * hard-coded bits-per-pixel (BPP).
- *
- * TODO: The rest of NX is configured to support multiple devices
- * with differing BPP. They logic should be extended to support
- * differing BPP's as well.
- */
-
-#if CONFIG_NXTERM_BPP < 8
- pixel = priv->wndo.wcolor[0];
-
-# if CONFIG_NXTERM_BPP == 1
-
- /* Pack 1-bit pixels into a 2-bits */
-
- pixel &= 0x01;
- pixel = (pixel) << 1 | pixel;
-
-# endif
-# if CONFIG_NXTERM_BPP < 4
-
- /* Pack 2-bit pixels into a nibble */
-
- pixel &= 0x03;
- pixel = (pixel) << 2 | pixel;
-
-# endif
-
- /* Pack 4-bit nibbles into a byte */
-
- pixel &= 0x0f;
- pixel = (pixel) << 4 | pixel;
-
- ptr = (FAR nxgl_mxpixel_t *)glyph->bitmap;
- for (row = 0; row < glyph->height; row++)
- {
- for (col = 0; col < glyph->stride; col++)
- {
- /* Transfer the packed bytes into the buffer */
-
- *ptr++ = pixel;
- }
- }
-
-#elif CONFIG_NXTERM_BPP == 24
-# error "Additional logic is needed here for 24bpp support"
-
-#else /* CONFIG_NXTERM_BPP = {8,16,32} */
-
- ptr = (FAR nxgl_mxpixel_t *)glyph->bitmap;
- for (row = 0; row < glyph->height; row++)
- {
- /* Just copy the color value into the glyph memory */
-
- for (col = 0; col < glyph->width; col++)
- {
- *ptr++ = priv->wndo.wcolor[0];
- }
- }
-#endif
-
- /* Then render the glyph into the allocated memory */
-
- ret = RENDERER((FAR nxgl_mxpixel_t*)glyph->bitmap,
- glyph->height, glyph->width, glyph->stride,
- fbm, priv->wndo.fcolor[0]);
- if (ret < 0)
- {
- /* Actually, the RENDERER never returns a failure */
-
- gdbg("nxcon_renderglyph: RENDERER failed\n");
- nxcon_freeglyph(glyph);
- glyph = NULL;
- }
- }
-
- return glyph;
-}
-
-/****************************************************************************
- * Name: nxcon_fontsize
- ****************************************************************************/
-
-static int nxcon_fontsize(NXHANDLE hfont, uint8_t ch, FAR struct nxgl_size_s *size)
-{
- FAR const struct nx_fontbitmap_s *fbm;
-
- /* No, it is not cached... Does the code map to a font? */
-
- fbm = nxf_getbitmap(hfont, ch);
- if (fbm)
- {
- /* Yes.. return the font size */
-
- size->w = fbm->metric.width + fbm->metric.xoffset;
- size->h = fbm->metric.height + fbm->metric.yoffset;
- return OK;
- }
-
- return ERROR;
-}
-
-/****************************************************************************
- * Name: nxcon_getglyph
- ****************************************************************************/
-
-static FAR struct nxcon_glyph_s *
-nxcon_getglyph(NXHANDLE hfont, FAR struct nxcon_state_s *priv, uint8_t ch)
-{
- FAR struct nxcon_glyph_s *glyph;
- FAR const struct nx_fontbitmap_s *fbm;
-
- /* First, try to find the glyph in the cache of pre-rendered glyphs */
-
- glyph = nxcon_findglyph(priv, ch);
- if (glyph)
- {
- /* We found it in the cache .. return the cached glyph */
-
- return glyph;
- }
-
- /* No, it is not cached... Does the code map to a font? */
-
- fbm = nxf_getbitmap(hfont, ch);
- if (fbm)
- {
- /* Yes.. render the glyph */
-
- glyph = nxcon_renderglyph(priv, fbm, ch);
- }
-
- return glyph;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_addchar
- *
- * Description:
- * This is part of the nxcon_putc logic. It creates and positions a
- * the character and renders (or re-uses) a glyph for font.
- *
- ****************************************************************************/
-
-FAR const struct nxcon_bitmap_s *
-nxcon_addchar(NXHANDLE hfont, FAR struct nxcon_state_s *priv, uint8_t ch)
-{
- FAR struct nxcon_bitmap_s *bm = NULL;
- FAR struct nxcon_glyph_s *glyph;
-
- /* Is there space for another character on the display? */
-
- if (priv->nchars < priv->maxchars)
- {
- /* Yes, setup the bitmap information */
-
- bm = &priv->bm[priv->nchars];
- bm->code = ch;
- bm->flags = 0;
- bm->pos.x = priv->fpos.x;
- bm->pos.y = priv->fpos.y;
-
- /* Find (or create) the matching glyph */
-
- glyph = nxcon_getglyph(hfont, priv, ch);
- if (!glyph)
- {
- /* No, there is no font for this code. Just mark this as a space. */
-
- bm->flags |= BMFLAGS_NOGLYPH;
-
- /* Set up the next character position */
-
- priv->fpos.x += priv->spwidth;
- }
- else
- {
- /* Set up the next character position */
-
- priv->fpos.x += glyph->width;
- }
-
- /* Success.. increment nchars to retain this character */
-
- priv->nchars++;
- }
-
- return bm;
-}
-
-/****************************************************************************
- * Name: nxcon_hidechar
- *
- * Description:
- * Erase a character from the window.
- *
- ****************************************************************************/
-int nxcon_hidechar(FAR struct nxcon_state_s *priv,
- FAR const struct nxcon_bitmap_s *bm)
-{
- struct nxgl_rect_s bounds;
- struct nxgl_size_s fsize;
- int ret;
-
- /* Get the size of the font glyph. If nxcon_fontsize, then the
- * character will have been rendered as a space, and no display
- * modification is required (not an error).
- */
-
- ret = nxcon_fontsize(priv->font, bm->code, &fsize);
- if (ret < 0)
- {
- /* It was rendered as a space. */
-
- return OK;
- }
-
- /* Construct a bounding box for the glyph */
-
- bounds.pt1.x = bm->pos.x;
- bounds.pt1.y = bm->pos.y;
- bounds.pt2.x = bm->pos.x + fsize.w - 1;
- bounds.pt2.y = bm->pos.y + fsize.h - 1;
-
- /* Fill the bitmap region with the background color, erasing the
- * character from the display. NOTE: This region might actually
- * be obscured... NX will handle that case.
- */
-
- return priv->ops->fill(priv, &bounds, priv->wndo.wcolor);
-}
-
-/****************************************************************************
- * Name: nxcon_backspace
- *
- * Description:
- * Remove the last character from the window.
- *
- ****************************************************************************/
-
-int nxcon_backspace(FAR struct nxcon_state_s *priv)
-{
- FAR struct nxcon_bitmap_s *bm;
- int ndx;
- int ret = -ENOENT;
-
- /* Is there a character on the display? */
-
- if (priv->nchars > 0)
- {
- /* Yes.. Get the index to the last bitmap on the display */
-
- ndx = priv->nchars - 1;
- bm = &priv->bm[ndx];
-
- /* Erase the character from the display */
-
- ret = nxcon_hidechar(priv, bm);
-
- /* The current position to the location where the last character was */
-
- priv->fpos.x = bm->pos.x;
- priv->fpos.y = bm->pos.y;
-
- /* Decrement nchars to discard this character */
-
- priv->nchars = ndx;
- }
-
- return ret;
-}
-
-/****************************************************************************
- * Name: nxcon_home
- *
- * Description:
- * Set the next character position to the top-left corner of the display.
- *
- ****************************************************************************/
-
-void nxcon_home(FAR struct nxcon_state_s *priv)
-{
- /* The first character is one space from the left */
-
- priv->fpos.x = priv->spwidth;
-
- /* And CONFIG_NXTERM_LINESEPARATION lines from the top */
-
- priv->fpos.y = CONFIG_NXTERM_LINESEPARATION;
-}
-
-/****************************************************************************
- * Name: nxcon_newline
- *
- * Description:
- * Set the next character position to the beginning of the next line.
- *
- ****************************************************************************/
-
-void nxcon_newline(FAR struct nxcon_state_s *priv)
-{
- /* Carriage return: The first character is one space from the left */
-
- priv->fpos.x = priv->spwidth;
-
- /* Linefeed: Down the max font height + CONFIG_NXTERM_LINESEPARATION */
-
- priv->fpos.y += (priv->fheight + CONFIG_NXTERM_LINESEPARATION);
-}
-
-/****************************************************************************
- * Name: nxcon_fillchar
- *
- * Description:
- * This implements the character display. It is part of the nxcon_putc
- * operation but may also be used when redrawing an existing display.
- *
- ****************************************************************************/
-
-void nxcon_fillchar(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxcon_bitmap_s *bm)
-{
- FAR struct nxcon_glyph_s *glyph;
- struct nxgl_rect_s bounds;
- struct nxgl_rect_s intersection;
- struct nxgl_size_s fsize;
- int ret;
-
- /* Handle the special case of spaces which have no glyph bitmap */
-
- if (BM_ISSPACE(bm))
- {
- return;
- }
-
- /* Get the size of the font glyph (which may not have been created yet) */
-
- ret = nxcon_fontsize(priv->font, bm->code, &fsize);
- if (ret < 0)
- {
- /* This would mean that there is no bitmap for the character code and
- * that the font would be rendered as a space. But this case should
- * never happen here because the BM_ISSPACE() should have already
- * found all such cases.
- */
-
- return;
- }
-
- /* Construct a bounding box for the glyph */
-
- bounds.pt1.x = bm->pos.x;
- bounds.pt1.y = bm->pos.y;
- bounds.pt2.x = bm->pos.x + fsize.w - 1;
- bounds.pt2.y = bm->pos.y + fsize.h - 1;
-
- /* Should this also be clipped to a region in the window? */
-
- if (rect)
- {
- /* Get the intersection of the redraw region and the character bitmap */
-
- nxgl_rectintersect(&intersection, rect, &bounds);
- }
- else
- {
- /* The intersection is the whole glyph */
-
- nxgl_rectcopy(&intersection, &bounds);
- }
-
- /* Check for empty intersections */
-
- if (!nxgl_nullrect(&intersection))
- {
- FAR const void *src;
-
- /* Find (or create) the glyph that goes with this font */
-
- glyph = nxcon_getglyph(priv->font, priv, bm->code);
- if (!glyph)
- {
- /* Shouldn't happen */
-
- return;
- }
-
- /* Blit the font bitmap into the window */
-
- src = (FAR const void *)glyph->bitmap;
- ret = priv->ops->bitmap(priv, &intersection, &src,
- &bm->pos, (unsigned int)glyph->stride);
- DEBUGASSERT(ret >= 0);
- }
-}
-
diff --git a/nuttx/graphics/nxconsole/nxcon_internal.h b/nuttx/graphics/nxconsole/nxcon_internal.h
deleted file mode 100644
index 1f66c119b..000000000
--- a/nuttx/graphics/nxconsole/nxcon_internal.h
+++ /dev/null
@@ -1,254 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_internal.h
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __GRAPHICS_NXCONSOLE_NXCON_INTERNAL_H
-#define __GRAPHICS_NXCONSOLE_NXCON_INTERNAL_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <semaphore.h>
-
-#include <nuttx/fs/fs.h>
-
-#include <nuttx/nx/nx.h>
-#include <nuttx/nx/nxtk.h>
-#include <nuttx/nx/nxfonts.h>
-#include <nuttx/nx/nxconsole.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-/* NxConsole Definitions ****************************************************/
-/* Bitmap flags */
-
-#define BMFLAGS_NOGLYPH (1 << 0) /* No glyph available, use space */
-#define BM_ISSPACE(bm) (((bm)->flags & BMFLAGS_NOGLYPH) != 0)
-
-/* Sizes and maximums */
-
-#define MAX_USECNT 255 /* Limit to range of a uint8_t */
-
-/* Device path formats */
-
-#define NX_DEVNAME_FORMAT "/dev/nxcon%d"
-#define NX_DEVNAME_SIZE 16
-
-/* Semaphore protection */
-
-#define NO_HOLDER (pid_t)-1
-
-/* VT100 escape sequence processing */
-
-#define VT100_MAX_SEQUENCE 3
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-/* Identifies the state of the VT100 escape sequence processing */
-
-enum nxcon_vt100state_e
-{
- VT100_NOT_CONSUMED = 0, /* Character is not part of a VT100 escape sequence */
- VT100_CONSUMED, /* Character was consumed as part of the VT100 escape processing */
- VT100_PROCESSED, /* The full VT100 escape sequence was processed */
- VT100_ABORT /* Invalid/unsupported character in buffered escape sequence */
-};
-
-/* Describes on set of console window callbacks */
-
-struct nxcon_state_s;
-struct nxcon_operations_s
-{
- int (*fill)(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES]);
-#ifndef CONFIG_NX_WRITEONLY
- int (*move)(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset);
-#endif
- int (*bitmap)(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride);
-};
-
-/* Describes one cached glyph bitmap */
-
-struct nxcon_glyph_s
-{
- uint8_t code; /* Character code */
- uint8_t height; /* Height of this glyph (in rows) */
- uint8_t width; /* Width of this glyph (in pixels) */
- uint8_t stride; /* Width of the glyph row (in bytes) */
- uint8_t usecnt; /* Use count */
- FAR uint8_t *bitmap; /* Allocated bitmap memory */
-};
-
-/* Describes on character on the display */
-
-struct nxcon_bitmap_s
-{
- uint8_t code; /* Character code */
- uint8_t flags; /* See BMFLAGS_* */
- struct nxgl_point_s pos; /* Character position */
-};
-
-/* Describes the state of one NX console driver*/
-
-struct nxcon_state_s
-{
- FAR const struct nxcon_operations_s *ops; /* Window operations */
- FAR void *handle; /* The window handle */
- FAR struct nxcon_window_s wndo; /* Describes the window and font */
- NXHANDLE font; /* The current font handle */
- sem_t exclsem; /* Forces mutually exclusive access */
-#ifdef CONFIG_DEBUG
- pid_t holder; /* Deadlock avoidance */
-#endif
- uint8_t minor; /* Device minor number */
-
- /* Text output support */
-
- uint8_t fheight; /* Max height of a font in pixels */
- uint8_t fwidth; /* Max width of a font in pixels */
- uint8_t spwidth; /* The width of a space */
- uint8_t maxglyphs; /* Size of the glyph[] array */
-
- uint16_t maxchars; /* Size of the bm[] array */
- uint16_t nchars; /* Number of chars in the bm[] array */
-
- struct nxgl_point_s fpos; /* Next display position */
-
- /* VT100 escape sequence processing */
-
- char seq[VT100_MAX_SEQUENCE]; /* Buffered characters */
- uint8_t nseq; /* Number of buffered characters */
-
- /* Font cache data storage */
-
- struct nxcon_bitmap_s cursor;
- struct nxcon_bitmap_s bm[CONFIG_NXTERM_MXCHARS];
-
- /* Glyph cache data storage */
-
- struct nxcon_glyph_s glyph[CONFIG_NXTERM_CACHESIZE];
-
- /* Keyboard input support */
-
-#ifdef CONFIG_NXTERM_NXKBDIN
- sem_t waitsem; /* Supports waiting for input data */
- uint8_t nwaiters; /* Number of threads waiting for data */
- uint8_t head; /* rxbuffer head/input index */
- uint8_t tail; /* rxbuffer tail/output index */
-
- uint8_t rxbuffer[CONFIG_NXTERM_KBDBUFSIZE];
-
- /* The following is a list if poll structures of threads waiting for
- * driver events. The 'struct pollfd' reference for each open is also
- * retained in the f_priv field of the 'struct file'.
- */
-
-#ifndef CONFIG_DISABLE_POLL
- struct pollfd *fds[CONFIG_NXTERM_NPOLLWAITERS];
-#endif
-#endif /* CONFIG_NXTERM_NXKBDIN */
-};
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/* This is the common NX driver file operations */
-
-extern const struct file_operations g_nxcon_drvrops;
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-/* Semaphore helpers */
-
-#ifdef CONFIG_DEBUG
-int nxcon_semwait(FAR struct nxcon_state_s *priv);
-int nxcon_sempost(FAR struct nxcon_state_s *priv);
-#else
-# define nxcon_semwait(p) sem_wait(&p->exclsem)
-# define nxcon_sempost(p) sem_post(&p->exclsem)
-#endif
-
-/* Common device registration */
-
-FAR struct nxcon_state_s *nxcon_register(NXCONSOLE handle,
- FAR struct nxcon_window_s *wndo, FAR const struct nxcon_operations_s *ops,
- int minor);
-
-#ifdef CONFIG_NXTERM_NXKBDIN
-ssize_t nxcon_read(FAR struct file *filep, FAR char *buffer, size_t len);
-#ifndef CONFIG_DISABLE_POLL
-int nxcon_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup);
-#endif
-#endif
-
-/* VT100 Terminal emulation */
-
-enum nxcon_vt100state_e nxcon_vt100(FAR struct nxcon_state_s *priv, char ch);
-
-/* Generic text display helpers */
-
-void nxcon_home(FAR struct nxcon_state_s *priv);
-void nxcon_newline(FAR struct nxcon_state_s *priv);
-FAR const struct nxcon_bitmap_s *nxcon_addchar(NXHANDLE hfont,
- FAR struct nxcon_state_s *priv, uint8_t ch);
-int nxcon_hidechar(FAR struct nxcon_state_s *priv,
- FAR const struct nxcon_bitmap_s *bm);
-int nxcon_backspace(FAR struct nxcon_state_s *priv);
-void nxcon_fillchar(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect, FAR const struct nxcon_bitmap_s *bm);
-
-void nxcon_putc(FAR struct nxcon_state_s *priv, uint8_t ch);
-void nxcon_showcursor(FAR struct nxcon_state_s *priv);
-void nxcon_hidecursor(FAR struct nxcon_state_s *priv);
-
-/* Scrolling support */
-
-void nxcon_scroll(FAR struct nxcon_state_s *priv, int scrollheight);
-
-#endif /* __GRAPHICS_NXCONSOLE_NXCON_INTERNAL_H */
diff --git a/nuttx/graphics/nxconsole/nxcon_kbdin.c b/nuttx/graphics/nxconsole/nxcon_kbdin.c
deleted file mode 100644
index fa7990a71..000000000
--- a/nuttx/graphics/nxconsole/nxcon_kbdin.c
+++ /dev/null
@@ -1,489 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_kbdin.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <fcntl.h>
-#include <sched.h>
-#include <assert.h>
-#include <poll.h>
-#include <errno.h>
-#include <debug.h>
-
-#include "nxcon_internal.h"
-
-#ifdef CONFIG_NXTERM_NXKBDIN
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_pollnotify
- ****************************************************************************/
-
-#ifndef CONFIG_DISABLE_POLL
-static void nxcon_pollnotify(FAR struct nxcon_state_s *priv, pollevent_t eventset)
-{
- FAR struct pollfd *fds;
- irqstate_t flags;
- int i;
-
- /* This function may be called from an interrupt handler */
-
- for (i = 0; i < CONFIG_NXTERM_NPOLLWAITERS; i++)
- {
- flags = irqsave();
- fds = priv->fds[i];
- if (fds)
- {
- fds->revents |= (fds->events & eventset);
- if (fds->revents != 0)
- {
- sem_post(fds->sem);
- }
- }
- irqrestore(flags);
- }
-}
-#else
-# define nxcon_pollnotify(priv,event)
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_read
- *
- * Description:
- * The optional NxConsole read method
- *
- ****************************************************************************/
-
-ssize_t nxcon_read(FAR struct file *filep, FAR char *buffer, size_t len)
-{
- FAR struct nxcon_state_s *priv;
- ssize_t nread;
- char ch;
- int ret;
-
- /* Recover our private state structure */
-
- DEBUGASSERT(filep && filep->f_priv);
- priv = (FAR struct nxcon_state_s *)filep->f_priv;
-
- /* Get exclusive access to the driver structure */
-
- ret = nxcon_semwait(priv);
- if (ret < 0)
- {
- gdbg("ERROR: nxcon_semwait failed\n");
- return ret;
- }
-
- /* Loop until something is read */
-
- for (nread = 0; nread < len; )
- {
- /* Get the next byte from the buffer */
-
- if (priv->head == priv->tail)
- {
- /* The circular buffer is empty. Did we read anything? */
-
- if (nread > 0)
- {
- /* Yes.. break out to return what we have. */
-
- break;
- }
-
- /* If the driver was opened with O_NONBLOCK option, then don't wait.
- * Just return EGAIN.
- */
-
- if (filep->f_oflags & O_NONBLOCK)
- {
- nread = -EAGAIN;
- break;
- }
-
- /* Otherwise, wait for something to be written to the circular
- * buffer. Increment the number of waiters so that the nxcon_write()
- * will not that it needs to post the semaphore to wake us up.
- */
-
- sched_lock();
- priv->nwaiters++;
- nxcon_sempost(priv);
-
- /* We may now be pre-empted! But that should be okay because we
- * have already incremented nwaiters. Pre-emption is disabled
- * but will be re-enabled while we are waiting.
- */
-
- ret = sem_wait(&priv->waitsem);
-
- /* Pre-emption will be disabled when we return. So the decrementing
- * nwaiters here is safe.
- */
-
- priv->nwaiters--;
- sched_unlock();
-
- /* Did we successfully get the waitsem? */
-
- if (ret >= 0)
- {
- /* Yes... then retake the mutual exclusion semaphore */
-
- ret = nxcon_semwait(priv);
- }
-
- /* Was the semaphore wait successful? Did we successful re-take the
- * mutual exclusion semaphore?
- */
-
- if (ret < 0)
- {
- /* No.. One of the two sem_wait's failed. */
-
- int errval = errno;
-
- gdbg("ERROR: nxcon_semwait failed\n");
-
- /* Were we awakened by a signal? Did we read anything before
- * we received the signal?
- */
-
- if (errval != EINTR || nread >= 0)
- {
- /* Yes.. return the error. */
-
- nread = -errval;
- }
-
- /* Break out to return what we have. Note, we can't exactly
- * "break" out because whichever error occurred, we do not hold
- * the exclusion semaphore.
- */
-
- goto errout_without_sem;
- }
- }
- else
- {
- /* The circular buffer is not empty, get the next byte from the
- * tail index.
- */
-
- ch = priv->rxbuffer[priv->tail];
-
- /* Increment the tail index and re-enable interrupts */
-
- if (++priv->tail >= CONFIG_NXTERM_KBDBUFSIZE)
- {
- priv->tail = 0;
- }
-
- /* Add the character to the user buffer */
-
- buffer[nread] = ch;
- nread++;
- }
- }
-
- /* Relinquish the mutual exclusion semaphore */
-
- nxcon_sempost(priv);
-
- /* Notify all poll/select waiters that they can write to the FIFO */
-
-errout_without_sem:
-
-#ifndef CONFIG_DISABLE_POLL
- if (nread > 0)
- {
- nxcon_pollnotify(priv, POLLOUT);
- }
-#endif
-
- /* Return the number of characters actually read */
-
- return nread;
-}
-
-/****************************************************************************
- * Name: nxcon_poll
- ****************************************************************************/
-
-#ifndef CONFIG_DISABLE_POLL
-int nxcon_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
-{
- FAR struct inode *inode = filep->f_inode;
- FAR struct nxcon_state_s *priv;
- pollevent_t eventset;
- int ret;
- int i;
-
- /* Some sanity checking */
-
- DEBUGASSERT(inode && inode->i_private);
- priv = inode->i_private;
-
- /* Get exclusive access to the driver structure */
-
- ret = nxcon_semwait(priv);
- if (ret < 0)
- {
- gdbg("ERROR: nxcon_semwait failed\n");
- return ret;
- }
-
- /* Are we setting up the poll? Or tearing it down? */
-
- if (setup)
- {
- /* This is a request to set up the poll. Find an available
- * slot for the poll structure reference
- */
-
- for (i = 0; i < CONFIG_NXTERM_NPOLLWAITERS; i++)
- {
- /* Find an available slot */
-
- if (!priv->fds[i])
- {
- /* Bind the poll structure and this slot */
-
- priv->fds[i] = fds;
- fds->priv = &priv->fds[i];
- break;
- }
- }
-
- if (i >= CONFIG_NXTERM_NPOLLWAITERS)
- {
- gdbg("ERROR: Too many poll waiters\n");
-
- fds->priv = NULL;
- ret = -EBUSY;
- goto errout;
- }
-
- /* Should immediately notify on any of the requested events?
- * This driver is always available for transmission.
- */
-
- eventset = POLLOUT;
-
- /* Check if the receive buffer is empty */
-
- if (priv->head != priv->tail)
- {
- eventset |= POLLIN;
- }
-
- if (eventset)
- {
- nxcon_pollnotify(priv, eventset);
- }
-
- }
- else if (fds->priv)
- {
- /* This is a request to tear down the poll. */
-
- struct pollfd **slot = (struct pollfd **)fds->priv;
-
-#ifdef CONFIG_DEBUG
- if (!slot)
- {
- gdbg("ERROR: No slot\n");
-
- ret = -EIO;
- goto errout;
- }
-#endif
-
- /* Remove all memory of the poll setup */
-
- *slot = NULL;
- fds->priv = NULL;
- }
-
-errout:
- nxcon_sempost(priv);
- return ret;
-}
-#endif
-
-/****************************************************************************
- * Name: nxcon_kbdin
- *
- * Description:
- * This function should be driven by the window kbdin callback function
- * (see nx.h). When the NxConsole is the top window and keyboard input is
- * received on the top window, that window callback should be directed to
- * this function. This function will buffer the keyboard data and makE
- * it available to the NxConsole as stdin.
- *
- * If CONFIG_NXTERM_NXKBDIN is not selected, then the NxConsole will
- * receive its input from stdin (/dev/console). This works great but
- * cannot be shared between different windows. Chaos will ensue if you
- * try to support multiple NxConsole windows without CONFIG_NXTERM_NXKBDIN
- *
- * Input Parameters:
- * handle - A handle previously returned by nx_register, nxtk_register, or
- * nxtool_register.
- * buffer - The array of characters
- * buflen - The number of characters that are available in buffer[]
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxcon_kbdin(NXCONSOLE handle, FAR const uint8_t *buffer, uint8_t buflen)
-{
- FAR struct nxcon_state_s *priv;
- ssize_t nwritten;
- int nexthead;
- char ch;
- int ret;
-
- gvdbg("buflen=%d\n");
- DEBUGASSERT(handle);
-
- /* Get the reference to the driver structure from the handle */
-
- priv = (FAR struct nxcon_state_s *)handle;
-
- /* Get exclusive access to the driver structure */
-
- ret = nxcon_semwait(priv);
- if (ret < 0)
- {
- gdbg("ERROR: nxcon_semwait failed\n");
- return;
- }
-
- /* Loop until all of the bytes have been written. This function may be
- * called from an interrupt handler! Semaphores cannot be used!
- *
- * The write logic only needs to modify the head index. Therefore,
- * there is a difference in the way that head and tail are protected:
- * tail is protected with a semaphore; tail is protected by disabling
- * interrupts.
- */
-
- for (nwritten = 0; nwritten < buflen; nwritten++)
- {
- /* Add the next character */
-
- ch = buffer[nwritten];
-
- /* Calculate the write index AFTER the next byte is add to the ring
- * buffer
- */
-
- nexthead = priv->head + 1;
- if (nexthead >= CONFIG_NXTERM_KBDBUFSIZE)
- {
- nexthead = 0;
- }
-
- /* Would the next write overflow the circular buffer? */
-
- if (nexthead == priv->tail)
- {
- /* Yes... Return an indication that nothing was saved in the buffer. */
-
- gdbg("ERROR: Keyboard data overrun\n");
- break;
- }
-
- /* No... copy the byte */
-
- priv->rxbuffer[priv->head] = ch;
- priv->head = nexthead;
- }
-
- /* Was anything written? */
-
- if (nwritten > 0)
- {
- int i;
-
- /* Are there threads waiting for read data? */
-
- sched_lock();
- for (i = 0; i < priv->nwaiters; i++)
- {
- /* Yes.. Notify all of the waiting readers that more data is available */
-
- sem_post(&priv->waitsem);
- }
-
- /* Notify all poll/select waiters that they can write to the FIFO */
-
-#ifndef CONFIG_DISABLE_POLL
- nxcon_pollnotify(priv, POLLIN);
-#endif
- sched_unlock();
- }
-
- nxcon_sempost(priv);
-}
-
-#endif /* CONFIG_NXTERM_NXKBDIN */
diff --git a/nuttx/graphics/nxconsole/nxcon_putc.c b/nuttx/graphics/nxconsole/nxcon_putc.c
deleted file mode 100644
index f612b2eb3..000000000
--- a/nuttx/graphics/nxconsole/nxcon_putc.c
+++ /dev/null
@@ -1,203 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_putc.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <nuttx/ascii.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_putc
- *
- * Description:
- * Render the specified character at the current display position.
- *
- ****************************************************************************/
-
-void nxcon_putc(FAR struct nxcon_state_s *priv, uint8_t ch)
-{
- FAR const struct nxcon_bitmap_s *bm;
- int lineheight;
-
- /* Ignore carriage returns */
-
- if (ch == '\r')
- {
- return;
- }
-
- /* Handle backspace (treating both BS and DEL as backspace) */
-
- if (ch == ASCII_BS || ch == ASCII_DEL)
- {
- nxcon_backspace(priv);
- return;
- }
-
- /* Will another character fit on this line? */
-
- if (priv->fpos.x + priv->fwidth > priv->wndo.wsize.w)
- {
-#ifndef CONFIG_NXTERM_NOWRAP
- /* No.. move to the next line */
-
- nxcon_newline(priv);
-
- /* If we were about to output a newline character, then don't */
-
- if (ch == '\n')
- {
- return;
- }
-#else
- /* No.. Ignore all further characters until a newline is encountered */
-
- if (ch != '\n')
- {
- return;
- }
-#endif
- }
-
- /* If it is a newline character, then just perform the logical newline
- * operation.
- */
-
- if (ch == '\n')
- {
- nxcon_newline(priv);
- return;
- }
-
- /* Check if we need to scroll up */
-
- lineheight = (priv->fheight + CONFIG_NXTERM_LINESEPARATION);
- while (priv->fpos.y >= priv->wndo.wsize.h - lineheight)
- {
- nxcon_scroll(priv, lineheight);
- }
-
- /* Find the glyph associated with the character and render it onto the
- * display.
- */
-
- bm = nxcon_addchar(priv->font, priv, ch);
- if (bm)
- {
- nxcon_fillchar(priv, NULL, bm);
- }
-}
-
-/****************************************************************************
- * Name: nxcon_showcursor
- *
- * Description:
- * Render the cursor character at the current display position.
- *
- ****************************************************************************/
-
-void nxcon_showcursor(FAR struct nxcon_state_s *priv)
-{
- int lineheight;
-
- /* Will another character fit on this line? */
-
- if (priv->fpos.x + priv->fwidth > priv->wndo.wsize.w)
- {
-#ifndef CONFIG_NXTERM_NOWRAP
- /* No.. move to the next line */
-
- nxcon_newline(priv);
-#else
- return;
-#endif
- }
-
- /* Check if we need to scroll up */
-
- lineheight = (priv->fheight + CONFIG_NXTERM_LINESEPARATION);
- while (priv->fpos.y >= priv->wndo.wsize.h - lineheight)
- {
- nxcon_scroll(priv, lineheight);
- }
-
- /* Render the cursor glyph onto the display. */
-
- priv->cursor.pos.x = priv->fpos.x;
- priv->cursor.pos.y = priv->fpos.y;
- nxcon_fillchar(priv, NULL, &priv->cursor);
-}
-
-/****************************************************************************
- * Name: nxcon_hidecursor
- *
- * Description:
- * Render the cursor cursor character from the display.
- *
- ****************************************************************************/
-
-void nxcon_hidecursor(FAR struct nxcon_state_s *priv)
-{
- (void)nxcon_hidechar(priv, &priv->cursor);
-}
diff --git a/nuttx/graphics/nxconsole/nxcon_redraw.c b/nuttx/graphics/nxconsole/nxcon_redraw.c
deleted file mode 100644
index b1363454c..000000000
--- a/nuttx/graphics/nxconsole/nxcon_redraw.c
+++ /dev/null
@@ -1,153 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_bkgd.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <semaphore.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/nx/nx.h>
-#include <nuttx/nx/nxglib.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_redraw
- *
- * Description:
- * Re-draw a portion of the NX console. This function should be called
- * from the appropriate window callback logic.
- *
- * Input Parameters:
- * handle - A handle previously returned by nx_register, nxtk_register, or
- * nxtool_register.
- * rect - The rectangle that needs to be re-drawn (in window relative
- * coordinates)
- * more - true: More re-draw requests will follow
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxcon_redraw(NXCONSOLE handle, FAR const struct nxgl_rect_s *rect, bool more)
-{
- FAR struct nxcon_state_s *priv;
- int ret;
- int i;
-
- DEBUGASSERT(handle && rect);
- gvdbg("rect={(%d,%d),(%d,%d)} more=%s\n",
- rect->pt1.x, rect->pt1.y, rect->pt2.x, rect->pt2.y,
- more ? "true" : "false");
-
- /* Recover our private state structure */
-
- priv = (FAR struct nxcon_state_s *)handle;
-
- /* Get exclusive access to the state structure */
-
- do
- {
- ret = nxcon_semwait(priv);
-
- /* Check for errors */
-
- if (ret < 0)
- {
- /* The only expected error is if the wait failed because of it
- * was interrupted by a signal.
- */
-
- DEBUGASSERT(errno == EINTR);
- }
- }
- while (ret < 0);
-
- /* Fill the rectangular region with the window background color */
-
- ret = priv->ops->fill(priv, rect, priv->wndo.wcolor);
- if (ret < 0)
- {
- gdbg("fill failed: %d\n", errno);
- }
-
- /* Then redraw each character on the display (Only the characters within
- * the rectangle will actually be redrawn).
- */
-
- for (i = 0; i < priv->nchars; i++)
- {
- nxcon_fillchar(priv, rect, &priv->bm[i]);
- }
-
- (void)nxcon_sempost(priv);
-}
diff --git a/nuttx/graphics/nxconsole/nxcon_register.c b/nuttx/graphics/nxconsole/nxcon_register.c
deleted file mode 100644
index 67859922f..000000000
--- a/nuttx/graphics/nxconsole/nxcon_register.c
+++ /dev/null
@@ -1,160 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_register.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdbool.h>
-#include <stdio.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/fs/fs.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_allocate
- ****************************************************************************/
-
-FAR struct nxcon_state_s *
- nxcon_register(NXCONSOLE handle, FAR struct nxcon_window_s *wndo,
- FAR const struct nxcon_operations_s *ops, int minor)
-{
- FAR struct nxcon_state_s *priv;
- char devname[NX_DEVNAME_SIZE];
- int ret;
-
- DEBUGASSERT(handle && wndo && ops && (unsigned)minor < 256);
-
- /* Allocate the driver structure */
-
- priv = (FAR struct nxcon_state_s *)kmm_zalloc(sizeof(struct nxcon_state_s));
- if (!priv)
- {
- gdbg("Failed to allocate the NX driver structure\n");
- return NULL;
- }
-
- /* Initialize the driver structure */
-
- priv->ops = ops;
- priv->handle = handle;
- priv->minor = minor;
- memcpy(&priv->wndo, wndo, sizeof( struct nxcon_window_s));
-
- sem_init(&priv->exclsem, 0, 1);
-#ifdef CONFIG_DEBUG
- priv->holder = NO_HOLDER;
-#endif
-
-#ifdef CONFIG_NXTERM_NXKBDIN
- sem_init(&priv->waitsem, 0, 0);
-#endif
-
- /* Select the font */
-
- priv->font = nxf_getfonthandle(wndo->fontid);
- if (!priv->font)
- {
- gdbg("Failed to get font ID %d: %d\n", wndo->fontid, errno);
- goto errout;
- }
-
- FAR const struct nx_font_s *fontset;
-
- /* Get information about the font set being used and save this in the
- * state structure
- */
-
- fontset = nxf_getfontset(priv->font);
- priv->fheight = fontset->mxheight;
- priv->fwidth = fontset->mxwidth;
- priv->spwidth = fontset->spwidth;
-
- /* Set up the text cache */
-
- priv->maxchars = CONFIG_NXTERM_MXCHARS;
-
- /* Set up the font glyph bitmap cache */
-
- priv->maxglyphs = CONFIG_NXTERM_CACHESIZE;
-
- /* Set the initial display position */
-
- nxcon_home(priv);
-
- /* Show the cursor */
-
- priv->cursor.code = CONFIG_NXTERM_CURSORCHAR;
- nxcon_showcursor(priv);
-
- /* Register the driver */
-
- snprintf(devname, NX_DEVNAME_SIZE, NX_DEVNAME_FORMAT, minor);
- ret = register_driver(devname, &g_nxcon_drvrops, 0666, priv);
- if (ret < 0)
- {
- gdbg("Failed to register %s\n", devname);
- }
- return (NXCONSOLE)priv;
-
-errout:
- kmm_free(priv);
- return NULL;
-}
diff --git a/nuttx/graphics/nxconsole/nxcon_scroll.c b/nuttx/graphics/nxconsole/nxcon_scroll.c
deleted file mode 100644
index 7c645976c..000000000
--- a/nuttx/graphics/nxconsole/nxcon_scroll.c
+++ /dev/null
@@ -1,253 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_scroll.c
- *
- * Copyright (C) 2012, 2014 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <semaphore.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/nx/nx.h>
-#include <nuttx/nx/nxfonts.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_movedisplay
- *
- * Description:
- * This function implements the data movement for the scroll operation. If
- * we can read the displays framebuffer memory, then the job is pretty
- * easy. However, many displays (such as SPI-based LCDs) are often read-
- * only.
- ****************************************************************************/
-
-#ifdef CONFIG_NX_WRITEONLY
-static inline void nxcon_movedisplay(FAR struct nxcon_state_s *priv,
- int bottom, int scrollheight)
-{
- FAR struct nxcon_bitmap_s *bm;
- struct nxgl_rect_s rect;
- nxgl_coord_t row;
- int ret;
- int i;
-
- /* Move each row, one at a time. They could all be moved at once (by calling
- * nxcon_redraw), but the since the region is cleared, then re-written, the
- * effect would not be good. Below the region is also cleared and re-written,
- * however, in much smaller chunks.
- */
-
- rect.pt1.x = 0;
- rect.pt2.x = priv->wndo.wsize.w - 1;
-
- for (row = CONFIG_NXTERM_LINESEPARATION; row < bottom; row += scrollheight)
- {
- /* Create a bounding box the size of one row of characters */
-
- rect.pt1.y = row;
- rect.pt2.y = row + scrollheight - 1;
-
- /* Clear the region */
-
- ret = priv->ops->fill(priv, &rect, priv->wndo.wcolor);
- if (ret < 0)
- {
- gdbg("Fill failed: %d\n", errno);
- }
-
- /* Fill each character that might lie within in the bounding box */
-
- for (i = 0; i < priv->nchars; i++)
- {
- bm = &priv->bm[i];
- if (bm->pos.y <= rect.pt2.y && bm->pos.y + priv->fheight >= rect.pt1.y)
- {
- nxcon_fillchar(priv, &rect, bm);
- }
- }
- }
-
- /* Finally, clear the vacated part of the display */
-
- rect.pt1.y = bottom;
- rect.pt2.y = priv->wndo.wsize.h- 1;
-
- ret = priv->ops->fill(priv, &rect, priv->wndo.wcolor);
- if (ret < 0)
- {
- gdbg("Fill failed: %d\n", errno);
- }
-}
-#else
-static inline void nxcon_movedisplay(FAR struct nxcon_state_s *priv,
- int bottom, int scrollheight)
-{
- struct nxgl_rect_s rect;
- struct nxgl_point_s offset;
- int ret;
-
- /* Add the line separation value to the scroll height */
-
- scrollheight += CONFIG_NXTERM_LINESEPARATION;
-
- /* Move the display in the range of 0-height up one scrollheight. The
- * line at the bottom will be reset to the background color automatically.
- *
- * The source rectangle to be moved.
- */
-
- rect.pt1.x = 0;
- rect.pt1.y = scrollheight;
- rect.pt2.x = priv->wndo.wsize.w - 1;
- rect.pt2.y = priv->wndo.wsize.h - 1;
-
- /* The offset that determines how far to move the source rectangle */
-
- offset.x = 0;
- offset.y = -scrollheight;
-
- /* Move the source rectangle upward by the scrollheight */
-
- ret = priv->ops->move(priv, &rect, &offset);
- if (ret < 0)
- {
- gdbg("Move failed: %d\n", errno);
- }
-
- /* Finally, clear the vacated bottom part of the display */
-
- rect.pt1.y = priv->wndo.wsize.h - scrollheight;
-
- ret = priv->ops->fill(priv, &rect, priv->wndo.wcolor);
- if (ret < 0)
- {
- gdbg("Fill failed: %d\n", errno);
- }
-}
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_scroll
- ****************************************************************************/
-
-void nxcon_scroll(FAR struct nxcon_state_s *priv, int scrollheight)
-{
- int i;
- int j;
-
- /* Adjust the vertical position of each character */
-
- for (i = 0; i < priv->nchars; )
- {
- FAR struct nxcon_bitmap_s *bm = &priv->bm[i];
-
- /* Has any part of this character scrolled off the screen? */
-
- if (bm->pos.y < scrollheight + CONFIG_NXTERM_LINESEPARATION)
- {
- /* Yes... Delete the character by moving all of the data */
-
- for (j = i; j < priv->nchars-1; j++)
- {
- memcpy(&priv->bm[j], &priv->bm[j+1], sizeof(struct nxcon_bitmap_s));
- }
-
- /* Decrement the number of cached characters ('i' is not incremented
- * in this case because it already points to the next character)
- */
-
- priv->nchars--;
- }
-
- /* No.. just decrement its vertical position (moving it "up" the
- * display by one line).
- */
-
- else
- {
- bm->pos.y -= scrollheight;
-
- /* We are keeping this one so increment to the next character */
-
- i++;
- }
- }
-
- /* And move the next display position up by one line as well */
-
- priv->fpos.y -= scrollheight;
-
- /* Move the display in the range of 0-height up one scrollheight. */
-
- nxcon_movedisplay(priv, priv->fpos.y, scrollheight);
-}
diff --git a/nuttx/graphics/nxconsole/nxcon_sem.c b/nuttx/graphics/nxconsole/nxcon_sem.c
deleted file mode 100644
index 26036c2f4..000000000
--- a/nuttx/graphics/nxconsole/nxcon_sem.c
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_sem.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <unistd.h>
-#include <semaphore.h>
-#include <assert.h>
-#include <errno.h>
-
-#include "nxcon_internal.h"
-
-#ifdef CONFIG_DEBUG
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_semwait and nxcon_sempost
- *
- * Description:
- * If debug is on, then lower level code may attempt console output while
- * we are doing console output! In this case, we will toss the nested
- * output to avoid deadlocks and infinite loops.
- *
- * Input Parameters:
- * priv - Driver data structure
- *
- * Returned Value:
- *
- *
- ****************************************************************************/
-
-int nxcon_semwait(FAR struct nxcon_state_s *priv)
-{
- pid_t me;
- int ret;
-
- /* Does I already hold the semaphore */
-
- me = getpid();
- if (priv->holder != me)
- {
- /* No.. then wait until the thread that does hold it is finished with it */
-
- ret = sem_wait(&priv->exclsem);
- if (ret == OK)
- {
- /* No I hold the semaphore */
-
- priv->holder = me;
- }
- return ret;
- }
-
- /* Abort, abort, abort! I have been re-entered */
-
- set_errno(EBUSY);
- return ERROR;
-}
-
-int nxcon_sempost(FAR struct nxcon_state_s *priv)
-{
- pid_t me = getpid();
-
- /* Make sure that I really hold the semaphore */
-
- ASSERT(priv->holder == me);
-
- /* Then let go of it */
-
- priv->holder = NO_HOLDER;
- return sem_post(&priv->exclsem);
-}
-
-#endif /* CONFIG_DEBUG */
diff --git a/nuttx/graphics/nxconsole/nxcon_unregister.c b/nuttx/graphics/nxconsole/nxcon_unregister.c
deleted file mode 100644
index 2ebfdf7ec..000000000
--- a/nuttx/graphics/nxconsole/nxcon_unregister.c
+++ /dev/null
@@ -1,123 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_unregister.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdbool.h>
-#include <stdio.h>
-#include <string.h>
-#include <errno.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/nx/nxconsole.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_unregister
- *
- * Description:
- * Un-register to NX console device.
- *
- * Input Parameters:
- * handle - A handle previously returned by nx_register, nxtk_register, or
- * nxtool_register.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxcon_unregister(NXCONSOLE handle)
-{
- FAR struct nxcon_state_s *priv;
- char devname[NX_DEVNAME_SIZE];
- int i;
-
- DEBUGASSERT(handle);
-
- /* Get the reference to the driver structure from the handle */
-
- priv = (FAR struct nxcon_state_s *)handle;
- sem_destroy(&priv->exclsem);
-#ifdef CONFIG_NXTERM_NXKBDIN
- sem_destroy(&priv->waitsem);
-#endif
-
- /* Free all allocated glyph bitmap */
-
- for (i = 0; i < CONFIG_NXTERM_CACHESIZE; i++)
- {
- FAR struct nxcon_glyph_s *glyph = &priv->glyph[i];
- if (glyph->bitmap)
- {
- kmm_free(glyph->bitmap);
- }
- }
-
- /* Unregister the driver */
-
- snprintf(devname, NX_DEVNAME_SIZE, NX_DEVNAME_FORMAT, priv->minor);
- (void)unregister_driver(devname);
-
- /* Free the private data structure */
-
- kmm_free(handle);
-}
diff --git a/nuttx/graphics/nxconsole/nxcon_vt100.c b/nuttx/graphics/nxconsole/nxcon_vt100.c
deleted file mode 100644
index 3e3374dce..000000000
--- a/nuttx/graphics/nxconsole/nxcon_vt100.c
+++ /dev/null
@@ -1,289 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_vt100.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <string.h>
-#include <assert.h>
-
-#include <nuttx/vt100.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-typedef int (*seqhandler_t)(FAR struct nxcon_state_s *priv);
-
-struct vt100_sequence_s
-{
- FAR const char *seq;
- seqhandler_t handler;
- uint8_t size;
-};
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int nxcon_erasetoeol(FAR struct nxcon_state_s *priv);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* All recognized VT100 escape sequences. Very little as present, this is
- * a placeholder for a future, more complete VT100 emulation.
- */
-
-/* <esc>[K is the VT100 command erases to the end of the line. */
-
-static const char g_erasetoeol[] = VT100_CLEAREOL;
-
-/* The list of all VT100 sequences supported by the emulation */
-
-static const struct vt100_sequence_s g_vt100sequences[] =
-{
- {g_erasetoeol, nxcon_erasetoeol, sizeof(g_erasetoeol)},
- {NULL, NULL, 0}
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_erasetoeol
- *
- * Description:
- * Handle the erase-to-eol VT100 escapte sequence
- *
- * Input Parameters:
- * priv - Driver data structure
- *
- * Returned Value:
- * The index of the match in g_vt100sequences[]
- *
- ****************************************************************************/
-
-static int nxcon_erasetoeol(FAR struct nxcon_state_s *priv)
-{
- /* Does nothing yet (other than consume the sequence) */
-
- return OK;
-}
-
-/****************************************************************************
- * Name: nxcon_vt100part
- *
- * Description:
- * Return the next entry that is a partial match to the sequence.
- *
- * Input Parameters:
- * priv - Driver data structure
- * seqsize - The number of bytes in the sequence
- * startndx - The index to start searching
- *
- * Returned Value:
- * A pointer to the matching sequence in g_vt100sequences[]
- *
- ****************************************************************************/
-
-FAR const struct vt100_sequence_s *
-nxcon_vt100part(FAR struct nxcon_state_s *priv, int seqsize)
-{
- FAR const struct vt100_sequence_s *seq;
- int ndx;
-
- /* Search from the beginning of the sequence table */
-
- for (ndx = 0; g_vt100sequences[ndx].seq; ndx++)
- {
- /* Is this sequence big enough? */
-
- seq = &g_vt100sequences[ndx];
- if (seq->size >= seqsize)
- {
- /* Yes... are the first 'seqsize' bytes the same */
-
- if (memcmp(seq->seq, priv->seq, seqsize) == 0)
- {
- /* Yes.. return the match */
-
- return seq;
- }
- }
- }
- return NULL;
-}
-
-/****************************************************************************
- * Name: nxcon_vt100seq
- *
- * Description:
- * Determine if the new sequence is a part of a supported VT100 escape
- * sequence.
- *
- * Input Parameters:
- * priv - Driver data structure
- * seqsize - The number of bytes in the sequence
- *
- * Returned Value:
- * state - See enum nxcon_vt100state_e;
- *
- ****************************************************************************/
-
-static enum nxcon_vt100state_e nxcon_vt100seq(FAR struct nxcon_state_s *priv,
- int seqsize)
-{
- FAR const struct vt100_sequence_s *seq;
- enum nxcon_vt100state_e ret;
-
- /* Is there any VT100 escape sequence that matches what we have
- * buffered so far?
- */
-
- seq = nxcon_vt100part(priv, seqsize);
- if (seq)
- {
- /* Yes.. if the size of that escape sequence is the same as what we
- * have buffered, then we have an exact match.
- */
-
- if (seq->size == seqsize)
- {
- /* Process the VT100 sequence */
-
- seq->handler(priv);
- priv->nseq = 0;
- return VT100_PROCESSED;
- }
-
- /* The 'seqsize' is still smaller than the potential match(es). We
- * will need to collect more characters before we can make a decision.
- * Retun an indication that we have consumed the character.
- */
-
- return VT100_CONSUMED;
- }
-
- /* We get here on a failure. The buffer sequence is not part of any
- * supported VT100 escape sequence. If seqsize > 1 then we need to
- * return a special value because we have to re-process the buffered
- * data.
- */
-
- ret = seqsize > 1 ? VT100_ABORT : VT100_NOT_CONSUMED;
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxcon_vt100
- *
- * Description:
- * Test if the newly received byte is part of a VT100 escape sequence
- *
- * Input Parameters:
- * priv - Driver data structure
- * ch - The newly received character
- *
- * Returned Value:
- * state - See enum nxcon_vt100state_e;
- *
- ****************************************************************************/
-
-enum nxcon_vt100state_e nxcon_vt100(FAR struct nxcon_state_s *priv, char ch)
-{
- enum nxcon_vt100state_e ret;
- int seqsize;
-
- DEBUGASSERT(priv && priv->nseq < VT100_MAX_SEQUENCE);
-
- /* If we have no buffered characters, then 'ch' must be the first character
- * of an escape sequence.
- */
-
- if (priv->nseq < 1)
- {
- /* The first character of an escape sequence must be an an escape
- * character (duh).
- */
-
- if (ch != ASCII_ESC)
- {
- return VT100_NOT_CONSUMED;
- }
-
- /* Add the escape character to the buffer but don't bother with any
- * further checking.
- */
-
- priv->seq[0] = ASCII_ESC;
- priv->nseq = 1;
- return VT100_CONSUMED;
- }
-
- /* Temporarily add the next character to the buffer */
-
- seqsize = priv->nseq;
- priv->seq[seqsize] = ch;
-
- /* Then check if this sequence is part of an a valid escape sequence */
-
- seqsize++;
- ret = nxcon_vt100seq(priv, seqsize);
- if (ret == VT100_CONSUMED)
- {
- /* The newly added character is indeed part of a VT100 escape sequence
- * (which is still incomplete). Keep it in the buffer.
- */
-
- priv->nseq = seqsize;
- }
- return ret;
-}
diff --git a/nuttx/graphics/nxconsole/nxtk_register.c b/nuttx/graphics/nxconsole/nxtk_register.c
deleted file mode 100644
index b3c17e864..000000000
--- a/nuttx/graphics/nxconsole/nxtk_register.c
+++ /dev/null
@@ -1,192 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxtk_register.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <nuttx/nx/nxtk.h>
-#include <nuttx/nx/nxconsole.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int nxtkcon_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES]);
-#ifndef CONFIG_NX_WRITEONLY
-static int nxtkcon_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset);
-#endif
-static int nxtkcon_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const struct nxcon_operations_s g_nxtkops =
-{
- nxtkcon_fill,
-#ifndef CONFIG_NX_WRITEONLY
- nxtkcon_move,
-#endif
- nxtkcon_bitmap
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxtkcon_fill
- *
- * Description:
- * Fill the specified rectangle in the window with the specified color
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - The location to be filled
- * color - The color to use in the fill
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxtkcon_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES])
-{
- return nxtk_fillwindow((NXTKWINDOW)priv->handle, rect, wcolor);
-}
-
-/****************************************************************************
- * Name: nxtkcon_move
- *
- * Description:
- * Move a rectangular region within the window
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - Describes the rectangular region to move
- * offset - The offset to move the region. The rectangular region will be
- * moved so that the origin is translated by this amount.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-#ifndef CONFIG_NX_WRITEONLY
-static int nxtkcon_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset)
-{
- return nxtk_movewindow((NXTKWINDOW)priv->handle, rect, offset);
-}
-#endif
-
-/****************************************************************************
- * Name: nxtkcon_bitmap
- *
- * Description:
- * Copy a rectangular region of a larger image into the rectangle in the
- * specified window.
- *
- * Input Parameters:
- * priv - The driver state structure.
- * dest - Describes the rectangular region on the display that will
- * receive the bit map.
- * src - The start of the source image. This is an array source
- * images of size CONFIG_NX_NPLANES.
- * origin - The origin of the upper, left-most corner of the full bitmap.
- * Both dest and origin are in window coordinates, however, origin
- * may lie outside of the display.
- * stride - The width of the full source image in bytes.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxtkcon_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride)
-{
- return nxtk_bitmapwindow((NXTKWINDOW)priv->handle, dest, src, origin, stride);
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxtk_register
- *
- * Description:
- * Register a console device on a framed NX window. The device will be
- * registered at /dev/nxtkN where N is the provided minor number.
- *
- * Input Parameters:
- * hfwnd - A handle that will be used to access the window. The window must
- * persist and this handle must be valid for the life of the NX console.
- * wndo - Describes the window and font to be used
- * minor - The device minor number
- *
- * Return:
- * A non-NULL handle is returned on success.
- *
- ****************************************************************************/
-
-NXCONSOLE nxtk_register(NXTKWINDOW hfwnd, FAR struct nxcon_window_s *wndo, int minor)
-{
- return nxcon_register((NXCONSOLE)hfwnd, wndo, &g_nxtkops, minor);
-}
diff --git a/nuttx/graphics/nxconsole/nxtool_register.c b/nuttx/graphics/nxconsole/nxtool_register.c
deleted file mode 100644
index d7666e523..000000000
--- a/nuttx/graphics/nxconsole/nxtool_register.c
+++ /dev/null
@@ -1,195 +0,0 @@
-/****************************************************************************
- * nuttx/graphics/nxconsole/nxtool_register.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <nuttx/nx/nxtk.h>
-#include <nuttx/nx/nxconsole.h>
-
-#include "nxcon_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int nxtool_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES]);
-#ifndef CONFIG_NX_WRITEONLY
-static int nxtool_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset);
-#endif
-static int nxtool_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const struct nxcon_operations_s g_nxtoolops =
-{
- nxtool_fill,
-#ifndef CONFIG_NX_WRITEONLY
- nxtool_move,
-#endif
- nxtool_bitmap
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxtool_fill
- *
- * Description:
- * Fill the specified rectangle in the window with the specified color
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - The location to be filled
- * color - The color to use in the fill
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxtool_fill(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- nxgl_mxpixel_t wcolor[CONFIG_NX_NPLANES])
-{
- return nxtk_filltoolbar((NXTKWINDOW)priv->handle, rect, wcolor);
-}
-
-/****************************************************************************
- * Name: nxtool_move
- *
- * Description:
- * Move a rectangular region within the window
- *
- * Input Parameters:
- * priv - The driver state structure.
- * rect - Describes the rectangular region to move
- * offset - The offset to move the region. The rectangular region will be
- * moved so that the origin is translated by this amount.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-#ifndef CONFIG_NX_WRITEONLY
-static int nxtool_move(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect,
- FAR const struct nxgl_point_s *offset)
-{
- return nxtk_movetoolbar((NXTKWINDOW)priv->handle, rect, offset);
-}
-#endif
-
-/****************************************************************************
- * Name: nxtool_bitmap
- *
- * Description:
- * Copy a rectangular region of a larger image into the rectangle in the
- * specified window.
- *
- * Input Parameters:
- * priv - The driver state structure.
- * dest - Describes the rectangular region on the display that will
- * receive the bit map.
- * src - The start of the source image. This is an array source
- * images of size CONFIG_NX_NPLANES.
- * origin - The origin of the upper, left-most corner of the full bitmap.
- * Both dest and origin are in window coordinates, however, origin
- * may lie outside of the display.
- * stride - The width of the full source image in bytes.
- *
- * Return:
- * OK on success; ERROR on failure with errno set appropriately
- *
- ****************************************************************************/
-
-static int nxtool_bitmap(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *dest,
- FAR const void *src[CONFIG_NX_NPLANES],
- FAR const struct nxgl_point_s *origin,
- unsigned int stride)
-{
- return nxtk_bitmaptoolbar((NXTKWINDOW)priv->handle, dest, src, origin, stride);
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxtool_register
- *
- * Description:
- * Register a console device on a toolbar of a framed NX window. The
- * device will be registered at /dev/nxtoolN where N is the provided minor
- * number.
- *
- * Input Parameters:
- * hfwnd - A handle that will be used to access the toolbar. The toolbar
- * must persist and this handle must be valid for the life of the NX
- * console.
- * wndo - Describes the window and font to be used
- * minor - The device minor number
- *
- * Return:
- * A non-NULL handle is returned on success.
- *
- ****************************************************************************/
-
-NXCONSOLE nxtool_register(NXTKWINDOW hfwnd, FAR struct nxcon_window_s *wndo, int minor)
-{
- return nxcon_register((NXCONSOLE)hfwnd, wndo, &g_nxtoolops, minor);
-}
-