From 6cdcf5a87d0490f4cc30bc604acb649b7fb49183 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 28 Sep 2011 17:41:58 +0000 Subject: Add a simulated touchscreen driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3989 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NXGraphicsSubsystem.html | 53 +- nuttx/arch/sim/src/Makefile | 4 + nuttx/arch/sim/src/up_framebuffer.c | 15 - nuttx/arch/sim/src/up_initialize.c | 23 + nuttx/arch/sim/src/up_internal.h | 90 +++- nuttx/arch/sim/src/up_touchscreen.c | 753 +++++++++++++++++++++++++++ nuttx/arch/sim/src/up_x11eventloop.c | 168 ++++++ nuttx/arch/sim/src/up_x11framebuffer.c | 10 +- nuttx/configs/sim/README.txt | 125 +++-- nuttx/configs/sim/nx/defconfig-x11 | 564 -------------------- nuttx/configs/sim/nx11/Make.defs | 110 ++++ nuttx/configs/sim/nx11/appconfig | 39 ++ nuttx/configs/sim/nx11/defconfig | 572 ++++++++++++++++++++ nuttx/configs/sim/nx11/setenv.sh | 45 ++ 14 files changed, 1921 insertions(+), 650 deletions(-) create mode 100644 nuttx/arch/sim/src/up_touchscreen.c create mode 100644 nuttx/arch/sim/src/up_x11eventloop.c delete mode 100644 nuttx/configs/sim/nx/defconfig-x11 create mode 100644 nuttx/configs/sim/nx11/Make.defs create mode 100644 nuttx/configs/sim/nx11/appconfig create mode 100644 nuttx/configs/sim/nx11/defconfig create mode 100755 nuttx/configs/sim/nx11/setenv.sh (limited to 'nuttx') diff --git a/nuttx/Documentation/NXGraphicsSubsystem.html b/nuttx/Documentation/NXGraphicsSubsystem.html index 419890574..6c3ccf7bb 100644 --- a/nuttx/Documentation/NXGraphicsSubsystem.html +++ b/nuttx/Documentation/NXGraphicsSubsystem.html @@ -12,7 +12,7 @@

NX Graphics Subsystem

-

Last Updated: August 24, 2011

+

Last Updated: September 28, 2011

@@ -3416,13 +3416,13 @@ static FAR const struct nx_fontpackage_s *g_fontpackages[] =

Building apps/examples/nx. NX testing was performed using apps/examples/nx with the Linux/Cygwin-based NuttX simulator. - Configuration files for building this test can be found in configs/sim/nx. + Configuration files for building this test can be found in configs/sim/nx + and configs/sim/nx11. There are two alternative configurations for building the simulation:

  1. - The default configuration using the configuration file at - configs/sim/nx/defconfig. + The configuration using the configuration file at configs/sim/nx/defconfig. This default configuration exercises the NX logic a 8 BPP but provides no visual feedback. In this configuration, a very simple, simulated framebuffer driver is used that is based upon a simple region of memory posing as video memory. @@ -3437,18 +3437,17 @@ make
  2. - A preferred configuration extends the test with a simulated framebuffer driver + The preferred configuration is at configs/sim/nx11/defconfig. + This configuration extends the test with a simulated framebuffer driver that uses an X window as a framebuffer. - This configuration uses the configuration file at configs/sim/nx/defconfig-x11. This is a superior test configuration because the X window appears at your desktop and you can see the NX output. This preferred configuration can be built as follows:

       cd <NuttX-Directory>/tools
      -./configure sim/nx
      +./configure sim/nx11
       cd  <NuttX-Directory>
      -cp <NuttX-Directory>/configs/sim/nx/defconfig-x11 .config
       make
       ./nuttx
       
    @@ -3456,29 +3455,40 @@ make Update: The sim target has suffered some bit-rot over the years and so the following caveats need to be added:
      -
    • - The X target does not build under recent Cygwin configurations. -
    • -
    • - The X target does not build under current Ubuntu distributions; - it fails to locate the X header files. -
    • -
    • +
    • + The X target builds under recent Cygwin configurations, but does not execute. + (It fails inside of XOpenDisplay(). +

    • +
    • + The X target does not build under current (9.09) Ubuntu distributions. + I needed to make the following changes: +

      +
        +cd /usr/lib/ +sudo ln -s libXext.so.6.4.0 libXext.so +
      +

      + The build will also fail to locate the X header files unless you install an X11 development package. +

    • +
    • The sim target itself is broken under 64-bit Linux. This is because the sim target is based upon some assembly language setjmp/longjmp logic that only works on 32-bit systems. -

      NOTE: There is a workaround in this case: +

      +

      + NOTE: There is a workaround in this case: You can build for 32-bit execution on a 64-bit machine by adding -m3 to the CFLAGS and -m32 -m elf_i386 to the LDFLAGS. See the patch file 0001-Quick-hacks-to-build-sim-nsh-ostest-on-x86_64-as-32-.patch that can be found in NuttX files. -

      +

    • +
    • + Refer to the readme file in sim configuration + README.txt file for additional information. +

-

- Why isn't this configuration the default? Because not all systems the use NX support X. -

Test Coverage. At present, apps/examples/nxt only exercises a subset of NX; @@ -3985,7 +3995,6 @@ make nxf_convert_32bpp() - Use defconfig-x11 when building. YES diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile index f7844a1d9..0213a69dc 100644 --- a/nuttx/arch/sim/src/Makefile +++ b/nuttx/arch/sim/src/Makefile @@ -53,6 +53,10 @@ else CSRCS += up_framebuffer.c ifeq ($(CONFIG_SIM_X11FB),y) HOSTSRCS += up_x11framebuffer.c +ifeq ($(CONFIG_SIM_TOUCHSCREEN),y) + CSRCS += up_touchscreen.c + HOSTSRCS += up_x11eventloop.c +endif endif endif diff --git a/nuttx/arch/sim/src/up_framebuffer.c b/nuttx/arch/sim/src/up_framebuffer.c index 298eb9f8a..66292ca3b 100644 --- a/nuttx/arch/sim/src/up_framebuffer.c +++ b/nuttx/arch/sim/src/up_framebuffer.c @@ -113,21 +113,6 @@ static int up_getcursor(FAR struct fb_vtable_s *vtable, FAR struct fb_cursorattr static int up_setcursor(FAR struct fb_vtable_s *vtable, FAR struct fb_setcursor_s *setttings); #endif -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef CONFIG_SIM_X11FB -extern int up_x11initialize(unsigned short width, unsigned short height, - void **fbmem, unsigned int *fblen, unsigned char *bpp, - unsigned short *stride); -#ifdef CONFIG_FB_CMAP -extern int up_x11cmap(unsigned short first, unsigned short len, - unsigned char *red, unsigned char *green, - unsigned char *blue, unsigned char *transp); -#endif -#endif - /**************************************************************************** * Private Data ****************************************************************************/ diff --git a/nuttx/arch/sim/src/up_initialize.c b/nuttx/arch/sim/src/up_initialize.c index 257be8ab5..26207b624 100644 --- a/nuttx/arch/sim/src/up_initialize.c +++ b/nuttx/arch/sim/src/up_initialize.c @@ -44,6 +44,7 @@ #include #include +#include "os_internal.h" #include "up_internal.h" /**************************************************************************** @@ -98,10 +99,32 @@ void up_initialize(void) devnull_register(); /* Standard /dev/null */ devzero_register(); /* Standard /dev/zero */ up_devconsole(); /* Our private /dev/console */ + #if defined(CONFIG_FS_FAT) && !defined(CONFIG_DISABLE_MOUNTPOINT) up_registerblockdevice(); /* Our FAT ramdisk at /dev/ram0 */ #endif + #ifdef CONFIG_NET uipdriver_init(); /* Our "real" netwok driver */ #endif + + /* Start the X11 event loop and register the touchscreen driver */ + +#if defined(CONFIG_SIM_X11FB) && defined(CONFIG_SIM_TOUCHSCREEN) + { + int ret; + + /* Start the X11 event loop */ + + ret = KERNEL_THREAD("evloop", CONFIG_SIM_EVLOOPPRIORITY, + CONFIG_SIM_EVLOOPSTACKSIZE, + (main_t)up_x11eventloop, (const char **)NULL); + ASSERT(ret != ERROR); + + /* Register the touchscreen driver */ + + ret = up_tcregister(0); + ASSERT(ret == OK); + } +#endif } diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h index 82df76e1f..19e50986b 100644 --- a/nuttx/arch/sim/src/up_internal.h +++ b/nuttx/arch/sim/src/up_internal.h @@ -1,7 +1,7 @@ /************************************************************************** * up_internal.h * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -45,26 +45,56 @@ #include /************************************************************************** - * Public Definitions + * Pre-processor Definitions **************************************************************************/ +/* Configuration **********************************************************/ +#ifndef CONFIG_SIM_X11FB +# ifdef CONFIG_SIM_TOUCHSCREEN +# error "CONFIG_SIM_TOUCHSCREEN depends on CONFIG_SIM_X11FB" +# undef CONFIG_SIM_TOUCHSCREEN +# endif +#endif + +#ifndef CONFIG_INPUT +# ifdef CONFIG_SIM_TOUCHSCREEN +# error "CONFIG_SIM_TOUCHSCREEN depends on CONFIG_INPUT" +# undef CONFIG_SIM_TOUCHSCREEN +# endif +#endif + +#ifdef CONFIG_SIM_TOUCHSCREEN +# ifndef CONFIG_SIM_EVLOOPPRIORITY +# define CONFIG_SIM_EVLOOPPRIORITY 50 +# endif +# ifndef CONFIG_SIM_EVLOOPSTACKSIZE +# define CONFIG_SIM_EVLOOPSTACKSIZE 4096 +# endif +#else +# undef CONFIG_SIM_EVLOOPPRIORITY +# undef CONFIG_SIM_EVLOOPSTACKSIZE +#endif + +/* Context Switching Definitions ******************************************/ /* Storage order: %ebx, $esi, %edi, %ebp, sp, and return PC */ + #ifdef __ASSEMBLY__ -# define JB_EBX (0*4) -# define JB_ESI (1*4) -# define JB_EDI (2*4) -# define JB_EBP (3*4) -# define JB_SP (4*4) -# define JB_PC (5*4) +# define JB_EBX (0*4) +# define JB_ESI (1*4) +# define JB_EDI (2*4) +# define JB_EBP (3*4) +# define JB_SP (4*4) +# define JB_PC (5*4) #else -# define JB_EBX (0) -# define JB_ESI (1) -# define JB_EDI (2) -# define JB_EBP (3) -# define JB_SP (4) -# define JB_PC (5) +# define JB_EBX (0) +# define JB_ESI (1) +# define JB_EDI (2) +# define JB_EBP (3) +# define JB_SP (4) +# define JB_PC (5) #endif /* __ASSEMBLY__ */ +/* Simulated Heap Definitions **********************************************/ /* Size of the simulated heap */ #if CONFIG_MM_SMALL @@ -73,6 +103,7 @@ # define SIM_HEAP_SIZE (4*1024*1024) #endif +/* File System Definitions **************************************************/ /* These definitions characterize the compressed filesystem image */ #define BLOCK_COUNT 1024 @@ -126,6 +157,37 @@ extern size_t up_hostwrite(const void *buffer, size_t len); extern unsigned long up_getwalltime( void ); #endif +/* up_x11framebuffer.c ******************************************************/ + +#ifdef CONFIG_SIM_X11FB +extern int up_x11initialize(unsigned short width, unsigned short height, + void **fbmem, unsigned int *fblen, unsigned char *bpp, + unsigned short *stride); +#ifdef CONFIG_FB_CMAP +extern int up_x11cmap(unsigned short first, unsigned short len, + unsigned char *red, unsigned char *green, + unsigned char *blue, unsigned char *transp); +#endif +#endif + +/* up_eventloop.c ***********************************************************/ + +#ifdef CONFIG_SIM_X11FB +#ifdef CONFIG_SIM_TOUCHSCREEN +extern int up_x11eventloop(int argc, char *argv[]); +#endif +#endif + +/* up_eventloop.c ***********************************************************/ + +#ifdef CONFIG_SIM_X11FB +#ifdef CONFIG_SIM_TOUCHSCREEN +extern int up_tcregister(int minor); +extern int up_tcenter(int x, int y, int buttons); +extern int up_tcleave(int x, int y, int buttons); +#endif +#endif + /* up_tapdev.c ************************************************************/ #if defined(CONFIG_NET) && !defined(__CYGWIN__) diff --git a/nuttx/arch/sim/src/up_touchscreen.c b/nuttx/arch/sim/src/up_touchscreen.c new file mode 100644 index 000000000..09e4e013e --- /dev/null +++ b/nuttx/arch/sim/src/up_touchscreen.c @@ -0,0 +1,753 @@ +/**************************************************************************** + * arch/sim/src/up_touchscreen.c + * + * Copyright (C) 2011 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 +#include +#include + +#include +#include +#include + +#include + +#include "up_internal.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +/* Driver support ***********************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This describes the state of one contact */ + +enum up_contact_3 +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one touchscreen sample */ + +struct up_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum up_contact_e) */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ +}; + +/* This structure describes the state of one touchscreen driver instance */ + +struct up_dev_s +{ + uint8_t nwaiters; /* Number of threads waiting for touchscreen data */ + uint8_t id; /* Current touch point ID */ + bool penchange; /* An unreported event is buffered */ + sem_t devsem; /* Manages exclusive access to this structure */ + sem_t waitsem; /* Used to wait for the availability of data */ + + struct up_sample_s sample; /* Last sampled touch point data */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_touchscreen_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static void up_notify(FAR struct up_dev_s *priv); +static int up_sample(FAR struct up_dev_s *priv, + FAR struct up_sample_s *sample); +static int up_waitsample(FAR struct up_dev_s *priv, + FAR struct up_sample_s *sample); +static int up_transfer(FAR struct up_dev_s *priv, uint8_t cmd); +static void up_worker(FAR void *arg); +static int up_interrupt(int irq, FAR void *context); + +/* Character driver methods */ + +static int up_open(FAR struct file *filep); +static int up_close(FAR struct file *filep); +static ssize_t up_read(FAR struct file *filep, FAR char *buffer, size_t len); +static int up_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int up_poll(FAR struct file *filep, struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This the the vtable that supports the character driver interface */ + +static const struct file_operations up_fops = +{ + up_open, /* open */ + up_close, /* close */ + up_read, /* read */ + 0, /* write */ + 0, /* seek */ + up_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , up_poll /* poll */ +#endif +}; + +/* Only one simulated touchscreen is supported o the the driver state + * structure may as well be pre-allocated. + */ + +static struct up_dev_s g_simtouchscreen; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_notify + ****************************************************************************/ + +static void up_notify(FAR struct up_dev_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the touchscreen + * is no longer avaialable. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for touchscreen data to become availabe, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_touchscreen_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: up_sample + ****************************************************************************/ + +static int up_sample(FAR struct up_dev_s *priv, + FAR struct up_sample_s *sample) +{ + int ret = -EAGAIN; + + /* Is there new touchscreen sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct up_sample_s )); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* Next.. no contract. Increment the ID so that next contact ID will be unique */ + + priv->sample.contact = CONTACT_NONE; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* First report -- next report will be a movement */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: up_waitsample + ****************************************************************************/ + +static int up_waitsample(FAR struct up_dev_s *priv, + FAR struct up_sample_s *sample) +{ + irqstate_t flags; + int ret; + + /* Interrupts me be disabled when this is called to (1) prevent posting + * of semphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + * + * In addition, we will also disable pre-emption to prevent other threads + * from getting control while we muck with the semaphores. + */ + + sched_lock(); + flags = irqsave(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->devsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is availble. + */ + + while (up_sample(priv, sample) < 0) + { + /* Wait for a change in the touchscreen state */ + + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + } + + /* Re-acquire the the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->devsem); + +errout: + /* Then re-enable interrupts. We might get interrupt here and there + * could be a new sample. But no new threads will run because we still + * have pre-emption disabled. + */ + + irqrestore(flags); + + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the touchscreen for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: up_open + ****************************************************************************/ + +static int up_open(FAR struct file *filep) +{ + return OK; +} + +/**************************************************************************** + * Name: up_close + ****************************************************************************/ + +static int up_close(FAR struct file *filep) +{ + return OK; +} + +/**************************************************************************** + * Name: up_read + ****************************************************************************/ + +static ssize_t up_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct up_dev_s *priv; + FAR struct touch_sample_s *report; + struct up_sample_s sample; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct up_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = up_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = up_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + goto errout; + } + } + + /* In any event, we now have sampled touchscreen data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = priv->id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + report->point[0].pressure = 42; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up */ + + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + else if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name:up_ioctl + ****************************************************************************/ + +static int up_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct up_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct up_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: up_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int up_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct up_dev_s *priv; + pollevent_t eventset; + int ndx; + int ret = OK; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct up_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->revents & POLLIN) == 0) + { + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_touchscreen_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_touchscreen_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + up_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->devsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_tcregister + * + * Description: + * Configure the touchscreen to use the provided I2C device instance. This + * will register the driver as /dev/inputN where N is the minor device + * number + * + * Input Parameters: + * dev - An I2C driver instance + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int up_tcregister(int minor) +{ + FAR struct up_dev_s *priv; + char devname[DEV_NAMELEN]; + int ret; + + ivdbg("dev: %p minor: %d\n", dev, minor); + + /* Debug-only sanity checks */ + + DEBUGASSERT(minor >= 0 && minor < 100); + + /* Create and initialize a touchscreen device driver instance */ + + priv = &g_simtouchscreen; + + /* Initialize the touchscreen device driver instance */ + + memset(priv, 0, sizeof(struct up_dev_s)); + sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ + sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ + + /* Register the device as an input device */ + + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ivdbg("Registering %s\n", devname); + + ret = register_driver(devname, &up_fops, 0666, priv); + if (ret < 0) + { + idbg("register_driver() failed: %d\n", ret); + goto errout_with_priv; + } + + /* And return success (?) */ + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); +#ifdef CONFIG_touchscreen_MULTIPLE + kfree(priv); +#endif + return ret; +} + +/**************************************************************************** + * Name: up_tcenter + ****************************************************************************/ + +int up_tcenter(int x, int y, int buttons) +{ + FAR struct up_dev_s *priv = (FAR struct up_dev_s *)&g_simtouchscreen; + bool pendown; /* true: pend is down */ + + /* Any button press will count as pendown. */ + + pendown = (buttons != 0); + + /* Handle the change from pen down to pen up */ + + if (!pendown) + { + /* Ignore the pend up if the pen was already up (CONTACT_NONE == pen up and + * already reported. CONTACT_UP == pen up, but not reported) + */ + + if (priv->sample.contact == CONTACT_NONE) + { + return OK; + } + + /* Not yet reported */ + + priv->sample.contact = CONTACT_UP; + } + else + { + /* Save the measurements */ + + priv->sample.x = x; + priv->sample.y = y; + + /* Note the availability of new measurements */ + /* If this is the first (acknowledged) pen down report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + } + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that nes touchscreen data is available */ + + up_notify(priv); + return OK; +} + +/**************************************************************************** + * Name: up_tcleave + ****************************************************************************/ + +int up_tcleave(int x, int y, int buttons) +{ + FAR struct up_dev_s *priv = (FAR struct up_dev_s *)&g_simtouchscreen; + + /* Treat leaving as penup */ + + /* Ignore the pen up if the pen was already up (CONTACT_NONE == pen up and + * already reported. CONTACT_UP == pen up, but not reported) + */ + + if (priv->sample.contact != CONTACT_NONE) + { + priv->sample.contact = CONTACT_UP; + } + return OK; +} + + diff --git a/nuttx/arch/sim/src/up_x11eventloop.c b/nuttx/arch/sim/src/up_x11eventloop.c new file mode 100644 index 000000000..d28a03ab9 --- /dev/null +++ b/nuttx/arch/sim/src/up_x11eventloop.c @@ -0,0 +1,168 @@ +/**************************************************************************** + * arch/sim/src/up_x11eventloop.c + * + * Copyright (C) 2011 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 + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ***************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +extern int up_tcenter(int x, int y, int buttons); +extern int up_tcleave(int x, int y, int buttons); + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/* Defined in up_x11framebuffer.c */ + +extern Display *g_display; +extern Window g_window; + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ***************************************************************************/ + +/**************************************************************************** + * Name: up_x11eventloop + ***************************************************************************/ + +static int up_buttonmap(int state) +{ + int ret = 0; + + /* Remove any X11 dependencies. Possible bit settings include: Button1Mask, + * Button2Mask, Button3Mask, Button4Mask, Button5Mask, ShiftMask, LockMask, + * ControlMask, Mod1Mask, Mod2Mask, Mod3Mask, Mod4Mask, Mod5Mask. I assume + * that for a mouse device Button1Mask, Button2Mask, and Button3Mask are + * sufficient. + */ + + if ((state & Button1Mask) != 0) + { + ret |= 1; + } + + if ((state & Button2Mask) != 0) + { + ret |= 2; + } + + if ((state & Button3Mask) != 0) + { + ret |= 4; + } + return ret; +} + +/**************************************************************************** + * Public Functions + ***************************************************************************/ + +/**************************************************************************** + * Name: up_x11eventloop + ***************************************************************************/ + +int up_x11eventloop(int argc, char *argv[]) +{ + XEvent event; + int ret; + + /* Grab the pointer (mouse) */ + + ret = XGrabPointer(g_display, g_window, 0, + EnterWindowMask|LeaveWindowMask, + GrabModeAsync, GrabModeAsync, None, None, CurrentTime); + if (ret != GrabSuccess) + { + fprintf(stderr, "Failed grap pointer\n"); + return -1; + } + + /* Then loop forever, waiting for events and processing events as they are + * received. + */ + + for (;;) + { + XNextEvent(g_display, &event); + switch (event.type) + { + case EnterNotify: + { + fprintf(stderr, "EnterNotify event: (%d,%d) %08x\n", + event.xcrossing.x, event.xcrossing.y, event.xcrossing.state); + up_tcenter(event.xcrossing.x, event.xcrossing.y, + up_buttonmap(event.xcrossing.state)); + } + break; + + case LeaveNotify : + { + fprintf(stderr, "LeaveNotify event: (%d,%d) %08x\n", + event.xcrossing.x, event.xcrossing.y, event.xcrossing.state); + up_tcleave(event.xcrossing.x, event.xcrossing.y, + up_buttonmap(event.xcrossing.state)); + } + break; + + default : + fprintf(stderr, "Unrecognized event: %d\n", event.type); + break; + } + } + return 0; +} diff --git a/nuttx/arch/sim/src/up_x11framebuffer.c b/nuttx/arch/sim/src/up_x11framebuffer.c index 0aa58a6a7..ad02625de 100644 --- a/nuttx/arch/sim/src/up_x11framebuffer.c +++ b/nuttx/arch/sim/src/up_x11framebuffer.c @@ -64,16 +64,19 @@ ****************************************************************************/ /**************************************************************************** - * Global Variables + * Public Variables ****************************************************************************/ +/* Also used in up_x11eventloop */ + +Display *g_display; +Window g_window; + /**************************************************************************** * Private Variables ****************************************************************************/ -static Display *g_display; static int g_screen; -static Window g_window; static GC g_gc; #ifndef CONFIG_SIM_X11NOSHM static XShmSegmentInfo g_xshminfo; @@ -438,4 +441,3 @@ void up_x11update(void) } XSync(g_display, 0); } - diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt index 9d16abc37..d2fb92ccd 100644 --- a/nuttx/configs/sim/README.txt +++ b/nuttx/configs/sim/README.txt @@ -68,7 +68,7 @@ X11 Issues ^^^^^^^^^^ There is an X11-based framebuffer driver that you can use exercise the NuttX graphics -subsystem on the simulator (see the sim/nx configuration below). This may require a +subsystem on the simulator (see the sim/nx11 configuration below). This may require a lot of tinkering to get working, depending upon where your X11 installation stores libraries and header files and how it names libraries. @@ -87,6 +87,9 @@ Configurations ^^^^^^^^^^^^^^ mount + + Description + ----------- Configures to use examples/mount. This configuration may be selected as follows: @@ -95,6 +98,8 @@ mount nettest + Description + ----------- Configures to use examples/nettest. This configuration enables networking using the network TAP device. It may be selected via: @@ -118,6 +123,9 @@ nettest select the IP address that you want to use. nsh + + Description + ----------- Configures to use the NuttShell at examples/nsh. This configuration may be selected as follows: @@ -125,59 +133,112 @@ nsh ./configure.sh sim/nsh nx + + Description + ----------- Configures to use examples/nx. This configuration may be selected as follows: cd /tools ./configure.sh sim/nx + Special Framebuffer Configuration + --------------------------------- Special simulated framebuffer configuration options: - CONFIG_SIM_X11FB - Use X11 window for framebuffer - CONFIG_SIM_FBHEIGHT - Height of the framebuffer in pixels - CONFIG_SIM_FBWIDTH - Width of the framebuffer in pixels. - CONFIG_SIM_FBBPP - Pixel depth in bits + CONFIG_SIM_FBHEIGHT - Height of the framebuffer in pixels + CONFIG_SIM_FBWIDTH - Width of the framebuffer in pixels. + CONFIG_SIM_FBBPP - Pixel depth in bits + + No Display! + ----------- + This version has NO DISPLAY and is only useful for debugging NX + internals in environments where X11 is not supported. There is + and additonal configuration that may be added to include an X11- + based simulated framebuffer driver: + + CONFIG_SIM_X11FB - Use X11 window for framebuffer + + See the nx11 configuration below for more information. + + Multi- and Single-User Modes + ---------------------------- + The default is the single-user NX implementation. To select + the multi-user NX implementation: + + CONFG_NX_MULTIUSER=y + CONFIG_DISABLE_MQUEUE=n + +nx11 + + Description + ----------- + Configures to use examples/nx. This configuration is similar + to the nx configuration except that it addes support for an X11- + based framebuffer driver. Of course, this configuration can only + be used in environments that support X11! (And it may not even + be usable in all of those environments without some "tweaking"). + + This configuration may be selected as follows: - NOTES: - - If CONFIG_SIM_X11FB is selected then the following are - needed + cd /tools + ./configure.sh sim/nx11 - CONFIG_SIM_FBBPP (must match the resolution of the display). - CONFIG_FB_CMAP=y + Special Framebuffer Configuration + --------------------------------- + This configuration uses the same special simulated framebuffer + configuration options as the nx configuration: - My system has 24-bit color, but packed into 32-bit words so - the correct seeting of CONFIG_SIM_FBBPP is 32. + CONFIG_SIM_X11FB - Use X11 window for framebuffer + CONFIG_SIM_FBHEIGHT - Height of the framebuffer in pixels + CONFIG_SIM_FBWIDTH - Width of the framebuffer in pixels. + CONFIG_SIM_FBBPP - Pixel depth in bits - - For whatever value of CONFIG_SIM_FBBPP is selected, then - the corresponidng CONFIG_NX_DISABLE_*BPP setting must - not be disabled. + X11 Configuration + ----------------- + But now, since CONFIG_SIM_X11FB is also selected the following + definitions are needed - - The default in defconfig is to use a generic memory buffer - for the framebuffer. defconfig-x11 is an example with X11 - support enabled. To use this configuration you have to - configure as follows: + CONFIG_SIM_FBBPP (must match the resolution of the display). + CONFIG_FB_CMAP=y - cd tools - ./configure.sh sim/nx - cd .. - cp configs/sim/nx/defconfig-x11 .config + My system has 24-bit color, but packed into 32-bit words so + the correct seeting of CONFIG_SIM_FBBPP is 32. + + For whatever value of CONFIG_SIM_FBBPP is selected, the + corresponidng CONFIG_NX_DISABLE_*BPP setting must not be + disabled. - - The default is the single-user NX implementation. To select - the multi-user NX implementation: + Touchscreen Support + ------------------- + A X11 mouse-based touchscreen simulation can also be enabled + by setting: - CONFG_NX_MULTIUSER=y - CONFIG_DISABLE_MQUEUE=n + CONFIG_INPUT=y + CONFIG_SIM_TOUCHSCREEN=y - - To get the system to compile under various X11 installations - you may have to modify a few things. For example, in order - to find libXext, I had to make the following change under - Ubuntu 9.09: + X11 Build Issues + ---------------- + To get the system to compile under various X11 installations + you may have to modify a few things. For example, in order + to find libXext, I had to make the following change under + Ubuntu 9.09: cd /usr/lib/ sudo ln -s libXext.so.6.4.0 libXext.so + Multi- and Single-User Modes + ---------------------------- + The default is the single-user NX implementation. To select + the multi-user NX implementation: + + CONFG_NX_MULTIUSER=y + CONFIG_DISABLE_MQUEUE=n + ostest + Description + ----------- The "standard" NuttX examples/ostest configuration. This configuration may be selected as follows: @@ -186,6 +247,8 @@ ostest pashello + Description + ----------- Configures to use examples/pashello. This configuration may by selected as follows: diff --git a/nuttx/configs/sim/nx/defconfig-x11 b/nuttx/configs/sim/nx/defconfig-x11 deleted file mode 100644 index 9228786df..000000000 --- a/nuttx/configs/sim/nx/defconfig-x11 +++ /dev/null @@ -1,564 +0,0 @@ -############################################################################ -# sim/nx/defconfig -# -# Copyright (C) 2008, 2010 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. -# -############################################################################ -# -# Architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_name - for use in C code. This identifies the particular -# processor architecture (CONFIG_ARCH_SIM). -# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# -CONFIG_ARCH=sim -CONFIG_ARCH_SIM=y -CONFIG_ARCH_BOARD=sim -CONFIG_ARCH_BOARD_SIM=y - -# -# Simulated framebuffer configuration -CONFIG_SIM_X11FB=y -CONFIG_SIM_FBWIDTH=480 -CONFIG_SIM_FBHEIGHT=240 -CONFIG_SIM_FBBPP=32 - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# CONFIG_DEBUG_SYMBOLS - build without optimization and with -# debug symbols (needed for use with a debugger). -# CONFIG_MM_REGIONS - If the architecture includes multiple -# regions of memory to allocate from, this specifies the -# number of memory regions that the memory manager must -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_JULIAN_TIME - Enables Julian time conversions -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket -# desciptors by task_create() when a new task is started. If -# set, all sockets will appear to be closed in the new task. -# -#CONFIG_APPS_DIR= -CONFIG_DEBUG=y -CONFIG_DEBUG_VERBOSE=y -CONFIG_DEBUG_SYMBOLS=n -CONFIG_DEBUG_GRAPHICS=y -CONFIG_MM_REGIONS=1 -CONFIG_ARCH_LOWPUTC=y -CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n -CONFIG_TASK_NAME_SIZE=32 -CONFIG_START_YEAR=2008 -CONFIG_START_MONTH=11 -CONFIG_START_DAY=28 -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=n -CONFIG_SDCLONE_DISABLE=y - -# -# The following can be used to disable categories of -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=y -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=y -CONFIG_DISABLE_ENVIRON=y -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve sysem performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_RAW_BINARY=n -CONFIG_HAVE_LIBM=y - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# CONFIG_NAME_MAX - The maximum size of a file name. -# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate -# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_NUNGET_CHARS - Number of characters that can be -# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) -# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=16 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=4 -CONFIG_NFILE_DESCRIPTORS=16 -CONFIG_NFILE_STREAMS=16 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=1024 -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=32 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=4 -CONFIG_PREALLOC_WDOGS=32 -CONFIG_PREALLOC_TIMERS=8 - -# -# Framebuffer driver options -CONFIG_FB_CMAP=y -CONFIG_FB_HWCURSOR=n -CONFIG_FB_HWCURSORIMAGE=n -#CONFIG_FB_HWCURSORSIZE -#CONFIG_FB_TRANSPARENCY - -# -# FAT filesystem configuration -# CONFIG_FS_FAT - Enable FAT filesystem support -# CONFIG_FAT_SECTORSIZE - Max supported sector size -# CONFIG_FS_ROMFS - Enable ROMFS filesystem support -CONFIG_FS_FAT=n -CONFIG_FS_ROMFS=n - -# -# TCP/IP and UDP support via uIP -# CONFIG_NET - Enable or disable all network features -# CONFIG_NET_IPv6 - Build in support for IPv6 -# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. -# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options -# CONFIG_NET_BUFSIZE - uIP buffer size -# CONFIG_NET_TCP - TCP support on or off -# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) -# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers -# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) -# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until -# accept() is called. The size of the backlog is selected when listen() is called. -# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) -# CONFIG_NET_UDP - UDP support on or off -# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off -# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections -# CONFIG_NET_ICMP - ICMP ping response support on or off -# CONFIG_NET_ICMP_PING - ICMP ping request support on or off -# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address -# CONFIG_NET_STATISTICS - uIP statistics on or off -# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window -# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table -# CONFIG_NET_BROADCAST - Broadcast support -# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates -# -CONFIG_NET=n -CONFIG_NET_IPv6=n -CONFIG_NSOCKET_DESCRIPTORS=0 -CONFIG_NET_SOCKOPTS=y -CONFIG_NET_BUFSIZE=420 -CONFIG_NET_TCP=n -CONFIG_NET_TCP_CONNS=40 -CONFIG_NET_MAX_LISTENPORTS=40 -CONFIG_NET_UDP=n -CONFIG_NET_UDP_CHECKSUMS=y -#CONFIG_NET_UDP_CONNS=10 -CONFIG_NET_ICMP=n -CONFIG_NET_ICMP_PING=n -#CONFIG_NET_PINGADDRCONF=0 -CONFIG_NET_STATISTICS=y -#CONFIG_NET_RECEIVE_WINDOW= -#CONFIG_NET_ARPTAB_SIZE=8 -CONFIG_NET_BROADCAST=n -#CONFIG_NET_FWCACHE_SIZE=2 - -# -# UIP Network Utilities -# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP -# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries -CONFIG_NET_DHCP_LIGHT=n -CONFIG_NET_RESOLV_ENTRIES=4 - -# -# Graphics related configuration settings -# -# CONFIG_NX -# Enables overall support for graphics library and NX -# CONFIG_NX_MULTIUSER -# Configures NX in multi-user mode -# CONFIG_NX_NPLANES -# Some YUV color formats requires support for multiple planes, -# one for each color component. Unless you have such special -# hardware, this value should be undefined or set to 1 -# CONFIG_NX_DISABLE_1BPP, CONFIG_NX_DISABLE_2BPP, -# CONFIG_NX_DISABLE_4BPP, CONFIG_NX_DISABLE_8BPP, -# CONFIG_NX_DISABLE_16BPP, CONFIG_NX_DISABLE_24BPP, and -# CONFIG_NX_DISABLE_32BPP -# NX supports a variety of pixel depths. You can save some -# memory by disabling support for unused color depths. -# CONFIG_NX_PACKEDMSFIRST -# If a pixel depth of less than 8-bits is used, then NX needs -# to know if the pixels pack from the MS to LS or from LS to MS -# CONFIG_NX_MOUSE -# Build in support for mouse input -# CONFIG_NX_KBD -# Build in support of keypad/keyboard input -# CONFIG_NXTK_BORDERWIDTH -# Specifies with with of the border (in pixels) used with -# framed windows. The default is 4. -# CONFIG_NXTK_BORDERCOLOR1 and CONFIG_NXTK_BORDERCOLOR2 -# Specify the colors of the border used with framed windows. -# CONFIG_NXTK_BORDERCOLOR2 is the shadow side color and so -# is normally darker. The default is medium and dark grey, -# respectively -# CONFIG_NXTK_AUTORAISE -# If set, a window will be raised to the top if the mouse position -# is over a visible portion of the window. Default: A mouse -# button must be clicked over a visible portion of the window. -# CONFIG_NXFONTS_CHARBITS -# The number of bits in the character set. Current options are -# only 7 and 8. The default is 7. -# CONFIG_NXFONT_SANS23X27 -# At present, there is only one font. But if there were were more, -# then this option would select the sans serif font. -# -# NX Multi-user only options: -# -# CONFIG_NX_BLOCKING -# Open the client message queues in blocking mode. In this case, -# nx_eventhandler() will not return until a message is received and processed. -# CONFIG_NX_MXSERVERMSGS and CONFIG_NX_MXCLIENTMSGS -# Specifies the maximum number of messages that can fit in -# the message queues. No additional resources are allocated, but -# this can be set to prevent flooding of the client or server with -# too many messages (CONFIG_PREALLOC_MQ_MSGS controls how many -# messages are pre-allocated). -# -CONFIG_NX=y -CONFIG_NX_MULTIUSER=n -CONFIG_NX_NPLANES=1 -CONFIG_NX_DISABLE_1BPP=y -CONFIG_NX_DISABLE_2BPP=y -CONFIG_NX_DISABLE_4BPP=y -CONFIG_NX_DISABLE_8BPP=y -CONFIG_NX_DISABLE_16BPP=y -CONFIG_NX_DISABLE_24BPP=y -CONFIG_NX_DISABLE_32BPP=n -CONFIG_NX_PACKEDMSFIRST=n -CONFIG_NX_MOUSE=y -CONFIG_NX_KBD=y -#CONFIG_NXTK_BORDERWIDTH=4 -#CONFIG_NXTK_BORDERCOLOR1 -#CONFIG_NXTK_BORDERCOLOR2 -CONFIG_NXTK_AUTORAISE=n -CONFIG_NXFONT_SANS23X27=y -CONFIG_NXFONTS_CHARBITS=7 -CONFIG_NX_BLOCKING=y -CONFIG_NX_MXSERVERMSGS=32 -CONFIG_NX_MXCLIENTMSGS=16 - -# -# Settings for examples/uip -CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|0<<8|128) -CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|0<<8|1) -CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_UIP_DHCPC=n - -# -# Settings for examples/nettest -CONFIG_EXAMPLE_NETTEST_SERVER=n -CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n -CONFIG_EXAMPLE_NETTEST_NOMAC=n -CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) -CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) -CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) - -# -# Settings for examples/ostest -CONFIG_EXAMPLES_OSTEST_LOOPS=100 -CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer -# CONFIG_NSH_STRERROR - Use strerror(errno) -# CONFIG_NSH_LINELEN - Maximum length of one command line -# CONFIG_NSH_STACKSIZE - Stack size to use for new threads. -# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# -# If CONFIG_NSH_TELNET is selected: -# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size -# CONFIG_NSH_DHCPC - Obtain address using DHCP -# CONFIG_NSH_IPADDR - Provides static IP address -# CONFIG_NSH_DRIPADDR - Provides static router IP address -# CONFIG_NSH_NETMASK - Provides static network mask -# CONFIG_NSH_NOMAC - Use a bogus MAC address -# -# If CONFIG_NSH_ROMFSETC is selected: -# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint -# CONFIG_NSH_INITSCRIPT - Relative path to init script -# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor -# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size -# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor -# CONFIG_NSH_FATSECTSIZE - FAT FS sector size -# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors -# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint -CONFIG_NSH_FILEIOSIZE=1024 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=80 -CONFIG_NSH_STACKSIZE=4096 -CONFIG_NSH_NESTDEPTH=3 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=y -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) -CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) -CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=1 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=2 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT=/tmp - -# -# Settings for examples/nx -# -# CONFIG_EXAMPLES_NX_VPLANE -- The plane to select from the frame- -# buffer driver for use in the test. Default: 0 -# CONFIG_EXAMPLES_NX_BGCOLOR -- The color of the background. Default depends on -# CONFIG_EXAMPLES_NX_BPP. -# CONFIG_EXAMPLES_NX_COLOR1 -- The color of window 1. Default depends on -# CONFIG_EXAMPLES_NX_BPP. -# CONFIG_EXAMPLES_NX_COLOR2 -- The color of window 2. Default depends on -# CONFIG_EXAMPLES_NX_BPP. -# CONFIG_EXAMPLES_NX_TBCOLOR -- The color of the toolbar. Default depends on -# CONFIG_EXAMPLES_NX_BPP. -# CONFIG_EXAMPLES_NX_FONTCOLOR -- The color of the toolbar. Default depends on -# CONFIG_EXAMPLES_NX_BPP. -# CONFIG_EXAMPLES_NX_BPP -- Pixels per pixel to use. Valid options -# include 2, 4, 8, 16, 24, and 32. Default is 32. -# CONFIG_EXAMPLES_NX_RAWWINDOWS -- Use raw windows; Default is to -# use pretty, framed NXTK windows with toolbars. -# CONFIG_EXAMPLES_NX_STACKSIZE -- The stacksize to use when creating -# the NX server. Default 2048 -# CONFIG_EXAMPLES_NX_CLIENTPRIO -- The client priority. Default: 80 -# CONFIG_EXAMPLES_NX_SERVERPRIO -- The server priority. Default: 120 -# CONFIG_EXAMPLES_NX_NOTIFYSIGNO -- The signal number to use with -# nx_eventnotify(). Default: 4 -CONFIG_EXAMPLES_NX_VPLANE=0 -#CONFIG_EXAMPLES_NX_BGCOLOR -#CONFIG_EXAMPLES_NX_COLOR1 -#CONFIG_EXAMPLES_NX_COLOR2 -#CONFIG_EXAMPLES_NX_TBCOLOR -#CONFIG_EXAMPLES_NX_FONTCOLOR -CONFIG_EXAMPLES_NX_BPP=CONFIG_SIM_FBBPP -CONFIG_EXAMPLES_NX_RAWWINDOWS=n -CONFIG_EXAMPLES_NX_STACKSIZE=8192 -CONFIG_EXAMPLES_NX_CLIENTPRIO=80 -CONFIG_EXAMPLES_NX_SERVERPRIO=120 -CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 - -# -# Settings for examples/mount -CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" -#CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 -#CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 -#CONFIG_EXAMPLES_MOUNT_RAMDEVNO=1 - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2) there after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_IDLETHREAD_STACKSIZE=4096 -CONFIG_USERMAIN_STACKSIZE=4096 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=8192 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/sim/nx11/Make.defs b/nuttx/configs/sim/nx11/Make.defs new file mode 100644 index 000000000..642dfbaf8 --- /dev/null +++ b/nuttx/configs/sim/nx11/Make.defs @@ -0,0 +1,110 @@ +############################################################################ +# configs/sim/nx11/Make.defs +# +# Copyright (C) 2008, 2011 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. +# +############################################################################ + +include ${TOPDIR}/.config + +HOSTOS = ${shell uname -o 2>/dev/null || echo "Other"} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = -O2 +endif + +ARCHCPUFLAGS = -fno-builtin +ARCHPICFLAGS = -fpic +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHDEFINES = +ARCHINCLUDES = -I. -isystem $(TOPDIR)/include +ARCHSCRIPT = + +CROSSDEV = +CC = $(CROSSDEV)gcc +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +OBJEXT = .o +LIBEXT = .a + +ifeq ($(HOSTOS),Cygwin) + EXEEXT = .exe +else + EXEEXT = +endif + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") + LDFLAGS += -g +endif + +define PREPROCESS + @echo "CPP: $1->$2" + @$(CPP) $(CPPFLAGS) $1 -o $2 +endef + +define COMPILE + @echo "CC: $1" + @$(CC) -c $(CFLAGS) $1 -o $2 +endef + +define ASSEMBLE + @echo "AS: $1" + @$(CC) -c $(AFLAGS) $1 -o $2 +endef + +define ARCHIVE + echo "AR: $2"; \ + $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; } +endef + +define CLEAN + @rm -f *.o *.a +endef + +MKDEP = $(TOPDIR)/tools/mkdeps.sh + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/sim/nx11/appconfig b/nuttx/configs/sim/nx11/appconfig new file mode 100644 index 000000000..d99648abc --- /dev/null +++ b/nuttx/configs/sim/nx11/appconfig @@ -0,0 +1,39 @@ +############################################################################ +# configs/sim/nx11/appconfig +# +# Copyright (C) 2011 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nx + diff --git a/nuttx/configs/sim/nx11/defconfig b/nuttx/configs/sim/nx11/defconfig new file mode 100644 index 000000000..420231d48 --- /dev/null +++ b/nuttx/configs/sim/nx11/defconfig @@ -0,0 +1,572 @@ +############################################################################ +# sim/nx11/defconfig +# +# Copyright (C) 2008, 2010-2011 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. +# +############################################################################ +# +# Architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the particular +# processor architecture (CONFIG_ARCH_SIM). +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=sim +CONFIG_ARCH_SIM=y +CONFIG_ARCH_BOARD=sim +CONFIG_ARCH_BOARD_SIM=y + +# +# Simulated framebuffer configuration +# +CONFIG_SIM_X11FB=y +CONFIG_SIM_FBWIDTH=480 +CONFIG_SIM_FBHEIGHT=240 +CONFIG_SIM_FBBPP=32 + +# +# Simulated touchscreen configuration +# (Set both of the following to 'y' to enable) +# +CONFIG_INPUT=n +CONFIG_SIM_TOUCHSCREEN=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=y +CONFIG_DEBUG_SYMBOLS=n +CONFIG_DEBUG_GRAPHICS=y +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2008 +CONFIG_START_MONTH=11 +CONFIG_START_DAY=28 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=n +CONFIG_SDCLONE_DISABLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_RAW_BINARY=n +CONFIG_HAVE_LIBM=y + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=16 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=1024 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 + +# +# Framebuffer driver options +CONFIG_FB_CMAP=y +CONFIG_FB_HWCURSOR=n +CONFIG_FB_HWCURSORIMAGE=n +#CONFIG_FB_HWCURSORSIZE +#CONFIG_FB_TRANSPARENCY + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +CONFIG_FS_FAT=n +CONFIG_FS_ROMFS=n + +# +# TCP/IP and UDP support via uIP +# CONFIG_NET - Enable or disable all network features +# CONFIG_NET_IPv6 - Build in support for IPv6 +# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread. +# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options +# CONFIG_NET_BUFSIZE - uIP buffer size +# CONFIG_NET_TCP - TCP support on or off +# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks) +# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers +# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero) +# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until +# accept() is called. The size of the backlog is selected when listen() is called. +# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks) +# CONFIG_NET_UDP - UDP support on or off +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_ICMP - ICMP ping response support on or off +# CONFIG_NET_ICMP_PING - ICMP ping request support on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +# +CONFIG_NET=n +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=0 +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_BUFSIZE=420 +CONFIG_NET_TCP=n +CONFIG_NET_TCP_CONNS=40 +CONFIG_NET_MAX_LISTENPORTS=40 +CONFIG_NET_UDP=n +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_ICMP=n +CONFIG_NET_ICMP_PING=n +#CONFIG_NET_PINGADDRCONF=0 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_RECEIVE_WINDOW= +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Graphics related configuration settings +# +# CONFIG_NX +# Enables overall support for graphics library and NX +# CONFIG_NX_MULTIUSER +# Configures NX in multi-user mode +# CONFIG_NX_NPLANES +# Some YUV color formats requires support for multiple planes, +# one for each color component. Unless you have such special +# hardware, this value should be undefined or set to 1 +# CONFIG_NX_DISABLE_1BPP, CONFIG_NX_DISABLE_2BPP, +# CONFIG_NX_DISABLE_4BPP, CONFIG_NX_DISABLE_8BPP, +# CONFIG_NX_DISABLE_16BPP, CONFIG_NX_DISABLE_24BPP, and +# CONFIG_NX_DISABLE_32BPP +# NX supports a variety of pixel depths. You can save some +# memory by disabling support for unused color depths. +# CONFIG_NX_PACKEDMSFIRST +# If a pixel depth of less than 8-bits is used, then NX needs +# to know if the pixels pack from the MS to LS or from LS to MS +# CONFIG_NX_MOUSE +# Build in support for mouse input +# CONFIG_NX_KBD +# Build in support of keypad/keyboard input +# CONFIG_NXTK_BORDERWIDTH +# Specifies with with of the border (in pixels) used with +# framed windows. The default is 4. +# CONFIG_NXTK_BORDERCOLOR1 and CONFIG_NXTK_BORDERCOLOR2 +# Specify the colors of the border used with framed windows. +# CONFIG_NXTK_BORDERCOLOR2 is the shadow side color and so +# is normally darker. The default is medium and dark grey, +# respectively +# CONFIG_NXTK_AUTORAISE +# If set, a window will be raised to the top if the mouse position +# is over a visible portion of the window. Default: A mouse +# button must be clicked over a visible portion of the window. +# CONFIG_NXFONTS_CHARBITS +# The number of bits in the character set. Current options are +# only 7 and 8. The default is 7. +# CONFIG_NXFONT_SANS23X27 +# At present, there is only one font. But if there were were more, +# then this option would select the sans serif font. +# +# NX Multi-user only options: +# +# CONFIG_NX_BLOCKING +# Open the client message queues in blocking mode. In this case, +# nx_eventhandler() will not return until a message is received and processed. +# CONFIG_NX_MXSERVERMSGS and CONFIG_NX_MXCLIENTMSGS +# Specifies the maximum number of messages that can fit in +# the message queues. No additional resources are allocated, but +# this can be set to prevent flooding of the client or server with +# too many messages (CONFIG_PREALLOC_MQ_MSGS controls how many +# messages are pre-allocated). +# +CONFIG_NX=y +CONFIG_NX_MULTIUSER=n +CONFIG_NX_NPLANES=1 +CONFIG_NX_DISABLE_1BPP=y +CONFIG_NX_DISABLE_2BPP=y +CONFIG_NX_DISABLE_4BPP=y +CONFIG_NX_DISABLE_8BPP=y +CONFIG_NX_DISABLE_16BPP=y +CONFIG_NX_DISABLE_24BPP=y +CONFIG_NX_DISABLE_32BPP=n +CONFIG_NX_PACKEDMSFIRST=n +CONFIG_NX_MOUSE=y +CONFIG_NX_KBD=y +#CONFIG_NXTK_BORDERWIDTH=4 +#CONFIG_NXTK_BORDERCOLOR1 +#CONFIG_NXTK_BORDERCOLOR2 +CONFIG_NXTK_AUTORAISE=n +CONFIG_NXFONT_SANS23X27=y +CONFIG_NXFONTS_CHARBITS=7 +CONFIG_NX_BLOCKING=y +CONFIG_NX_MXSERVERMSGS=32 +CONFIG_NX_MXCLIENTMSGS=16 + +# +# Settings for examples/uip +CONFIG_EXAMPLE_UIP_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_UIP_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_UIP_DHCPC=n + +# +# Settings for examples/nettest +CONFIG_EXAMPLE_NETTEST_SERVER=n +CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n +CONFIG_EXAMPLE_NETTEST_NOMAC=n +CONFIG_EXAMPLE_NETTEST_IPADDR=(192<<24|168<<16|0<<8|128) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(192<<24|168<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(192<<24|168<<16|0<<8|106) + +# +# Settings for examples/ostest +CONFIG_EXAMPLES_OSTEST_LOOPS=100 +CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192 + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_STACKSIZE - Stack size to use for new threads. +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +CONFIG_NSH_FILEIOSIZE=1024 +CONFIG_NSH_STRERROR=n +CONFIG_NSH_LINELEN=80 +CONFIG_NSH_STACKSIZE=4096 +CONFIG_NSH_NESTDEPTH=3 +CONFIG_NSH_DISABLESCRIPT=n +CONFIG_NSH_DISABLEBG=n +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) +CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) +CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=1 +CONFIG_NSH_ROMFSSECTSIZE=64 +CONFIG_NSH_FATDEVNO=2 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT=/tmp + +# +# Settings for examples/nx +# +# CONFIG_EXAMPLES_NX_VPLANE -- The plane to select from the frame- +# buffer driver for use in the test. Default: 0 +# CONFIG_EXAMPLES_NX_BGCOLOR -- The color of the background. Default depends on +# CONFIG_EXAMPLES_NX_BPP. +# CONFIG_EXAMPLES_NX_COLOR1 -- The color of window 1. Default depends on +# CONFIG_EXAMPLES_NX_BPP. +# CONFIG_EXAMPLES_NX_COLOR2 -- The color of window 2. Default depends on +# CONFIG_EXAMPLES_NX_BPP. +# CONFIG_EXAMPLES_NX_TBCOLOR -- The color of the toolbar. Default depends on +# CONFIG_EXAMPLES_NX_BPP. +# CONFIG_EXAMPLES_NX_FONTCOLOR -- The color of the toolbar. Default depends on +# CONFIG_EXAMPLES_NX_BPP. +# CONFIG_EXAMPLES_NX_BPP -- Pixels per pixel to use. Valid options +# include 2, 4, 8, 16, 24, and 32. Default is 32. +# CONFIG_EXAMPLES_NX_RAWWINDOWS -- Use raw windows; Default is to +# use pretty, framed NXTK windows with toolbars. +# CONFIG_EXAMPLES_NX_STACKSIZE -- The stacksize to use when creating +# the NX server. Default 2048 +# CONFIG_EXAMPLES_NX_CLIENTPRIO -- The client priority. Default: 80 +# CONFIG_EXAMPLES_NX_SERVERPRIO -- The server priority. Default: 120 +# CONFIG_EXAMPLES_NX_NOTIFYSIGNO -- The signal number to use with +# nx_eventnotify(). Default: 4 +CONFIG_EXAMPLES_NX_VPLANE=0 +#CONFIG_EXAMPLES_NX_BGCOLOR +#CONFIG_EXAMPLES_NX_COLOR1 +#CONFIG_EXAMPLES_NX_COLOR2 +#CONFIG_EXAMPLES_NX_TBCOLOR +#CONFIG_EXAMPLES_NX_FONTCOLOR +CONFIG_EXAMPLES_NX_BPP=CONFIG_SIM_FBBPP +CONFIG_EXAMPLES_NX_RAWWINDOWS=n +CONFIG_EXAMPLES_NX_STACKSIZE=8192 +CONFIG_EXAMPLES_NX_CLIENTPRIO=80 +CONFIG_EXAMPLES_NX_SERVERPRIO=120 +CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4 + +# +# Settings for examples/mount +CONFIG_EXAMPLES_MOUNT_DEVNAME="/dev/ram0" +#CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 +#CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 +#CONFIG_EXAMPLES_MOUNT_RAMDEVNO=1 + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/sim/nx11/setenv.sh b/nuttx/configs/sim/nx11/setenv.sh new file mode 100755 index 000000000..dd51ecec2 --- /dev/null +++ b/nuttx/configs/sim/nx11/setenv.sh @@ -0,0 +1,45 @@ +#!/bin/bash +# sim/nx11/setenv.sh +# +# Copyright (C) 2008, 2011 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi + +#export NUTTX_BIN= +#export PATH=${NUTTX_BIN}:/sbin:/usr/sbin:${PATH_ORIG} + +echo "PATH : ${PATH}" -- cgit v1.2.3