forked from Archive/PX4-Autopilot
NFS update + another NX console driver file
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4525 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
5c2c73f6f5
commit
7d8338dbfc
|
@ -81,7 +81,7 @@
|
|||
|
||||
#define NFS_CMPFH(n, f, s) \
|
||||
((n)->n_fhsize == (s) && !bcmp((void *)(n)->n_fhp, (void *)(f), (s)))
|
||||
#define NFS_ISV3(v) (VFSTONFS((v)->v_mount)->nm_flag & NFSMNT_NFSV3)
|
||||
#define NFS_ISV3(i) (VFSTONFS((i)->f_inode)->nm_flag & NFSMNT_NFSV3)
|
||||
#define NFS_SRVMAXDATA(n) \
|
||||
(((n)->nd_flag & ND_NFSV3) ? (((n)->nd_nam2) ? \
|
||||
NFS_MAXDGRAMDATA : NFS_MAXDATA) : NFS_V2MAXDATA)
|
||||
|
|
|
@ -127,7 +127,7 @@ struct nfs_args
|
|||
int addrlen; /* length of address */
|
||||
int sotype; /* Socket type */
|
||||
int proto; /* and Protocol */
|
||||
unsigned char *fh; /* File handle to be mounted */
|
||||
nfsfh_t *fh; /* File handle to be mounted */
|
||||
int fhsize; /* Size, in bytes, of fh */
|
||||
int flags; /* flags */
|
||||
int wsize; /* write size in bytes */
|
||||
|
|
|
@ -73,6 +73,8 @@ struct nfsmount
|
|||
int nm_flag; /* Flags for soft/hard... */
|
||||
int nm_state; /* Internal state flags */
|
||||
struct inode *nm_mountp; /* Vfs structure for this filesystem */
|
||||
struct nfsnode *nfs_head; /* A list to all files opened on this mountpoint */
|
||||
bool nfs_mounted; /* true: The file system is ready */
|
||||
int nm_numgrps; /* Max. size of groupslist */
|
||||
nfsfh_t nm_fh; /* File handle of root dir */
|
||||
int nm_fhsize; /* Size of root file handle */
|
||||
|
@ -114,7 +116,6 @@ void nfs_decode_args(struct nfsmount *, struct nfs_args *, struct nfs_args *);
|
|||
int nfs_start(struct mount *, int, struct proc *);
|
||||
int nfs_unmount(struct mount *, int, struct proc *);
|
||||
int nfs_root(struct mount *, struct vnode **);
|
||||
int nfs_quotactl(struct mount *, int, uid_t, caddr_t, struct proc *);
|
||||
int nfs_statfs(struct mount *, struct statfs *, struct proc *);
|
||||
int nfs_sync(struct mount *, int, struct ucred *, struct proc *);
|
||||
int nfs_vget(struct mount *, ino_t, struct vnode **);
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/****************************************************************************
|
||||
* fs/nfs/nfs_mount.h
|
||||
* fs/nfs/nfs_node.h
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
|
||||
|
@ -47,11 +47,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef _NFS_NFS_H_
|
||||
# include <nfs/nfs.h>
|
||||
#endif
|
||||
|
||||
#include <sys/rwlock.h>
|
||||
#include "nfs.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
|
@ -115,15 +111,16 @@ struct sillyrename
|
|||
|
||||
struct nfsnode
|
||||
{
|
||||
RB_ENTRY(nfsnode) n_entry; /* filehandle/node tree. */
|
||||
struct nfsnode *nfs_next; /* Retained in a singly linked list filehandle/node tree. */
|
||||
bool nfs_open; /* true: The file is (still) open */
|
||||
uint64_t n_size; /* Current size of file */
|
||||
//struct vattr n_vattr; /* Vnode attribute cache */
|
||||
struct nfs_fattr n_fattr; /* nfs file attribute cache */
|
||||
time_t n_attrstamp; /* Attr. cache timestamp */
|
||||
struct timespec n_mtime; /* Prev modify time. */
|
||||
time_t n_ctime; /* Prev create time. */
|
||||
nfsfh_t *n_fhp; /* NFS File Handle */
|
||||
nfstype nfsv3_type; /* File type */
|
||||
struct inode *n_inode; /* associated inode */
|
||||
//struct lockf *n_lockf; /* Locking record of file */
|
||||
int n_error; /* Save write error value */
|
||||
union
|
||||
{
|
||||
|
@ -135,7 +132,6 @@ struct nfsnode
|
|||
struct timespec nf_mtim;
|
||||
off_t nd_direof; /* Dir. EOF offset cache */
|
||||
} n_un2;
|
||||
//struct sillyrename *n_sillyrename; /* Ptr to silly rename struct */
|
||||
short n_fhsize; /* size in bytes, of fh */
|
||||
short n_flag; /* Flag for locking.. */
|
||||
nfsfh_t n_fh; /* Small File Handle */
|
||||
|
@ -143,8 +139,6 @@ struct nfsnode
|
|||
uid_t n_accuid; /* Last access requester */
|
||||
int n_accmode; /* Last mode requested */
|
||||
int n_accerror; /* Last returned error */
|
||||
//struct ucred *n_rcred;
|
||||
//struct ucred *n_wcred;
|
||||
|
||||
off_t n_pushedlo; /* 1st blk in commited range */
|
||||
off_t n_pushedhi; /* Last block in range */
|
||||
|
|
|
@ -80,7 +80,7 @@ static struct rpc_program nfs3_program =
|
|||
* Public Variables
|
||||
****************************************************************************/
|
||||
|
||||
int nfs_ticks;
|
||||
int nfs_ticks = rpcclnt_ticks;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
|
@ -158,7 +158,7 @@ void nfsx_safedisconnect(struct nfsmount *nmp)
|
|||
}
|
||||
#endif
|
||||
|
||||
int nfsx_request_xx(struct nfsmount *nm, int procnum)
|
||||
int nfsx_request_xx(struct nfsmount *nm, int procnum, void *data)
|
||||
{
|
||||
int error;
|
||||
struct nfsmount *nmp;
|
||||
|
@ -176,6 +176,7 @@ tryagain:
|
|||
if ((error = rpcclnt_request(clnt, procnum, &reply)) != 0)
|
||||
goto out;
|
||||
|
||||
data = reply->where;
|
||||
|
||||
if (reply->rpc_verfi.authtype != 0)
|
||||
{
|
||||
|
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -158,6 +158,8 @@ struct rpc_reply
|
|||
uint32_t type;
|
||||
uint32_t status;
|
||||
|
||||
void where; /* Data */
|
||||
|
||||
/* used only when reply == RPC_MSGDENIED and status == RPC_AUTHERR */
|
||||
|
||||
uint32_t autherr;
|
||||
|
|
|
@ -1163,6 +1163,7 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, struct rpc_reply *reply)
|
|||
if (reply->stat.status == RPC_SUCCESS)
|
||||
{
|
||||
printf("RPC_SUCCESS");
|
||||
reply->where = replysvr->where;
|
||||
}
|
||||
else if (reply->stat.status == RPC_PROGMISMATCH)
|
||||
{
|
||||
|
|
|
@ -1,80 +0,0 @@
|
|||
/****************************************************************************
|
||||
* fs/nfs/rpc_types.h
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
|
||||
* Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
|
||||
*
|
||||
* Leveraged from OpenBSD:
|
||||
*
|
||||
* Copyright (c) 1982, 1986, 1988, 1993
|
||||
* The Regents of the University of California. All rights reserved.
|
||||
*
|
||||
* 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 of the University 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 REGENTS 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 REGENTS 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 __FS_NFS_RPC_TYPES_H
|
||||
#define __FS_NFS_RPC_TYPES_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <time.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
struct lock
|
||||
{
|
||||
int dummy;
|
||||
};
|
||||
|
||||
struct componentname
|
||||
{
|
||||
/* Arguments to lookup. */
|
||||
|
||||
unsigned long cn_nameiop; /* namei operation */
|
||||
uint64_t cn_flags; /* flags to namei */
|
||||
struct thread *cn_thread; /* thread requesting lookup */
|
||||
struct ucred *cn_cred; /* credentials */
|
||||
int cn_lkflags; /* Lock flags LK_EXCLUSIVE or LK_SHARED */
|
||||
|
||||
/* Shared between lookup and commit routines. */
|
||||
|
||||
char *cn_pnbuf; /* pathname buffer */
|
||||
char *cn_nameptr; /* pointer to looked up name */
|
||||
long cn_namelen; /* length of looked up component */
|
||||
long cn_consume; /* chars to consume in lookup() */
|
||||
};
|
||||
|
||||
#endif /* __FS_NFS_RPC_TYPES_H */
|
|
@ -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
|
||||
|
|
|
@ -0,0 +1,184 @@
|
|||
/****************************************************************************
|
||||
* 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 */
|
||||
|
||||
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
|
||||
****************************************************************************/
|
||||
|
|
@ -43,6 +43,7 @@
|
|||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <semaphore.h>
|
||||
|
||||
#include <nuttx/fs/fs.h>
|
||||
|
||||
|
@ -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 */
|
||||
|
||||
/* These characterize the font in use */
|
||||
|
||||
NXHANDLE font; /* The current font handle */
|
||||
sem_t exclsem; /* Forces mutually exclusive access */
|
||||
struct nxgl_point_s fpos; /* Next display position */
|
||||
|
||||
#ifdef CONFIG_NXCONSOLE_FONTCACHE
|
||||
uint16_t maxchars; /* Size of the bm[] array */
|
||||
uint16_t nchars; /* Number of chars in the bm[] array */
|
||||
#endif
|
||||
|
||||
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 */
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue