summaryrefslogtreecommitdiff
path: root/nuttx/graphics
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/graphics')
-rw-r--r--nuttx/graphics/README.txt3
-rw-r--r--nuttx/graphics/nxconsole/Make.defs4
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_driver.c4
-rw-r--r--nuttx/graphics/nxconsole/nxcon_font.c9
-rw-r--r--nuttx/graphics/nxconsole/nxcon_internal.h17
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_redraw.c4
-rwxr-xr-xnuttx/graphics/nxconsole/nxcon_scroll.c2
-rw-r--r--nuttx/graphics/nxconsole/nxcon_sem.c129
-rw-r--r--nuttx/graphics/nxtk/nxtk_events.c8
9 files changed, 163 insertions, 17 deletions
diff --git a/nuttx/graphics/README.txt b/nuttx/graphics/README.txt
index 3e7f61bcf..5d6e098e3 100644
--- a/nuttx/graphics/README.txt
+++ b/nuttx/graphics/README.txt
@@ -37,6 +37,9 @@ at the present, but here is the longer term roadmap:
NxConsole - NxConsole is a write-only character device that is built on top of
an NX window. This character device can be used to provide stdout
and stderr and, hence, can provide the output side of NuttX console.
+ NxConsole is only available when the multi-user NX implementation is
+ selected (CONFIG_NX_MULTIUSERs).
+
Related Header Files
^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/graphics/nxconsole/Make.defs b/nuttx/graphics/nxconsole/Make.defs
index df84d758d..6438a93bf 100644
--- a/nuttx/graphics/nxconsole/Make.defs
+++ b/nuttx/graphics/nxconsole/Make.defs
@@ -37,3 +37,7 @@ 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
+
+ifeq ($(CONFIG_DEBUG),y)
+NXCON_CSRCS += nxcon_sem.c
+endif
diff --git a/nuttx/graphics/nxconsole/nxcon_driver.c b/nuttx/graphics/nxconsole/nxcon_driver.c
index d4ab71464..8c69272f3 100755
--- a/nuttx/graphics/nxconsole/nxcon_driver.c
+++ b/nuttx/graphics/nxconsole/nxcon_driver.c
@@ -136,7 +136,7 @@ static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
/* Get exclusive access */
- ret = sem_wait(&priv->exclsem);
+ ret = nxcon_semwait(priv);
if (ret < 0)
{
return ret;
@@ -195,7 +195,7 @@ static ssize_t nxcon_write(FAR struct file *filep, FAR const char *buffer,
nxcon_putc(priv, (uint8_t)ch);
}
- sem_post(&priv->exclsem);
+ nxcon_sempost(priv);
return (ssize_t)buflen;
}
diff --git a/nuttx/graphics/nxconsole/nxcon_font.c b/nuttx/graphics/nxconsole/nxcon_font.c
index 436f91477..140da4ad7 100644
--- a/nuttx/graphics/nxconsole/nxcon_font.c
+++ b/nuttx/graphics/nxconsole/nxcon_font.c
@@ -241,10 +241,6 @@ nxcon_renderglyph(FAR struct nxcon_state_s *priv,
int col;
int ret;
- /* Make sure that there is room for another glyph */
-
- gvdbg("ch=%c [%02x]\n", isprint(ch) ? ch : '.', ch);
-
/* Allocate the glyph (always succeeds) */
glyph = nxcon_allocglyph(priv);
@@ -629,10 +625,7 @@ void nxcon_fillchar(FAR struct nxcon_state_s *priv,
src = (FAR const void *)glyph->bitmap;
ret = priv->ops->bitmap(priv, &intersection, &src,
&bm->pos, (unsigned int)glyph->stride);
- if (ret < 0)
- {
- gdbg("bitmap failed: %d\n", errno);
- }
+ DEBUGASSERT(ret >= 0);
}
}
diff --git a/nuttx/graphics/nxconsole/nxcon_internal.h b/nuttx/graphics/nxconsole/nxcon_internal.h
index 963511b29..62ae71705 100644
--- a/nuttx/graphics/nxconsole/nxcon_internal.h
+++ b/nuttx/graphics/nxconsole/nxcon_internal.h
@@ -70,6 +70,10 @@
#define NX_DEVNAME_FORMAT "/dev/nxcon%d"
#define NX_DEVNAME_SIZE 16
+/* Semaphore protection */
+
+#define NO_HOLDER (pid_t)-1
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -126,6 +130,9 @@ struct nxcon_state_s
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
struct nxgl_point_s fpos; /* Next display position */
uint16_t maxchars; /* Size of the bm[] array */
@@ -165,6 +172,16 @@ 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,
diff --git a/nuttx/graphics/nxconsole/nxcon_redraw.c b/nuttx/graphics/nxconsole/nxcon_redraw.c
index 1a40a7ee1..05f0a47f8 100755
--- a/nuttx/graphics/nxconsole/nxcon_redraw.c
+++ b/nuttx/graphics/nxconsole/nxcon_redraw.c
@@ -117,7 +117,7 @@ void nxcon_redraw(NXCONSOLE handle, FAR const struct nxgl_rect_s *rect, bool mor
do
{
- ret = sem_wait(&priv->exclsem);
+ ret = nxcon_semwait(priv);
/* Check for errors */
@@ -148,5 +148,5 @@ void nxcon_redraw(NXCONSOLE handle, FAR const struct nxgl_rect_s *rect, bool mor
{
nxcon_fillchar(priv, rect, &priv->bm[i]);
}
- ret = sem_post(&priv->exclsem);
+ ret = nxcon_sempost(priv);
}
diff --git a/nuttx/graphics/nxconsole/nxcon_scroll.c b/nuttx/graphics/nxconsole/nxcon_scroll.c
index 81bd3a7e8..b0a1a2335 100755
--- a/nuttx/graphics/nxconsole/nxcon_scroll.c
+++ b/nuttx/graphics/nxconsole/nxcon_scroll.c
@@ -236,4 +236,4 @@ void nxcon_scroll(FAR struct nxcon_state_s *priv, int 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
+}
diff --git a/nuttx/graphics/nxconsole/nxcon_sem.c b/nuttx/graphics/nxconsole/nxcon_sem.c
new file mode 100644
index 000000000..0025005d2
--- /dev/null
+++ b/nuttx/graphics/nxconsole/nxcon_sem.c
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * 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 <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/nxtk/nxtk_events.c b/nuttx/graphics/nxtk/nxtk_events.c
index e778b2736..7b081ec77 100644
--- a/nuttx/graphics/nxtk/nxtk_events.c
+++ b/nuttx/graphics/nxtk/nxtk_events.c
@@ -1,8 +1,8 @@
/****************************************************************************
* graphics/nxtk/nxtk_events.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2009, 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
@@ -131,7 +131,7 @@ static void nxtk_redraw(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect,
nxtk_containerclip(fwnd, &intersection, rect, &fwnd->fwrect);
- gvdbg("fwrect intersction={(%d,%d),(%d,%d)}\n",
+ gvdbg("fwrect intersection={(%d,%d),(%d,%d)}\n",
intersection.pt1.x, intersection.pt1.y,
intersection.pt2.x, intersection.pt2.y);
@@ -154,7 +154,7 @@ static void nxtk_redraw(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect,
nxtk_containerclip(fwnd, &intersection, rect, &fwnd->tbrect);
- gvdbg("tbrect intersction={(%d,%d),(%d,%d)}\n",
+ gvdbg("tbrect intersection={(%d,%d),(%d,%d)}\n",
intersection.pt1.x, intersection.pt1.y,
intersection.pt2.x, intersection.pt2.y);