summaryrefslogtreecommitdiff
path: root/nuttx/graphics
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-30 18:42:40 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-30 18:42:40 +0000
commit7b4b14ec2acf251ba72ef2929011037bfc26e714 (patch)
tree5ab49f724ed67d3506856d404b0cd3c03f8fea86 /nuttx/graphics
parentef881d69ec4bd4b9d5cd2783418e506ce7fb8444 (diff)
downloadpx4-nuttx-7b4b14ec2acf251ba72ef2929011037bfc26e714.tar.gz
px4-nuttx-7b4b14ec2acf251ba72ef2929011037bfc26e714.tar.bz2
px4-nuttx-7b4b14ec2acf251ba72ef2929011037bfc26e714.zip
Add framework in NxConsole to support VT100 escape sequences
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4542 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/graphics')
-rw-r--r--nuttx/graphics/README.txt2
-rw-r--r--nuttx/graphics/nxconsole/Make.defs7
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_driver.c92
-rw-r--r--nuttx/graphics/nxconsole/nxcon_font.c58
-rw-r--r--nuttx/graphics/nxconsole/nxcon_internal.h38
-rw-r--r--nuttx/graphics/nxconsole/nxcon_putc.c140
-rw-r--r--nuttx/graphics/nxconsole/nxcon_sem.c2
-rw-r--r--nuttx/graphics/nxconsole/nxcon_vt100.c289
8 files changed, 529 insertions, 99 deletions
diff --git a/nuttx/graphics/README.txt b/nuttx/graphics/README.txt
index 5d6e098e3..935df9140 100644
--- a/nuttx/graphics/README.txt
+++ b/nuttx/graphics/README.txt
@@ -346,7 +346,7 @@ CONFIG_NXCONSOLE_CACHESIZE
If CONFIG_NXCONSOLE_FONTCACHE, then this setting will control the size
of the font cache (in number of glyphs). Default: 16.
CONFIG_NXCONSOLE_LINESEPARATION
- This the space (in rows) between each row of test. Default: 2
+ This the space (in rows) between each row of test. Default: 0
CONFIG_NXCONSOLE_NOWRAP
By default, lines will wrap when the test reaches the right hand side
of the window. This setting can be defining to change this behavior so
diff --git a/nuttx/graphics/nxconsole/Make.defs b/nuttx/graphics/nxconsole/Make.defs
index 6438a93bf..c25151f71 100644
--- a/nuttx/graphics/nxconsole/Make.defs
+++ b/nuttx/graphics/nxconsole/Make.defs
@@ -34,9 +34,10 @@
############################################################################
NXCON_ASRCS =
-NXCON_CSRCS = nx_register.c nxcon_driver.c nxcon_font.c nxcon_redraw.c
-NXCON_CSRCS += nxcon_register.c nxcon_scroll.c nxcon_unregister.c
-NXCON_CSRCS += nxtk_register.c nxtool_register.c
+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_DEBUG),y)
NXCON_CSRCS += nxcon_sem.c
diff --git a/nuttx/graphics/nxconsole/nxcon_driver.c b/nuttx/graphics/nxconsole/nxcon_driver.c
index 8c69272f3..646485146 100755
--- a/nuttx/graphics/nxconsole/nxcon_driver.c
+++ b/nuttx/graphics/nxconsole/nxcon_driver.c
@@ -124,9 +124,9 @@ 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 lineheight;
int ret;
/* Recover our private state structure */
@@ -144,55 +144,77 @@ static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
/* Loop writing each character to the display */
- lineheight = (priv->fheight + CONFIG_NXCONSOLE_LINESEPARATION);
-
for (remaining = (ssize_t)buflen; remaining > 0; remaining--)
{
- /* Ignore carriage returns */
+ /* Get the next character from the user buffer */
ch = *buffer++;
- if (ch == '\r')
- {
- continue;
- }
- /* Will another character fit on this line? */
+ /* Check if this character is part of a VT100 escape sequence */
- if (priv->fpos.x + priv->fwidth > priv->wndo.wsize.w)
+ do
{
-#ifndef CONFIG_NXCONSOLE_NOWRAP
- /* No.. move to the next line */
+ /* Is the character part of a VT100 escape sequnce? */
- nxcon_newline(priv);
+ state = nxcon_vt100(priv, ch);
+ switch (state)
+ {
+ /* Character is not part of a VT100 escape sequence (and no
+ * characters are buffer.
+ */
- /* If we were about to output a newline character, then don't */
+ default:
+ case VT100_NOT_CONSUMED:
+ {
+ /* We can output the character to the window */
- if (ch == '\n')
- {
- continue;
- }
-#else
- /* No.. Ignore all further characters until a newline is encountered */
+ nxcon_putc(priv, (uint8_t)ch);
+ }
+ break;
- if (ch != '\n')
- {
- continue;
- }
-#endif
- }
+ /* The full VT100 escape sequence was processed (and the new
+ * character was consumed)
+ */
- /* Check if we need to scroll up (handling a corner case where
- * there may be more than one newline).
- */
+ case VT100_PROCESSED:
- while (priv->fpos.y >= priv->wndo.wsize.h - lineheight)
- {
- nxcon_scroll(priv, lineheight);
- }
+ /* 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;
- /* Finally, we can output the character */
+ /* Add the first unhandled character to the window */
- nxcon_putc(priv, (uint8_t)ch);
+ 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);
}
nxcon_sempost(priv);
diff --git a/nuttx/graphics/nxconsole/nxcon_font.c b/nuttx/graphics/nxconsole/nxcon_font.c
index 140da4ad7..cb5320d25 100644
--- a/nuttx/graphics/nxconsole/nxcon_font.c
+++ b/nuttx/graphics/nxconsole/nxcon_font.c
@@ -39,20 +39,9 @@
#include <nuttx/config.h>
-#include <stdint.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <string.h>
-#include <ctype.h>
-#include <errno.h>
+#include <assert.h>
#include <debug.h>
-#include <nuttx/kmalloc.h>
-
-#include <nuttx/nx/nx.h>
-#include <nuttx/nx/nxtk.h>
-#include <nuttx/nx/nxfonts.h>
-
#include "nxcon_internal.h"
/****************************************************************************
@@ -411,6 +400,10 @@ nxcon_getglyph(NXHANDLE hfont, FAR struct nxcon_state_s *priv, uint8_t ch)
}
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: nxcon_addchar
*
* Description:
@@ -419,7 +412,7 @@ nxcon_getglyph(NXHANDLE hfont, FAR struct nxcon_state_s *priv, uint8_t ch)
*
****************************************************************************/
-static FAR const struct nxcon_bitmap_s *
+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;
@@ -466,10 +459,6 @@ nxcon_addchar(NXHANDLE hfont, FAR struct nxcon_state_s *priv, uint8_t ch)
}
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
* Name: nxcon_home
*
* Description:
@@ -508,41 +497,6 @@ void nxcon_newline(FAR struct nxcon_state_s *priv)
}
/****************************************************************************
- * 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;
-
- /* If it is a newline character, then just perform the logical newline
- * operation.
- */
-
- if (ch == '\n')
- {
- nxcon_newline(priv);
- }
-
- /* Otherwise, find the glyph associated with the character and render it
- * onto the display.
- */
-
- else
- {
- bm = nxcon_addchar(priv->font, priv, ch);
- if (bm)
- {
- nxcon_fillchar(priv, NULL, bm);
- }
- }
-}
-
-/****************************************************************************
* Name: nxcon_fillchar
*
* Description:
diff --git a/nuttx/graphics/nxconsole/nxcon_internal.h b/nuttx/graphics/nxconsole/nxcon_internal.h
index 62ae71705..996ea9d5d 100644
--- a/nuttx/graphics/nxconsole/nxcon_internal.h
+++ b/nuttx/graphics/nxconsole/nxcon_internal.h
@@ -58,25 +58,38 @@
/* NxConsole Definitions ****************************************************/
/* Bitmap flags */
-#define BMFLAGS_NOGLYPH (1 << 0) /* No glyph available, use space */
-#define BM_ISSPACE(bm) (((bm)->flags & BMFLAGS_NOGLYPH) != 0)
+#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 */
+#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
+#define NX_DEVNAME_FORMAT "/dev/nxcon%d"
+#define NX_DEVNAME_SIZE 16
/* Semaphore protection */
-#define NO_HOLDER (pid_t)-1
+#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 */
@@ -146,6 +159,11 @@ struct nxcon_state_s
uint8_t maxglyphs; /* Size of the glyph[] array */
#endif
+ /* 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 bm[CONFIG_NXCONSOLE_MXCHARS];
@@ -188,13 +206,19 @@ FAR struct nxcon_state_s *nxcon_register(NXCONSOLE handle,
FAR struct nxcon_window_s *wndo, FAR const struct nxcon_operations_s *ops,
int minor);
+/* 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);
void nxcon_putc(FAR struct nxcon_state_s *priv, uint8_t ch);
+FAR const struct nxcon_bitmap_s *nxcon_addchar(NXHANDLE hfont,
+ FAR struct nxcon_state_s *priv, uint8_t ch);
void nxcon_fillchar(FAR struct nxcon_state_s *priv,
- FAR const struct nxgl_rect_s *rect, FAR const struct nxcon_bitmap_s *bm);
+ FAR const struct nxgl_rect_s *rect, FAR const struct nxcon_bitmap_s *bm);
/* Scrolling support */
diff --git a/nuttx/graphics/nxconsole/nxcon_putc.c b/nuttx/graphics/nxconsole/nxcon_putc.c
new file mode 100644
index 000000000..97e3314a6
--- /dev/null
+++ b/nuttx/graphics/nxconsole/nxcon_putc.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * 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 "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;
+ }
+
+ /* Will another character fit on this line? */
+
+ if (priv->fpos.x + priv->fwidth > priv->wndo.wsize.w)
+ {
+#ifndef CONFIG_NXCONSOLE_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_NXCONSOLE_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);
+ }
+}
diff --git a/nuttx/graphics/nxconsole/nxcon_sem.c b/nuttx/graphics/nxconsole/nxcon_sem.c
index 0025005d2..4cf960971 100644
--- a/nuttx/graphics/nxconsole/nxcon_sem.c
+++ b/nuttx/graphics/nxconsole/nxcon_sem.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * nuttx/graphics/nxconsole/nxcon_unregister.c
+ * nuttx/graphics/nxconsole/nxcon_sem.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/graphics/nxconsole/nxcon_vt100.c b/nuttx/graphics/nxconsole/nxcon_vt100.c
new file mode 100644
index 000000000..3e3374dce
--- /dev/null
+++ b/nuttx/graphics/nxconsole/nxcon_vt100.c
@@ -0,0 +1,289 @@
+/****************************************************************************
+ * 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;
+}