summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/sim/src/up_initialize.c21
-rw-r--r--nuttx/arch/sim/src/up_internal.h1
-rw-r--r--nuttx/arch/sim/src/up_touchscreen.c38
-rw-r--r--nuttx/configs/sim/README.txt65
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c2
-rw-r--r--nuttx/include/nuttx/input/touchscreen.h20
6 files changed, 100 insertions, 47 deletions
diff --git a/nuttx/arch/sim/src/up_initialize.c b/nuttx/arch/sim/src/up_initialize.c
index 26207b624..4e07904e4 100644
--- a/nuttx/arch/sim/src/up_initialize.c
+++ b/nuttx/arch/sim/src/up_initialize.c
@@ -44,7 +44,6 @@
#include <nuttx/arch.h>
#include <nuttx/fs.h>
-#include "os_internal.h"
#include "up_internal.h"
/****************************************************************************
@@ -107,24 +106,4 @@ void up_initialize(void)
#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 19e50986b..71a2380e2 100644
--- a/nuttx/arch/sim/src/up_internal.h
+++ b/nuttx/arch/sim/src/up_internal.h
@@ -182,7 +182,6 @@ extern int up_x11eventloop(int argc, char *argv[]);
#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
diff --git a/nuttx/arch/sim/src/up_touchscreen.c b/nuttx/arch/sim/src/up_touchscreen.c
index 09e4e013e..38e893128 100644
--- a/nuttx/arch/sim/src/up_touchscreen.c
+++ b/nuttx/arch/sim/src/up_touchscreen.c
@@ -58,6 +58,7 @@
#include <nuttx/input/touchscreen.h>
+#include "os_internal.h"
#include "up_internal.h"
/****************************************************************************
@@ -106,6 +107,7 @@ struct up_dev_s
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 */
+ pid_t eventloop; /* PID of the eventloop */
struct up_sample_s sample; /* Last sampled touch point data */
@@ -604,15 +606,13 @@ errout:
****************************************************************************/
/****************************************************************************
- * Name: up_tcregister
+ * Name: up_simtouchscreen
*
* 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
+ * Configure the simulated touchscreen. 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:
@@ -621,9 +621,9 @@ errout:
*
****************************************************************************/
-int up_tcregister(int minor)
+int up_simtouchscreen(int minor)
{
- FAR struct up_dev_s *priv;
+ FAR struct up_dev_s *priv = ( FAR struct up_dev_s *)&g_simtouchscreen;
char devname[DEV_NAMELEN];
int ret;
@@ -631,11 +631,7 @@ int up_tcregister(int minor)
/* Debug-only sanity checks */
- DEBUGASSERT(minor >= 0 && minor < 100);
-
- /* Create and initialize a touchscreen device driver instance */
-
- priv = &g_simtouchscreen;
+ DEBUGASSERT(minor >= 0 && minor < 100 && priv->eventloop == 0);
/* Initialize the touchscreen device driver instance */
@@ -643,6 +639,18 @@ int up_tcregister(int minor)
sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
+ /* Start the X11 event loop */
+
+ ret = KERNEL_THREAD("evloop", CONFIG_SIM_EVLOOPPRIORITY,
+ CONFIG_SIM_EVLOOPSTACKSIZE,
+ (main_t)up_x11eventloop, (const char **)NULL);
+ if (ret < 0)
+ {
+ idbg("Failed to start event loop: %d\n", ret);
+ goto errout_with_priv;
+ }
+ priv->eventloop = ret;
+
/* Register the device as an input device */
(void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
@@ -660,10 +668,8 @@ int up_tcregister(int minor)
return OK;
errout_with_priv:
+ sem_destroy(&priv->waitsem);
sem_destroy(&priv->devsem);
-#ifdef CONFIG_touchscreen_MULTIPLE
- kfree(priv);
-#endif
return ret;
}
@@ -749,5 +755,3 @@ int up_tcleave(int x, int y, int buttons)
}
return OK;
}
-
-
diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt
index d2fb92ccd..64258a6cb 100644
--- a/nuttx/configs/sim/README.txt
+++ b/nuttx/configs/sim/README.txt
@@ -1,6 +1,25 @@
README
^^^^^^
+Contents
+^^^^^^^^
+ o Overview
+ - Description
+ - Fake Interrupts
+ - Timing Fidelity
+ o Debugging
+ o Issues
+ - 64-bit Issues
+ - Buffered I/O Issues
+ - Networking Issues
+ - X11 Issues
+ o Configurations
+
+Overview
+^^^^^^^^
+
+Description
+-----------
This README file describes the contents of the build configurations available
for the NuttX "sim" target. The sim target is a NuttX port that runs as a
user-space program under Linux or Cygwin. It is a very "low fidelity" embedded
@@ -8,6 +27,8 @@ system simulation: This environment does not support any kind of asynchonous
events -- there are nothing like interrupts in this context. Therefore, there
can be no pre-empting events.
+Fake Interrupts
+---------------
In order to get timed behavior, the system timer "interrupt handler" is called
from the sim target's IDLE loop. The IDLE runs whenever there is no other task
running. So, for example, if a task calls sleep(), then that task will suspend
@@ -20,6 +41,8 @@ The sim target is used primarily as a development and test platform for new
RTOS features. It is also of academic interest. But it has no real-world
application that I know of.
+Timing Fidelity
+---------------
NOTE: In order to facility fast testing, the sim target's IDLE loop, by default,
calls the system "interrupt handler" as fast as possible. As a result, there
really are no noticeable delays when a task sleeps. However, the task really does
@@ -30,9 +53,38 @@ on each call so that the system "timer interrupt" is called at a rate approximat
correct for the system timer tick rate. With this definition in the configuration,
sleep() behavior is more or less normal.
-64-Bit Issues
-^^^^^^^^^^^^^
+Debugging
+^^^^^^^^^
+One of the best reasons to use the simulation is that is supports great, Linux-
+based debugging. Here are the steps that I following to use the Linux ddd
+graphical front-end to GDB:
+
+1. Modify the top-level configuration file. Enable debug symbols by defining
+ the following.
+
+ cd <NuttX-Directory>
+ CONFIG_DEBUG_SYMBOLS=y
+
+2. Re-build:
+
+ cd <NuttX-Directory>
+ make clean
+ make
+
+3. Then start the debugging:
+
+ ddd nuttx &
+ gdb> b user_start
+ gdb> r
+NOTE: This above steps work fine on both Linux and Cygwin. On Cygwin, you
+will need to start the Cywin-X server before running ddd.
+
+Issues
+^^^^^^
+
+64-Bit Issues
+-------------
As mentioned above, context switching is based on logic like setjmp and longjmp.
This context switching is only available for 32-bit targets. On 64-bit machines,
this context switching will fail.
@@ -50,23 +102,20 @@ are included in the LDFLAGS. See the patch 0001-Quick-hacks-to-build-sim-nsh-os
that can be found at http://tech.groups.yahoo.com/group/nuttx/files.
Buffered I/O Issues
-^^^^^^^^^^^^^^^^^^^
-
+-------------------
The simulated serial driver has some odd behavior. It will stall for a long time
on reads when the C stdio buffers are being refilled. This only effects the behavior
of things like fgetc(). Workaround: Set CONFIG_STDIO_BUFFER_SIZE=0, suppressing
all C buffered I/O.
Networking Issues
-^^^^^^^^^^^^^^^^^
-
+-----------------
I never did get networking to work on the sim target. It tries to use the tap device
(/dev/net/tun) to emulate an Ethernet NIC, but I never got it correctly integrated
with the NuttX networking (I probably should try using raw sockets instead).
X11 Issues
-^^^^^^^^^^
-
+----------
There is an X11-based framebuffer driver that you can use exercise the NuttX graphics
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
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
index 7fd1d51fc..0fa879f75 100644
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ b/nuttx/fs/nxffs/nxffs_initialize.c
@@ -280,7 +280,9 @@ errout_with_buffer:
errout_with_cache:
kfree(volume->cache);
errout_with_volume:
+#ifndef CONFIG_NXFSS_PREALLOCATED
kfree(volume);
+#endif
return ret;
}
diff --git a/nuttx/include/nuttx/input/touchscreen.h b/nuttx/include/nuttx/input/touchscreen.h
index cd5e96bae..35fdf3469 100644
--- a/nuttx/include/nuttx/input/touchscreen.h
+++ b/nuttx/include/nuttx/input/touchscreen.h
@@ -127,6 +127,26 @@ extern "C" {
#define EXTERN extern
#endif
+/****************************************************************************
+ * Name: up_simtouchscreen
+ *
+ * Description:
+ * Configure the simulated touchscreen. This will register the driver as
+ * /dev/inputN where N is the minor device number
+ *
+ * Input Parameters:
+ * 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.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_SIM_X11FB) && defined(CONFIG_SIM_TOUCHSCREEN)
+EXTERN int up_simtouchscreen(int minor);
+#endif
+
#undef EXTERN
#ifdef __cplusplus
}