summaryrefslogtreecommitdiff
path: root/NxWidgets
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-05-20 22:10:34 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-05-20 22:10:34 +0000
commit7b639cc17a46229cacb9eca78a451a66122c54d8 (patch)
tree33492e787345ddef26740d5a9c1282f59324c2b0 /NxWidgets
parent01bce341a9d065e8250f655c246c07a525779bc0 (diff)
downloadpx4-nuttx-7b639cc17a46229cacb9eca78a451a66122c54d8.tar.gz
px4-nuttx-7b639cc17a46229cacb9eca78a451a66122c54d8.tar.bz2
px4-nuttx-7b639cc17a46229cacb9eca78a451a66122c54d8.zip
Add an NxWM console/keyboard thread and eliminate all issues with NxConsole window serial input
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4755 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'NxWidgets')
-rw-r--r--NxWidgets/ChangeLog.txt12
-rw-r--r--NxWidgets/TODO.txt8
-rw-r--r--NxWidgets/UnitTests/nxwm/main.cxx45
-rw-r--r--NxWidgets/libnxwidgets/include/ccallback.hxx2
-rw-r--r--NxWidgets/nxwm/Makefile4
-rw-r--r--NxWidgets/nxwm/doc/NxWM-ThreadingModel.pptbin126464 -> 129024 bytes
-rw-r--r--NxWidgets/nxwm/include/ckeyboard.hxx133
-rw-r--r--NxWidgets/nxwm/include/ctaskbar.hxx10
-rw-r--r--NxWidgets/nxwm/include/nxwmconfig.hxx39
-rw-r--r--NxWidgets/nxwm/src/ckeyboard.cxx245
-rw-r--r--NxWidgets/nxwm/src/ctaskbar.cxx49
11 files changed, 529 insertions, 18 deletions
diff --git a/NxWidgets/ChangeLog.txt b/NxWidgets/ChangeLog.txt
index c61d48375..9a5855252 100644
--- a/NxWidgets/ChangeLog.txt
+++ b/NxWidgets/ChangeLog.txt
@@ -124,3 +124,15 @@
* NxWM:CNxConsole: Configures the NxConsole window to redirectin keyboard
input to the NxConsole; redirects standard input to the NxConsole
device driver.
+* NxWM:CKeyboard: Add a new class that implements a keyboard listener
+ thread. This thread reads from /dev/console and injects the keyboard
+ input into NX. NX will determine which window is at the top of the
+ heirarchy and re-direct the keyboard input to only that top window.
+ This solves an important problem with, for example, running multiple
+ copies of the NxConsole: On the copy of the NxConsole at the top of
+ the heirarchy should get the keyboard input.
+* UnitTests/nxwm/main.cxx: Now starts the keyboard thread if
+ CONFIG_NXWM_KEYBOARD is defined.
+* NxWM::CTaskbar: After drawing the task bar, need to raise the
+ application window otherwise the taskbar will be on the top and
+ keyboard input will not be received by the top application.
diff --git a/NxWidgets/TODO.txt b/NxWidgets/TODO.txt
index 6264d2f3d..e47b3cf1a 100644
--- a/NxWidgets/TODO.txt
+++ b/NxWidgets/TODO.txt
@@ -72,7 +72,9 @@ o NxConsole Issues
NxConsoles get their input from /dev/console which is the serial
port. The necessary change is to create an NX input device for
/dev/console that will get its input from NX.
- Status: Open
+ Status: Closed with was fixed with the last check of 5/20/2012 (about
+ SVN version 4754). The fixed version is available in SVN but
+ won't be in a released version until NxWidgets-1.2 is released.
Priority: Medium high, basically prohibits the use of multiple NSH windows.
Title: CLOSING AN NxCONSOLE
@@ -81,7 +83,9 @@ o NxConsole Issues
you close one of the NxConsoles, then the others no longer
received input (or no long generate output -- that cannot be
distinguished).
- Status: Open
+ Status: Closed with was fixed with the last check of 5/20/2012 (about
+ SVN version 4754). The fixed version is available in SVN but
+ won't be in a released version until NxWidgets-1.2 is released.
Priority: Medium high, basically prohibits the use of multiple NSH windows.
Title: DOUBLE DISPLAY UPDATES
diff --git a/NxWidgets/UnitTests/nxwm/main.cxx b/NxWidgets/UnitTests/nxwm/main.cxx
index 86ea324d5..3cc85dc43 100644
--- a/NxWidgets/UnitTests/nxwm/main.cxx
+++ b/NxWidgets/UnitTests/nxwm/main.cxx
@@ -53,6 +53,10 @@
# include "ccalibration.hxx"
#endif
+#ifdef CONFIG_NXWM_KEYBOARD
+# include "ckeyboard.hxx"
+#endif
+
/////////////////////////////////////////////////////////////////////////////
// Pre-processor Definitions
/////////////////////////////////////////////////////////////////////////////
@@ -408,7 +412,7 @@ static bool createTouchScreen(void)
printf("createTouchScreen: ERROR: Failed to create CTouchscreen\n");
return false;
}
- showTestCaseMemory("createTouchScreen: createTouchScreen: After creating CTouchscreen");
+ showTestCaseMemory("createTouchScreen: After creating CTouchscreen");
printf("createTouchScreen: Start touchscreen listener\n");
if (!g_nxwmtest.touchscreen->start())
@@ -424,6 +428,35 @@ static bool createTouchScreen(void)
#endif
/////////////////////////////////////////////////////////////////////////////
+// Name: createKeyboard
+/////////////////////////////////////////////////////////////////////////////
+
+#ifdef CONFIG_NXWM_KEYBOARD
+static bool createKeyboard(void)
+{
+ printf("createKeyboard: Creating CKeyboard\n");
+ NxWM::CKeyboard *keyboard = new NxWM::CKeyboard(g_nxwmtest.taskbar);
+ if (!keyboard)
+ {
+ printf("createKeyboard: ERROR: Failed to create CKeyboard\n");
+ return false;
+ }
+ showTestCaseMemory("createKeyboard After creating CKeyboard");
+
+ printf("createKeyboard: Start keyboard listener\n");
+ if (!keyboard->start())
+ {
+ printf("createKeyboard: ERROR: Failed start the keyboard listener\n");
+ delete keyboard;
+ return false;
+ }
+
+ showTestCaseMemory("createKeyboard: After starting the keyboard listener");
+ return true;
+}
+#endif
+
+/////////////////////////////////////////////////////////////////////////////
// Name: createCalibration
/////////////////////////////////////////////////////////////////////////////
@@ -574,6 +607,16 @@ int MAIN_NAME(int argc, char *argv[])
testCleanUpAndExit(EXIT_FAILURE);
}
+ // Create the keyboard device
+
+#ifdef CONFIG_NXWM_KEYBOARD
+ if (!createKeyboard())
+ {
+ printf(MAIN_STRING "ERROR: Failed to create the keyboard\n");
+ testCleanUpAndExit(EXIT_FAILURE);
+ }
+#endif
+
// Create the touchscreen device
#ifdef CONFIG_NXWM_TOUCHSCREEN
diff --git a/NxWidgets/libnxwidgets/include/ccallback.hxx b/NxWidgets/libnxwidgets/include/ccallback.hxx
index 8d3c13cd2..714ed1a7f 100644
--- a/NxWidgets/libnxwidgets/include/ccallback.hxx
+++ b/NxWidgets/libnxwidgets/include/ccallback.hxx
@@ -39,7 +39,7 @@
/****************************************************************************
* Included Files
****************************************************************************/
-
+
#include <nuttx/config.h>
#include <sys/types.h>
diff --git a/NxWidgets/nxwm/Makefile b/NxWidgets/nxwm/Makefile
index b0b33c73d..01b8d4513 100644
--- a/NxWidgets/nxwm/Makefile
+++ b/NxWidgets/nxwm/Makefile
@@ -51,6 +51,10 @@ ifeq ($(CONFIG_NXWM_TOUCHSCREEN),y)
CXXSRCS += ccalibration.cxx ctouchscreen.cxx
endif
+ifeq ($(CONFIG_NXWM_KEYBOARD),y)
+CXXSRCS += ckeyboard.cxx
+endif
+
# Images
CXXSRCS += glyph_calibration.cxx glyph_cmd.cxx glyph_minimize.cxx glyph_nsh.cxx
CXXSRCS += glyph_play.cxx glyph_start.cxx glyph_stop.cxx
diff --git a/NxWidgets/nxwm/doc/NxWM-ThreadingModel.ppt b/NxWidgets/nxwm/doc/NxWM-ThreadingModel.ppt
index acae788c2..1b7b43622 100644
--- a/NxWidgets/nxwm/doc/NxWM-ThreadingModel.ppt
+++ b/NxWidgets/nxwm/doc/NxWM-ThreadingModel.ppt
Binary files differ
diff --git a/NxWidgets/nxwm/include/ckeyboard.hxx b/NxWidgets/nxwm/include/ckeyboard.hxx
new file mode 100644
index 000000000..8f16bd506
--- /dev/null
+++ b/NxWidgets/nxwm/include/ckeyboard.hxx
@@ -0,0 +1,133 @@
+/****************************************************************************
+ * NxWidgets/nxwm/include/keyboard.hxx
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX, NxWidgets, nor the names of its contributors
+ * me 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_CKEYBOARD_HXX
+#define __INCLUDE_CKEYBOARD_HXX
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/nx/nxglib.h>
+
+#include <semaphore.h>
+#include <pthread.h>
+
+#include <nuttx/input/touchscreen.h>
+
+#include "cnxserver.hxx"
+#include "ccalibration.hxx"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Implementation Classes
+ ****************************************************************************/
+
+namespace NxWM
+{
+ /**
+ * The CKeyboard class provides the the calibration window and obtains
+ * callibration data.
+ */
+
+ class CKeyboard
+ {
+ private:
+ /**
+ * The state of the listener thread.
+ */
+
+ enum EListenerState
+ {
+ LISTENER_NOTRUNNING = 0, /**< The listener thread has not yet been started */
+ LISTENER_STARTED, /**< The listener thread has been started, but is not yet running */
+ LISTENER_RUNNING, /**< The listener thread is running normally */
+ LISTENER_STOPREQUESTED, /**< The listener thread has been requested to stop */
+ LISTENER_TERMINATED, /**< The listener thread terminated normally */
+ LISTENER_FAILED /**< The listener thread terminated abnormally */
+ };
+
+ /**
+ * CKeyboard state data
+ */
+
+ NXWidgets::CNxServer *m_server; /**< The current NX server */
+ int m_kbdFd; /**< File descriptor of the opened keyboard device */
+ pthread_t m_thread; /**< The listener thread ID */
+ volatile enum EListenerState m_state; /**< The state of the listener thread */
+ sem_t m_waitSem; /**< Used to synchronize with the listener thread */
+
+ /**
+ * The keyboard listener thread. This is the entry point of a thread that
+ * listeners for and dispatches keyboard events to the NX server.
+ *
+ * @param arg. The CKeyboard 'this' pointer cast to a void*.
+ * @return This function normally does not return but may return NULL on
+ * error conditions.
+ */
+
+ static FAR void *listener(FAR void *arg);
+
+ public:
+
+ /**
+ * CKeyboard Constructor
+ *
+ * @param server. An instance of the NX server. This will be needed for
+ * injecting mouse data.
+ */
+
+ CKeyboard(NXWidgets::CNxServer *server);
+
+ /**
+ * CKeyboard Destructor
+ */
+
+ ~CKeyboard(void);
+
+ /**
+ * Start the keyboard listener thread.
+ *
+ * @return True if the keyboard listener thread was correctly started.
+ */
+
+ bool start(void);
+ };
+}
+
+#endif // __INCLUDE_CKEYBOARD_HXX
diff --git a/NxWidgets/nxwm/include/ctaskbar.hxx b/NxWidgets/nxwm/include/ctaskbar.hxx
index 2578a3ce9..5aab9e6bf 100644
--- a/NxWidgets/nxwm/include/ctaskbar.hxx
+++ b/NxWidgets/nxwm/include/ctaskbar.hxx
@@ -184,7 +184,15 @@ namespace NxWM
* @return true on success
*/
- bool redrawTopWindow(void);
+ bool redrawTopApplication(void);
+
+ /**
+ * Raise the top window to the top of the NXheirarchy.
+ *
+ * @return true on success
+ */
+
+ void raiseTopApplication(void);
/**
* (Re-)draw the background window.
diff --git a/NxWidgets/nxwm/include/nxwmconfig.hxx b/NxWidgets/nxwm/include/nxwmconfig.hxx
index 25a8beb66..8a7700af4 100644
--- a/NxWidgets/nxwm/include/nxwmconfig.hxx
+++ b/NxWidgets/nxwm/include/nxwmconfig.hxx
@@ -65,6 +65,7 @@
* CONFIG_NXWM_DEFAULT_FONTID - the NxWM default font ID. Default:
* NXFONT_DEFAULT
* CONFIG_NXWM_TOUCHSCREEN - Define to build in touchscreen support.
+ * CONFIG_NXWM_KEYBOARD - Define to build in touchscreen support.
*/
#ifndef CONFIG_HAVE_CXX
@@ -386,7 +387,7 @@
*
* CONFIG_NXWM_TOUCHSCREEN_DEVNO - Touchscreen device minor number, i.e., the
* N in /dev/inputN. Default: 0
- * CONFIG_NXWM_TOUCHSCREEN_DEVNO - The full path to the touchscreen device.
+ * CONFIG_NXWM_TOUCHSCREEN_DEVPATH - The full path to the touchscreen device.
* Default: "/dev/input0"
* CONFIG_NXWM_TOUCHSCREEN_SIGNO - The realtime signal used to wake up the
* touchscreen listener thread. Default: 5
@@ -416,6 +417,42 @@
# define CONFIG_NXWM_TOUCHSCREEN_LISTENERSTACK 1024
#endif
+/* Keyboard device **********************************************************/
+/**
+ * Keyboard device settings
+ *
+ * CONFIG_NXWM_KEYBOARD_DEVNO - The full path to the touchscreen device.
+ * Default: "/dev/console"
+ * CONFIG_NXWM_KEYBOARD_SIGNO - The realtime signal used to wake up the
+ * touchscreen listener thread. Default: 6
+ * CONFIG_NXWM_KEYBOARD_BUFSIZE - The size of the keyboard read data buffer.
+ * Default: 16
+ * CONFIG_NXWM_KEYBOARD_LISTENERPRIO - Priority of the touchscreen listener
+ * thread. Default: SCHED_PRIORITY_DEFAULT
+ * CONFIG_NXWM_KEYBOARD_LISTENERSTACK - Keyboard listener thread stack
+ * size. Default 1024
+ */
+
+#ifndef CONFIG_NXWM_KEYBOARD_DEVPATH
+# define CONFIG_NXWM_KEYBOARD_DEVPATH "/dev/console"
+#endif
+
+#ifndef CONFIG_NXWM_KEYBOARD_SIGNO
+# define CONFIG_NXWM_KEYBOARD_SIGNO 6
+#endif
+
+#ifndef CONFIG_NXWM_KEYBOARD_BUFSIZE
+# define CONFIG_NXWM_KEYBOARD_BUFSIZE 6
+#endif
+
+#ifndef CONFIG_NXWM_KEYBOARD_LISTENERPRIO
+# define CONFIG_NXWM_KEYBOARD_LISTENERPRIO SCHED_PRIORITY_DEFAULT
+#endif
+
+#ifndef CONFIG_NXWM_KEYBOARD_LISTENERSTACK
+# define CONFIG_NXWM_KEYBOARD_LISTENERSTACK 1024
+#endif
+
/* Calibration display ******************************************************/
/**
* Calibration display settings:
diff --git a/NxWidgets/nxwm/src/ckeyboard.cxx b/NxWidgets/nxwm/src/ckeyboard.cxx
new file mode 100644
index 000000000..6e9d7b818
--- /dev/null
+++ b/NxWidgets/nxwm/src/ckeyboard.cxx
@@ -0,0 +1,245 @@
+/********************************************************************************************
+ * NxWidgets/nxwm/src/ckeyboard.cxx
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX, NxWidgets, nor the names of its contributors
+ * me be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+#include <nuttx/config.h> // REMOVE ME
+#define CONFIG_DEBUG 1 // REMOVE ME
+#define CONFIG_DEBUG_VERBOSE 1 // REMOVE ME
+#define CONFIG_DEBUG_GRAPHICS 1 // REMOVE ME
+#include <debug.h> // REMOVE ME
+
+#include <nuttx/config.h>
+
+#include <cunistd>
+#include <cerrno>
+#include <cfcntl>
+
+#include <sched.h>
+#include <pthread.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "nxwmconfig.hxx"
+#include "ckeyboard.hxx"
+
+/********************************************************************************************
+ * Pre-Processor Definitions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * CKeyboard Method Implementations
+ ********************************************************************************************/
+
+using namespace NxWM;
+
+/**
+ * CKeyboard Constructor
+ *
+ * @param server. An instance of the NX server. This will be needed for
+ * injecting mouse data.
+ */
+
+CKeyboard::CKeyboard(NXWidgets::CNxServer *server)
+{
+ m_server = server; // Save the NX server
+ m_kbdFd = -1; // Device driver is not opened
+ m_state = LISTENER_NOTRUNNING; // The listener thread is not running yet
+
+ // Initialize the semaphore used to synchronize with the listener thread
+
+ sem_init(&m_waitSem, 0, 0);
+}
+
+/**
+ * CKeyboard Destructor
+ */
+
+CKeyboard::~CKeyboard(void)
+{
+ // Stop the listener thread
+
+ m_state = LISTENER_STOPREQUESTED;
+
+ // Wake up the listener thread so that it will use our buffer
+ // to receive data
+ // REVISIT: Need wait here for the listener thread to terminate
+
+ (void)pthread_kill(m_thread, CONFIG_NXWM_KEYBOARD_SIGNO);
+
+ // Close the keyboard device (or should these be done when the thread exits?)
+
+ if (m_kbdFd >= 0)
+ {
+ std::close(m_kbdFd);
+ }
+}
+
+/**
+ * Start the keyboard listener thread.
+ *
+ * @return True if the keyboard listener thread was correctly started.
+ */
+
+bool CKeyboard::start(void)
+{
+ pthread_attr_t attr;
+
+ gvdbg("Starting listener\n");
+
+ // Start a separate thread to listen for keyboard events
+
+ (void)pthread_attr_init(&attr);
+
+ struct sched_param param;
+ param.sched_priority = CONFIG_NXWM_KEYBOARD_LISTENERPRIO;
+ (void)pthread_attr_setschedparam(&attr, &param);
+
+ (void)pthread_attr_setstacksize(&attr, CONFIG_NXWM_KEYBOARD_LISTENERSTACK);
+
+ m_state = LISTENER_STARTED; // The listener thread has been started, but is not yet running
+
+ int ret = pthread_create(&m_thread, &attr, listener, (FAR void *)this);
+ if (ret != 0)
+ {
+ gdbg("CKeyboard::start: pthread_create failed: %d\n", ret);
+ return false;
+ }
+
+ // Detach from the thread
+
+ (void)pthread_detach(m_thread);
+
+ // Don't return until we are sure that the listener thread is running
+ // (or until it reports an error).
+
+ while (m_state == LISTENER_STARTED)
+ {
+ // Wait for the listener thread to wake us up when we really
+ // are connected.
+
+ (void)sem_wait(&m_waitSem);
+ }
+
+ // Then return true only if the listener thread reported successful
+ // initialization.
+
+ gvdbg("Listener m_state=%d\n", (int)m_state);
+ return m_state == LISTENER_RUNNING;
+}
+
+ /**
+ * The keyboard listener thread. This is the entry point of a thread that
+ * listeners for and dispatches keyboard events to the NX server.
+ *
+ * @param arg. The CKeyboard 'this' pointer cast to a void*.
+ * @return This function normally does not return but may return NULL on
+ * error conditions.
+ */
+
+FAR void *CKeyboard::listener(FAR void *arg)
+{
+ CKeyboard *This = (CKeyboard *)arg;
+
+ gvdbg("Listener started\n");
+
+ // Open the keyboard device
+
+ This->m_kbdFd = std::open(CONFIG_NXWM_KEYBOARD_DEVPATH, O_RDONLY);
+ if (This->m_kbdFd < 0)
+ {
+ gdbg("ERROR Failed to open %s for reading: %d\n",
+ CONFIG_NXWM_KEYBOARD_DEVPATH, errno);
+ This->m_state = LISTENER_FAILED;
+ sem_post(&This->m_waitSem);
+ return (FAR void *)0;
+ }
+
+ // Indicate that we have successfully initialized
+
+ This->m_state = LISTENER_RUNNING;
+ sem_post(&This->m_waitSem);
+
+ // Now loop, reading and dispatching keyboard data
+
+ while (This->m_state == LISTENER_RUNNING)
+ {
+ // Read one keyboard sample
+
+ gvdbg("Listening for keyboard input\n");
+
+ uint8_t rxbuffer[CONFIG_NXWM_KEYBOARD_BUFSIZE];
+ ssize_t nbytes = read(This->m_kbdFd, rxbuffer, CONFIG_NXWM_KEYBOARD_BUFSIZE);
+dbg("nbytes=%d\n"); // REMOVE ME
+ // Check for errors
+
+ if (nbytes < 0)
+ {
+ // The only expect error is to be interrupt by a signal
+#ifdef CONFIG_DEBUG
+ int errval = errno;
+
+ gdbg("ERROR: read %s failed: %d\n", CONFIG_NXWM_KEYBOARD_DEVPATH, errval);
+ DEBUGASSERT(errval == EINTR);
+#endif
+ }
+
+ // Give the keyboard input to NX
+
+ else if (nbytes > 0)
+ {
+ // Looks like good keyboard input... process it.
+ // First, get the server handle
+
+ NXHANDLE handle = This->m_server->getServer();
+
+ // Then inject the keyboard input into NX
+
+ int ret = nx_kbdin(handle, (uint8_t)nbytes, rxbuffer);
+ if (ret < 0)
+ {
+ gdbg("ERROR: nx_kbdin failed\n");
+ }
+ }
+ }
+
+ // We should get here only if we were asked to terminate via
+ // m_state = LISTENER_STOPREQUESTED
+
+ gvdbg("Listener exiting\n");
+ This->m_state = LISTENER_TERMINATED;
+ return (FAR void *)0;
+}
diff --git a/NxWidgets/nxwm/src/ctaskbar.cxx b/NxWidgets/nxwm/src/ctaskbar.cxx
index 2130293c2..111d800e9 100644
--- a/NxWidgets/nxwm/src/ctaskbar.cxx
+++ b/NxWidgets/nxwm/src/ctaskbar.cxx
@@ -610,7 +610,7 @@ bool CTaskbar::minimizeApplication(IApplication *app)
// Re-draw the new top, non-minimized application
- return redrawTopWindow();
+ return redrawTopApplication();
}
return false;
@@ -672,7 +672,7 @@ bool CTaskbar::stopApplication(IApplication *app)
// Re-draw the new top, non-minimized application
- bool ret = redrawTopWindow();
+ bool ret = redrawTopApplication();
if (ret)
{
// And redraw the task bar (without the icon for this task)
@@ -1184,6 +1184,11 @@ bool CTaskbar::redrawTaskbarWindow(void)
}
#endif
}
+
+ // If there is a top application then we must now raise it above the task
+ // bar so that itwill get the keyboard input.
+
+ raiseTopApplication();
}
// Return success (it is not a failure if the window manager is not started
@@ -1198,7 +1203,7 @@ bool CTaskbar::redrawTaskbarWindow(void)
* @return true on success
*/
-bool CTaskbar::redrawTopWindow(void)
+bool CTaskbar::redrawTopApplication(void)
{
// Check if there is already a top application
@@ -1237,6 +1242,30 @@ bool CTaskbar::redrawTopWindow(void)
}
/**
+ * Raise the top window to the top of the NXheirarchy.
+ *
+ * @return true on success
+ */
+
+void CTaskbar::raiseTopApplication(void)
+{
+ if (m_topApp)
+ {
+ // Every application provides a method to obtain its application window
+
+ IApplicationWindow *appWindow = m_topApp->getWindow();
+
+ // Each application window provides a method to get the underlying NX window
+
+ NXWidgets::INxWindow *window = appWindow->getWindow();
+
+ // Raise the application window to the top of the hierarchy
+
+ window->raise();
+ }
+}
+
+/**
* (Re-)draw the background window.
*
* @return true on success
@@ -1301,17 +1330,13 @@ bool CTaskbar::redrawApplicationWindow(IApplication *app)
m_backImage->disableDrawing();
- // Every application provides a method to obtain its application window
+ // Raise to top application to the top of the NX window heirarchy
- IApplicationWindow *appWindow = app->getWindow();
-
- // Each application window provides a method to get the underlying NX window
-
- NXWidgets::INxWindow *window = appWindow->getWindow();
+ raiseTopApplication();
- // Raise the application window to the top of the hierarchy
+ // Every application provides a method to obtain its application window
- window->raise();
+ IApplicationWindow *appWindow = app->getWindow();
// Re-draw the application window toolbar
@@ -1333,7 +1358,7 @@ bool CTaskbar::redrawApplicationWindow(IApplication *app)
void CTaskbar::hideApplicationWindow(IApplication *app)
{
// The hidden window is certainly not the top application any longer
- // If it was before then redrawTopWindow() will pick a new one (rather
+ // If it was before then redrawTopApplication() will pick a new one (rather
// arbitrarily).
if (app->isTopApplication())