From 6be0b0839beb799e6d8ca12c155783b1a1d7291a Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 27 Mar 2012 00:23:40 +0000 Subject: NFS update + another NX console driver file git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4525 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/graphics/nxconsole/Make.defs | 2 +- nuttx/graphics/nxconsole/nxcon_driver.c | 184 ++++++++++++++++++++++++++++ nuttx/graphics/nxconsole/nxcon_internal.h | 57 ++++++--- nuttx/graphics/nxconsole/nxcon_register.c | 26 +++- nuttx/graphics/nxconsole/nxcon_unregister.c | 7 ++ 5 files changed, 258 insertions(+), 18 deletions(-) create mode 100755 nuttx/graphics/nxconsole/nxcon_driver.c (limited to 'nuttx/graphics') diff --git a/nuttx/graphics/nxconsole/Make.defs b/nuttx/graphics/nxconsole/Make.defs index 95b4ff49e..3b27853f2 100644 --- a/nuttx/graphics/nxconsole/Make.defs +++ b/nuttx/graphics/nxconsole/Make.defs @@ -34,5 +34,5 @@ ############################################################################ NXCON_ASRCS = -NXCON_CSRCS = nx_register.c nxcon_register.c nxcon_unregister.c +NXCON_CSRCS = nx_register.c nxcon_driver.c nxcon_register.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 new file mode 100755 index 000000000..71fa2aabf --- /dev/null +++ b/nuttx/graphics/nxconsole/nxcon_driver.c @@ -0,0 +1,184 @@ +/**************************************************************************** + * nuttx/graphics/nxconsole/nxcon_driver.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#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 */ + +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 +}; + +/**************************************************************************** + * 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 */ + + if ((filep->f_oflags & O_WROK) != 0) + { + gdbg("Attempted open with write access\n"); + return -EACCES; + } + + /* 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; + char ch; + int lineheight; + + /* Recover our private state structure */ + + DEBUGASSERT(filep && filep->f_priv); + priv = (FAR struct nxcon_state_s *)filep->f_priv; + + /* Loop writing each character to the display */ + + lineheight = (priv->fheight + CONFIG_NXCONSOLE_LINESEPARATION); + + while (buflen-- > 0) + { + /* Will another character fit on this line? */ + + if (priv->fpos.x + priv->fwidth > priv->wndo.wsize.w) + { + /* No.. move to the next line */ + + nxcon_newline(priv); + + /* If we were about to output a newline character, then don't */ + + if (*buffer == '\n') + { + buffer++; + continue; + } + } + + /* Check if we need to scroll up (handling a corner case where + * there may be more than one newline). + */ + + while (priv->fpos.y >= priv->wndo.wsize.h - lineheight) + { + nxcon_scroll(priv, lineheight); + } + + /* Ignore carriage returns */ + + ch = *buffer++; + if (ch != '\r') + { + /* Finally, we can output the character */ + + nxcon_putc(priv, (uint8_t)ch); + } + } + + return buflen; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + diff --git a/nuttx/graphics/nxconsole/nxcon_internal.h b/nuttx/graphics/nxconsole/nxcon_internal.h index d0e332ba4..ea2e8c747 100644 --- a/nuttx/graphics/nxconsole/nxcon_internal.h +++ b/nuttx/graphics/nxconsole/nxcon_internal.h @@ -43,6 +43,7 @@ #include #include +#include #include @@ -54,16 +55,36 @@ /**************************************************************************** * Definitions ****************************************************************************/ +/* Configuration ************************************************************/ +/* Font cache */ + +#ifdef CONFIG_NXCONSOLE_FONTCACHE +# ifndef CONFIG_NXCONSOLE_BMCACHE +# define CONFIG_NXCONSOLE_BMCACHE 128 +# endif +# ifndef CONFIG_NXCONSOLE_GLCACHE +# define CONFIG_NXCONSOLE_GLCACHE 16 +# endif +#else +# undef CONFIG_NXCONSOLE_BMCACHE +# undef CONFIG_NXCONSOLE_GLCACHE +#endif + +/* Space (in rows) between lines */ + +#ifndef CONFIG_NXCONSOLE_LINESEPARATION +# define CONFIG_NXCONSOLE_LINESEPARATION 2 +#endif + +/* 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 */ -#define LINE_SEPARATION 2 /* Space (in rows) between lines */ /* Device path formats */ @@ -121,25 +142,28 @@ struct nxcon_state_s { FAR const struct nxcon_operations_s *ops; /* Window operations */ FAR void *handle; /* The window handle */ - uint8_t minor; /* Device minor number */ FAR struct nxcon_window_s wndo; /* Describes the window and font */ + NXHANDLE font; /* The current font handle */ + sem_t exclsem; /* Forces mutually exclusive access */ + struct nxgl_point_s fpos; /* Next display position */ - /* These characterize the font in use */ +#ifdef CONFIG_NXCONSOLE_FONTCACHE + uint16_t maxchars; /* Size of the bm[] array */ + uint16_t nchars; /* Number of chars in the bm[] array */ +#endif - NXHANDLE font; /* The current font handle */ + uint8_t minor; /* Device minor number */ 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 */ - struct nxgl_point_s fpos; /* Next display position */ - - /* These describe all text already added to the display */ - +#ifdef CONFIG_NXCONSOLE_FONTCACHE 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 */ - FAR struct nxcon_bitmap_s *bm; /* List of characters on the display */ - FAR struct nxcon_glyph_s *glyph; /* Cache of rendered fonts in use */ + /* Font cache data storage */ + + struct nxcon_bitmap_s bm[CONFIG_NXCONSOLE_BMCACHE]; + struct nxcon_glyph_s glyph[CONFIG_NXCONSOLE_GLCACHE]; +#endif }; /**************************************************************************** @@ -148,7 +172,7 @@ struct nxcon_state_s /* This is the common NX driver file operations */ -extern const struct file_operations g_nxcondrvrops; +extern const struct file_operations g_nxcon_drvrops; /**************************************************************************** * Public Function Prototypes @@ -159,12 +183,13 @@ FAR struct nxcon_state_s *nxcon_register(NXCONSOLE handle, FAR struct nxcon_window_s *wndo, FAR const struct nxcon_operations_s *ops, int minor); -/* Generic text helpers */ +/* 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, NXHANDLE hfont, uint8_t ch); +void nxcon_putc(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); +void nxcon_scroll(FAR struct nxcon_state_s *priv, int scrollheight); #endif /* __GRAPHICS_NXCONSOLE_NXCON_INTERNAL_H */ diff --git a/nuttx/graphics/nxconsole/nxcon_register.c b/nuttx/graphics/nxconsole/nxcon_register.c index d85b5ffc3..7fd9310c8 100644 --- a/nuttx/graphics/nxconsole/nxcon_register.c +++ b/nuttx/graphics/nxconsole/nxcon_register.c @@ -98,6 +98,8 @@ FAR struct nxcon_state_s * priv->minor = minor; memcpy(&priv->wndo, wndo, sizeof( struct nxcon_window_s)); + sem_init(&priv->exclsem, 0, 1); + /* Select the font */ priv->font = nxf_getfonthandle(wndo->fontid); @@ -107,10 +109,32 @@ FAR struct nxcon_state_s * 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 caches */ + +#ifdef CONFIG_NXCONSOLE_FONTCACHE + priv->maxchars = CONFIG_NXCONSOLE_BMCACHE; + priv->maxglyphs = CONFIG_NXCONSOLE_GLCACHE; +#endif + + /* Set the initial display position */ + + nxcon_home(priv); + /* Register the driver */ snprintf(devname, NX_DEVNAME_SIZE, NX_DEVNAME_FORMAT, minor); - ret = register_driver(devname, &g_nxcondrvrops, 0666, priv); + ret = register_driver(devname, &g_nxcon_drvrops, 0666, priv); if (ret < 0) { gdbg("Failed to register %s\n", devname); diff --git a/nuttx/graphics/nxconsole/nxcon_unregister.c b/nuttx/graphics/nxconsole/nxcon_unregister.c index 1b92649cd..8a19736ed 100644 --- a/nuttx/graphics/nxconsole/nxcon_unregister.c +++ b/nuttx/graphics/nxconsole/nxcon_unregister.c @@ -90,6 +90,13 @@ void nxcon_unregister(NXCONSOLE handle) FAR struct nxcon_state_s *priv; char devname[NX_DEVNAME_SIZE]; + DEBUGASSERT(handle); + + /* Get the reference to the driver structure from the handle */ + + priv = (FAR struct nxcon_state_s *)handle; + sem_destroy(&priv->exclsem); + /* Unregister the driver */ snprintf(devname, NX_DEVNAME_SIZE, NX_DEVNAME_FORMAT, priv->minor); -- cgit v1.2.3