summaryrefslogtreecommitdiff
path: root/nuttx/graphics/nxconsole
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-27 19:40:49 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-27 19:40:49 +0000
commit99075db33f33272ed59617de9d584d29d342c5a9 (patch)
treee854fe214319b7ac3a98fe3dc9b25e7d946e23c5 /nuttx/graphics/nxconsole
parent5d3e1ee2e876b618f11a16753ca1d992260089be (diff)
downloadpx4-nuttx-99075db33f33272ed59617de9d584d29d342c5a9.tar.gz
px4-nuttx-99075db33f33272ed59617de9d584d29d342c5a9.tar.bz2
px4-nuttx-99075db33f33272ed59617de9d584d29d342c5a9.zip
NX console driver is code complete but untested
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4529 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/graphics/nxconsole')
-rw-r--r--nuttx/graphics/nxconsole/Make.defs5
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_driver.c10
-rw-r--r--nuttx/graphics/nxconsole/nxcon_internal.h36
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_redraw.c131
-rw-r--r--nuttx/graphics/nxconsole/nxcon_register.c4
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_scroll.c239
6 files changed, 414 insertions, 11 deletions
diff --git a/nuttx/graphics/nxconsole/Make.defs b/nuttx/graphics/nxconsole/Make.defs
index e77f9450c..df84d758d 100644
--- a/nuttx/graphics/nxconsole/Make.defs
+++ b/nuttx/graphics/nxconsole/Make.defs
@@ -34,5 +34,6 @@
############################################################################
NXCON_ASRCS =
-NXCON_CSRCS = nx_register.c nxcon_driver.c nxcon_font.c nxcon_register.c
-NXCON_CSRCS += nxcon_unregister.c nxtk_register.c nxtool_register.c
+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
diff --git a/nuttx/graphics/nxconsole/nxcon_driver.c b/nuttx/graphics/nxconsole/nxcon_driver.c
index 58ad027fe..60ed3242a 100755
--- a/nuttx/graphics/nxconsole/nxcon_driver.c
+++ b/nuttx/graphics/nxconsole/nxcon_driver.c
@@ -126,12 +126,21 @@ static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
FAR struct nxcon_state_s *priv;
char ch;
int lineheight;
+ 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 = sem_wait(&priv->exclsem);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
/* Loop writing each character to the display */
lineheight = (priv->fheight + CONFIG_NXCONSOLE_LINESEPARATION);
@@ -185,6 +194,7 @@ static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
nxcon_putc(priv, (uint8_t)ch);
}
+ sem_post(&priv->exclsem);
return buflen;
}
diff --git a/nuttx/graphics/nxconsole/nxcon_internal.h b/nuttx/graphics/nxconsole/nxcon_internal.h
index 590c169e6..27b963d73 100644
--- a/nuttx/graphics/nxconsole/nxcon_internal.h
+++ b/nuttx/graphics/nxconsole/nxcon_internal.h
@@ -58,8 +58,8 @@
/* Configuration ************************************************************/
/* The maximum number of characters that can be remembered */
-#ifndef CONFIG_NXCONSOLE_BMCACHE
-# define CONFIG_NXCONSOLE_BMCACHE 128
+#ifndef CONFIG_NXCONSOLE_MXCHARS
+# define CONFIG_NXCONSOLE_MXCHARS 128
#endif
/* Font cache -- this is the number or pre-rendered font glyphs that can be
@@ -67,11 +67,33 @@
*/
#ifdef CONFIG_NXCONSOLE_FONTCACHE
-# ifndef CONFIG_NXCONSOLE_GLCACHE
-# define CONFIG_NXCONSOLE_GLCACHE 16
+# ifndef CONFIG_NXCONSOLE_CACHESIZE
+# define CONFIG_NXCONSOLE_CACHESIZE 16
# endif
#else
-# undef CONFIG_NXCONSOLE_GLCACHE
+# undef CONFIG_NXCONSOLE_CACHESIZE
+#endif
+
+/* Pixel depth */
+
+#ifndef CONFIG_NXCONSOLE_BPP
+# if !defined(CONFIG_NX_DISABLE_1BPP)
+# define CONFIG_NXCONSOLE_BPP 1
+# elif !defined(CONFIG_NX_DISABLE_2BPP)
+# define CONFIG_NXCONSOLE_BPP 2
+# elif !defined(CONFIG_NX_DISABLE_4BPP)
+# define CONFIG_NXCONSOLE_BPP 4
+# elif !defined(CONFIG_NX_DISABLE_8BPP)
+# define CONFIG_NXCONSOLE_BPP 8
+# elif !defined(CONFIG_NX_DISABLE_16BPP)
+# define CONFIG_NXCONSOLE_BPP 16
+//#elif !defined(CONFIG_NX_DISABLE_24BPP)
+//# define CONFIG_NXCONSOLE_BPP 24
+# elif !defined(CONFIG_NX_DISABLE_32BPP)
+# define CONFIG_NXCONSOLE_BPP 32
+# else
+# error "No pixel depth provided"
+# endif
#endif
/* Space (in rows) between lines */
@@ -164,12 +186,12 @@ struct nxcon_state_s
/* Font cache data storage */
- struct nxcon_bitmap_s bm[CONFIG_NXCONSOLE_BMCACHE];
+ struct nxcon_bitmap_s bm[CONFIG_NXCONSOLE_MXCHARS];
/* Glyph cache data storage */
#ifdef CONFIG_NXCONSOLE_FONTCACHE
- struct nxcon_glyph_s glyph[CONFIG_NXCONSOLE_GLCACHE];
+ struct nxcon_glyph_s glyph[CONFIG_NXCONSOLE_CACHESIZE];
#else
/* A glyph cache of size one -- all fonts will be re-rendered on each use */
diff --git a/nuttx/graphics/nxconsole/nxcon_redraw.c b/nuttx/graphics/nxconsole/nxcon_redraw.c
new file mode 100755
index 000000000..23bebd622
--- /dev/null
+++ b/nuttx/graphics/nxconsole/nxcon_redraw.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * 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 <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;
+
+ /* 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]);
+ }
+}
diff --git a/nuttx/graphics/nxconsole/nxcon_register.c b/nuttx/graphics/nxconsole/nxcon_register.c
index 9ed42c74d..cc878b239 100644
--- a/nuttx/graphics/nxconsole/nxcon_register.c
+++ b/nuttx/graphics/nxconsole/nxcon_register.c
@@ -122,9 +122,9 @@ FAR struct nxcon_state_s *
/* Set up the text caches */
- priv->maxchars = CONFIG_NXCONSOLE_BMCACHE;
+ priv->maxchars = CONFIG_NXCONSOLE_MXCHARS;
#ifdef CONFIG_NXCONSOLE_FONTCACHE
- priv->maxglyphs = CONFIG_NXCONSOLE_GLCACHE;
+ priv->maxglyphs = CONFIG_NXCONSOLE_CACHESIZE;
#endif
/* Set the initial display position */
diff --git a/nuttx/graphics/nxconsole/nxcon_scroll.c b/nuttx/graphics/nxconsole/nxcon_scroll.c
new file mode 100755
index 000000000..81bd3a7e8
--- /dev/null
+++ b/nuttx/graphics/nxconsole/nxcon_scroll.c
@@ -0,0 +1,239 @@
+/****************************************************************************
+ * nuttx/graphics/nxconsole/nxcon_scroll.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 <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.
+ ****************************************************************************/
+
+#ifndef CONFIG_NXCONSOLE_NOGETRUN
+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_NXCONSOLE_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 bottom 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("nxcon_movedisplay: 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;
+
+ /* 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 + CONFIG_NXCONSOLE_LINESEPARATION;
+ 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 */
+
+ ret = priv->move(priv, &rect, &offset);
+ if (ret < 0)
+ {
+ gdbg("move 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_NXCONSOLE_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);
+} \ No newline at end of file