From 4a93240e48b34ea69e612f549520cb498aeeea89 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 28 Nov 2008 14:42:52 +0000 Subject: Multi-user graphics front-end git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1325 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/graphics/nxmu/Make.defs | 43 +++ nuttx/graphics/nxmu/nx_bitmap.c | 137 ++++++++ nuttx/graphics/nxmu/nx_closewindow.c | 107 +++++++ nuttx/graphics/nxmu/nx_connect.c | 220 +++++++++++++ nuttx/graphics/nxmu/nx_disconnect.c | 109 +++++++ nuttx/graphics/nxmu/nx_eventhandler.c | 224 +++++++++++++ nuttx/graphics/nxmu/nx_fill.c | 127 ++++++++ nuttx/graphics/nxmu/nx_filltrapezoid.c | 128 ++++++++ nuttx/graphics/nxmu/nx_getposition.c | 123 +++++++ nuttx/graphics/nxmu/nx_kbdchin.c | 105 ++++++ nuttx/graphics/nxmu/nx_kbdin.c | 125 ++++++++ nuttx/graphics/nxmu/nx_lower.c | 105 ++++++ nuttx/graphics/nxmu/nx_mousein.c | 106 ++++++ nuttx/graphics/nxmu/nx_move.c | 121 +++++++ nuttx/graphics/nxmu/nx_openwindow.c | 127 ++++++++ nuttx/graphics/nxmu/nx_raise.c | 105 ++++++ nuttx/graphics/nxmu/nx_setbgcolor.c | 121 +++++++ nuttx/graphics/nxmu/nx_setposition.c | 117 +++++++ nuttx/graphics/nxmu/nx_setsize.c | 116 +++++++ nuttx/graphics/nxmu/nxfe.h | 514 ++++++++++++++++++++++++++++++ nuttx/graphics/nxmu/nxmu_kbdin.c | 122 +++++++ nuttx/graphics/nxmu/nxmu_mouse.c | 178 +++++++++++ nuttx/graphics/nxmu/nxmu_openwindow.c | 113 +++++++ nuttx/graphics/nxmu/nxmu_redrawreq.c | 98 ++++++ nuttx/graphics/nxmu/nxmu_reportposition.c | 104 ++++++ nuttx/graphics/nxmu/nxmu_semtake.c | 88 +++++ nuttx/graphics/nxmu/nxmu_server.c | 499 +++++++++++++++++++++++++++++ 27 files changed, 4082 insertions(+) create mode 100644 nuttx/graphics/nxmu/Make.defs create mode 100644 nuttx/graphics/nxmu/nx_bitmap.c create mode 100644 nuttx/graphics/nxmu/nx_closewindow.c create mode 100644 nuttx/graphics/nxmu/nx_connect.c create mode 100644 nuttx/graphics/nxmu/nx_disconnect.c create mode 100644 nuttx/graphics/nxmu/nx_eventhandler.c create mode 100644 nuttx/graphics/nxmu/nx_fill.c create mode 100644 nuttx/graphics/nxmu/nx_filltrapezoid.c create mode 100644 nuttx/graphics/nxmu/nx_getposition.c create mode 100644 nuttx/graphics/nxmu/nx_kbdchin.c create mode 100644 nuttx/graphics/nxmu/nx_kbdin.c create mode 100644 nuttx/graphics/nxmu/nx_lower.c create mode 100644 nuttx/graphics/nxmu/nx_mousein.c create mode 100644 nuttx/graphics/nxmu/nx_move.c create mode 100644 nuttx/graphics/nxmu/nx_openwindow.c create mode 100644 nuttx/graphics/nxmu/nx_raise.c create mode 100644 nuttx/graphics/nxmu/nx_setbgcolor.c create mode 100644 nuttx/graphics/nxmu/nx_setposition.c create mode 100644 nuttx/graphics/nxmu/nx_setsize.c create mode 100644 nuttx/graphics/nxmu/nxfe.h create mode 100644 nuttx/graphics/nxmu/nxmu_kbdin.c create mode 100644 nuttx/graphics/nxmu/nxmu_mouse.c create mode 100644 nuttx/graphics/nxmu/nxmu_openwindow.c create mode 100644 nuttx/graphics/nxmu/nxmu_redrawreq.c create mode 100644 nuttx/graphics/nxmu/nxmu_reportposition.c create mode 100644 nuttx/graphics/nxmu/nxmu_semtake.c create mode 100644 nuttx/graphics/nxmu/nxmu_server.c (limited to 'nuttx/graphics/nxmu') diff --git a/nuttx/graphics/nxmu/Make.defs b/nuttx/graphics/nxmu/Make.defs new file mode 100644 index 000000000..0fb5e2c70 --- /dev/null +++ b/nuttx/graphics/nxmu/Make.defs @@ -0,0 +1,43 @@ +############################################################################ +# graphics/nxmu/Make.defs +# +# Copyright (C) 2008 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. +# +############################################################################ + +NX_ASRCS = +NXAPI_CSRCS = nx_bitmap.c nx_connect.c nx_disconnect.c nx_eventhandler.c \ + nx_fill.c nx_filltrapezoid.c nx_getposition.c nx_kbdchin.c \ + nx_kbdin.c nx_lower.c nx_mousein.c nx_move.c nx_openwindow.c \ + nx_raise.c nx_setsize.c nx_setbgcolor.c nx_setposition.c +NXMU_CSRCS = nxmu_server.c nxmu_openwindow.c nxmu_reportposition.c nxmu_kbdin.c \ + nxmu_mouse.c nxmu_redrawreq.c nxmu_semtake.c +NX_CSRCS = $(NXAPI_CSRCS) $(NXMU_CSRCS) diff --git a/nuttx/graphics/nxmu/nx_bitmap.c b/nuttx/graphics/nxmu/nx_bitmap.c new file mode 100644 index 000000000..43dc6acde --- /dev/null +++ b/nuttx/graphics/nxmu/nx_bitmap.c @@ -0,0 +1,137 @@ +/**************************************************************************** + * graphics/nxmu/nx_bitmap.c + * + * Copyright (C) 2008 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 "nxbe.h" +#include "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_bitmap + * + * Description: + * Copy a rectangular region of a larger image into the rectangle in the + * specified window. + * + * Input Parameters: + * hwnd - The window that will receive the bitmap image + * dest - Describes the rectangular region on the display that will receive the + * the bit map. + * src - The start of the source image. + * origin - The origin of the upper, left-most corner of the full bitmap. + * Both dest and origin are in window coordinates, however, origin + * may lie outside of the display. + * stride - The width of the full source image in pixels. + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_bitmap(NXWINDOW hwnd, FAR const struct nxgl_rect_s *dest, + FAR const void *src[CONFIG_NX_NPLANES], + FAR const struct nxgl_point_s *origin, unsigned int stride) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_bitmap_s outmsg; + int ret; + int i; + +#ifdef CONFIG_DEBUG + if (!wnd || !wnd->conn || !dest || !src || !origin) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Format the bitmap command */ + + outmsg.msgid = NX_SVRMSG_BITMAP; + outmsg.wnd = wnd; + outmsg.stride = stride; + + for (i = 0; i < CONFIG_NX_NPLANES; i++) + { + outmsg.src[i] = src[i]; + } + + outmsg.origin.x = origin->x; + outmsg.origin.y = origin->y; + nxgl_rectcopy(&outmsg.dest, dest); + + /* Forward the fill command to the server */ + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_bitmap_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} diff --git a/nuttx/graphics/nxmu/nx_closewindow.c b/nuttx/graphics/nxmu/nx_closewindow.c new file mode 100644 index 000000000..0eab0170c --- /dev/null +++ b/nuttx/graphics/nxmu/nx_closewindow.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * graphics/nxmu/nx_closewindow.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + + +/**************************************************************************** + * Name: nx_closewindow + * + * Description: + * Destroy a window created by nx_openwindow. + * + * Input Parameters: + * wnd - The window to be destroyed + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_closewindow(NXWINDOW hwnd) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_closewindow_s outmsg; + int ret; + + /* Request destruction of the window by the serer */ + + outmsg.msgid = NX_SVRMSG_CLOSEWINDOW; + outmsg.wnd = wnd; + + ret = mq_send(conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_closewindow_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} + diff --git a/nuttx/graphics/nxmu/nx_connect.c b/nuttx/graphics/nxmu/nx_connect.c new file mode 100644 index 000000000..9e29f736b --- /dev/null +++ b/nuttx/graphics/nxmu/nx_connect.c @@ -0,0 +1,220 @@ +/**************************************************************************** + * graphics/nxmu/nx_connect.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Each client is assigned a unique ID using the g_nxcid counter. That + * counter increments as each new counter is created and is* protected for + * thread safefy with g_nxlibsem. Note that these are the only global values + * in the NX implementation. This is because the client ID must be unique + * even across all server instances. + * + * NOTE: that client ID 0 is reserved for the server(s) themselves + */ + +static sem_t g_nxlibsem = { 1 }; +static uint32 g_nxcid = 1; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_connectinstance + * + * Description: + * Open a connection from a client to the NX server. One one client + * connection is normally needed per thread as each connection can host + * multiple windows. + * + * NOTE that multiple instances of the NX server may run at the same time, + * each with different message queue names. + * + * Input Parameters: + * svrmqname - The name for the server incoming message queue + * cb - Callbacks used to process received NX server messages + * + * Return: + * Success: A non-NULL handle used with subsequent NX accesses + * Failure: NULL is returned and errno is set appropriately + * + ****************************************************************************/ + +NXHANDLE nx_connectionstance(FAR const char *svrmqname, + FAR const struct nx_callback_s *cb) +{ + FAR struct nxfe_conn_s *conn; + struct nxsvrmsg_s msg; + char climqname[NX_CLIENT_MXNAMELEN]; + struct mq_attr attr; + int ret; + + /* Sanity checking */ + +#ifdef CONFIG_DEBUG + if (!svrmqname || !cb) + { + errno = EINVAL; + return NULL; + } +#endif + + /* Allocate the NX client structure */ + + conn = (FAR struct nxfe_conn_s *)zalloc(sizeof(struct nxfe_conn_s)); + if (!conn) + { + errno = ENOMEM; + goto errout; + } + + /* Save the callback vtable */ + + conn->cb = cb; + + /* Create the client MQ name */ + + nxmu_semtake(&g_nxlibsem); + conn->cid = g_nxcid++; + nxmu_semgive(&g_nxlibsem); + + sprintf(climqname, NX_CLIENT_MQNAMEFMT, conn->cid); + + /* Open the client MQ for reading */ + + attr.mq_maxmsg = CONFIG_NX_MXCLIENTMSGS; + attr.mq_msgsize = NX_MXCLIMSGLEN; + attr.mq_flags = 0; + +#ifdef CONFIG_NX_BLOCKING + conn->crdmq = mq_open(climqname, O_RDONLY|O_CREAT, 0666, &attr); +#else + conn->crdmq = mq_open(climqname, O_RDONLY|O_CREAT|O_NONBLOCK, 0666, &attr); +#endif + if (conn->crdmq) + { + gdbg("mq_open(%s) failed: %d\n", climqname, errno); + goto errout_with_conn; + } + + /* Open the server MQ for writing */ + + attr.mq_maxmsg = CONFIG_NX_MXSERVERMSGS; + attr.mq_msgsize = NX_MXSVRMSGLEN; + attr.mq_flags = 0; + + conn->cwrmq = mq_open(svrmqname, O_WRONLY|O_CREAT, 0666, &attr); + if (conn->cwrmq) + { + gdbg("mq_open(%s) failed: %d\n", svrmqname, errno); + goto errout_with_rmq; + } + + /* Inform the server that this client exists */ + + msg.msgid = NX_SVRMSG_CONNECT; + msg.conn = conn; + + ret = mq_send(conn->cwrmq, &msg, sizeof(struct nxsvrmsg_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + goto errout_with_wmq; + } + + /* Now read until we get a response to this message. The server will + * respond with either (1) NX_CLIMSG_CONNECTED, in which case the state + * will change to NX_CLISTATE_CONNECTED, or (2) NX_CLIMSG_DISCONNECTED + * in which case, nx_message will fail with errno = EHOSTDOWN. + */ + + do + { + ret = nx_eventhandler((NXHANDLE)conn); + if (ret < 0) + { + gdbg("nx_message failed: %d\n", errno); + goto errout_with_wmq; + } + } + while (conn->state != NX_CLISTATE_CONNECTED); + + return (NXHANDLE)conn; + +errout_with_wmq: + mq_close(conn->cwrmq); +errout_with_rmq: + mq_close(conn->crdmq); +errout_with_conn: + free(conn); +errout: + return NULL; +} + diff --git a/nuttx/graphics/nxmu/nx_disconnect.c b/nuttx/graphics/nxmu/nx_disconnect.c new file mode 100644 index 000000000..efce1279a --- /dev/null +++ b/nuttx/graphics/nxmu/nx_disconnect.c @@ -0,0 +1,109 @@ +/**************************************************************************** + * graphics/nxmu/nx_disconnect.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_disconnect + * + * Description: + * Disconnect a client from the NX server and/or free resources reserved + * by nx_connect/nx_connectinstance. + * + * Input Parameters: + * handle - the handle returned by nx_connect + * + * Return: + * OK on success; ERROR on failure with the errno set appropriately. + * NOTE that handle will no long be valid upon return. + * + ****************************************************************************/ + +void nx_disconnect(NXHANDLE handle) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + struct nxsvrmsg_s msg; + int ret; + + /* Inform the server that this client no longer exists */ + + msg.msgid = NX_SVRMSG_CONNECT; + msg.conn = conn; + + ret = mq_send(conn->cwrmq, &msg, sizeof(struct nxsvrmsg_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + + /* We will finish the teardown upon receipt of the DISCONNECTED message */ +} + diff --git a/nuttx/graphics/nxmu/nx_eventhandler.c b/nuttx/graphics/nxmu/nx_eventhandler.c new file mode 100644 index 000000000..f89565b01 --- /dev/null +++ b/nuttx/graphics/nxmu/nx_eventhandler.c @@ -0,0 +1,224 @@ +/**************************************************************************** + * graphics/nxmu/nx_eventhandler.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_connected + * + * Description: + * The server has completed the connection and is ready. + * + ****************************************************************************/ + +static inline void nx_connected(FAR struct nxfe_conn_s *conn) +{ + DEBUGASSERT(conn->state == NX_CLISTATE_NOTCONNECTED); + conn->state = NX_CLISTATE_CONNECTED; +} + +/**************************************************************************** + * Name: nx_disconnected + ****************************************************************************/ + +static inline void nx_disconnected(FAR struct nxfe_conn_s *conn) +{ + /* Close the server and client MQs */ + + (void)mq_close(conn->cwrmq); + (void)mq_close(conn->crdmq); + + /* And free the client structure */ + + free(conn); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_eventhandler + * + * Description: + * The client code must call this function periodically to process + * incoming messages from the server. + * + * Input Parameters: + * handle - the handle returned by nx_connect + * + * Return: + * >0: The length of the message received in msgbuffer + * 0: No message was received + * <0: An error occurred and errno has been set appropriately + * + * Of particular interest, it will return errno == EHOSTDOWN when the + * server is disconnected. After that event, the handle can not longer + * be used. + * + ****************************************************************************/ + +int nx_eventhandler(NXHANDLE handle) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + struct nxsvrmsg_s *msg; + ubyte buffer[NX_MXCLIMSGLEN]; + int nbytes; + + /* Get the next message from our incoming message queue */ + + do + { + nbytes = mq_receive(conn->crdmq, buffer, NX_MXCLIMSGLEN, 0); + if (nbytes < 0) + { + /* EINTR is not an error. The wait was interrupted by a signal and + * we just need to try reading again. + */ + + if (errno != EINTR) + { + if (errno == EAGAIN) + { + /* EAGAIN is not an error. It occurs because the MQ is opened with + * O_NONBLOCK and there is no message available now. + */ + + return OK; + } + else + { + gdbg("mq_receive failed: %d\n", errno); + return ERROR; + } + } + } + } + while (nbytes < 0); + + DEBUGASSERT(nbytes >= sizeof(struct nxclimsg_s)); + + /* Dispatch the message appropriately */ + + msg = (struct nxsvrmsg_s *)buffer; + switch (msg->msgid) + { + case NX_SVRMSG_CONNECT: + nx_connected(conn); + break; + + case NX_SVRMSG_DISCONNECT: + nx_disconnected(conn); + errno = EHOSTDOWN; + return ERROR; + + case NX_CLIMSG_REDRAW: + if (conn->cb->redraw) + { + FAR struct nxclimsg_redraw_s *redraw = (FAR struct nxclimsg_redraw_s *)buffer; + conn->cb->redraw((NXWINDOW)redraw->wnd, &redraw->rect, redraw->more); + } + break; + + case NX_CLIMSG_NEWPOSITION: + if (conn->cb->position) + { + FAR struct nxclimsg_newposition_s *postn = (FAR struct nxclimsg_newposition_s *)buffer; + conn->cb->position((NXWINDOW)postn->wnd, &postn->size, &postn->pos); + } + break; + +#ifdef CONFIG_NX_KBD + case NX_CLIMSG_MOUSEIN: + if (conn->cb->mousein) + { + FAR struct nxclimsg_mousein_s *mouse = (FAR struct nxclimsg_mousein_s *)buffer; + conn->cb->mousein((NXWINDOW)mouse->wnd, &mouse->pos, mouse->buttons); + } + break; +#endif + +#ifdef CONFIG_NX_KBD + case NX_CLIMSG_KBDIN: + if (conn->cb->kbdin) + { + FAR struct nxclimsg_kbdin_s *kbd = (FAR struct nxclimsg_kbdin_s *)buffer; + conn->cb->kbdin((NXWINDOW)kbd->wnd, kbd->nch, kbd->ch); + } + break; +#endif + + default: + gdbg("Unrecogized message opcode: %d\n", (FAR struct nxsvrmsg_s *)buffer->msgid); + break; + } + + return OK; +} + diff --git a/nuttx/graphics/nxmu/nx_fill.c b/nuttx/graphics/nxmu/nx_fill.c new file mode 100644 index 000000000..79a71ce8b --- /dev/null +++ b/nuttx/graphics/nxmu/nx_fill.c @@ -0,0 +1,127 @@ +/**************************************************************************** + * graphics/nxmu/nx_fill.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_fill + * + * Description: + * Fill the specified rectangle in the window with the specified color + * + * Input Parameters: + * hwnd - The window handle + * rect - The location to be filled + * color - The color to use in the fill + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_fill(NXWINDOW hwnd, FAR struct nxgl_rect_s *rect, + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_fill_s outmsg; + int ret; + int i; + +#ifdef CONFIG_DEBUG + if (!wnd || !wnd->conn || !rect || !color) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Format the fill command */ + + outmsg.msgid = NX_SVRMSG_FILL; + outmsg.wnd = wnd; + + nxgl_rectcopy(&outmsg.rect, rect); + + for (i = 0; i < CONFIG_NX_NPLANES; i++) + { + outmsg.color[i] = color[i]; + } + + /* Forward the fill command to the server */ + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_fill_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} diff --git a/nuttx/graphics/nxmu/nx_filltrapezoid.c b/nuttx/graphics/nxmu/nx_filltrapezoid.c new file mode 100644 index 000000000..415305e7e --- /dev/null +++ b/nuttx/graphics/nxmu/nx_filltrapezoid.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * graphics/nxmu/nx_filltrapezoid.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_filltrapezoid + * + * Description: + * Fill the specified trapezoidal region in the window with the specified color + * + * Input Parameters: + * hwnd - The window handle + * trap - The trapezoidal region to be filled + * color - The color to use in the fill + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_filltrapezoid(NXWINDOW hwnd, FAR struct nxgl_trapezoid_s *trap, + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_filltrapezoid_s outmsg; + int ret; + int i; + +#ifdef CONFIG_DEBUG + if (!wnd || !wnd->conn || !trap || !color) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Format the fill command */ + + outmsg.msgid = NX_SVRMSG_FILLTRAP; + outmsg.wnd = wnd; + + nxgl_trapcopy(&outmsg.trap, trap); + + for (i = 0; i < CONFIG_NX_NPLANES; i++) + { + outmsg.color[i] = color[i]; + } + + /* Forward the fill command to the server */ + + ret = mq_send(wnd->conn->cwrmq, &outmsg, + sizeof(struct nxsvrmsg_filltrapezoid_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} diff --git a/nuttx/graphics/nxmu/nx_getposition.c b/nuttx/graphics/nxmu/nx_getposition.c new file mode 100644 index 000000000..21bb985aa --- /dev/null +++ b/nuttx/graphics/nxmu/nx_getposition.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * graphics/nxmu/nx_getposition.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_getposition + * + * Description: + * Request the position and size information for the selected window. The + * values will be return asynchronously through the client callback function + * pointer. + * + * Input Parameters: + * hwnd - The window handle + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_getposition(NXWINDOW hwnd) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_getposition_s outmsg; + int ret; + +#ifdef CONFIG_DEBUG + if (!wnd) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Request the size/position info. + * + * It is tempting to just take the positional information from the window + * structure that we have in our hands now. However, we need to run this through + * the server to keep things serialized. There might, for example, be a pending + * size/position change and, in that case, this function would return the + * wrong info. + */ + + outmsg.msgid = NX_SVRMSG_GETPOSITION; + outmsg.wnd = wnd; + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_getposition_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + return ERROR; + } + + return OK; +} diff --git a/nuttx/graphics/nxmu/nx_kbdchin.c b/nuttx/graphics/nxmu/nx_kbdchin.c new file mode 100644 index 000000000..4f16c1d28 --- /dev/null +++ b/nuttx/graphics/nxmu/nx_kbdchin.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * graphics/nxmu/nx_kbdchin.c + * + * Copyright (C) 2008 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 "nxfe.h" + +#ifdef CONFIG_NX_KBD + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_kbdchin + * + * Description: + * Used by a thread or interrupt handler that manages some kind of keypad + * hardware to report text information to the NX server. That text + * data will be routed by the NX server to the appropriate window client. + * + ****************************************************************************/ + +int nx_kbdchin(NXHANDLE handle, ubyte ch) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + struct nxsvrmsg_kbdin_s outmsg; + int ret; + + /* Inform the server of the new keypad data */ + + outmsg.msgid = NX_SVRMSG_KBDIN; + outmsg.nch = 1; + outmsg.ch[0] = ch; + + ret = mq_send(conn->c_cwrmq, &outmsg, sizeof(struct nxsvrmsg_kbdin_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} + +#endif /* CONFIG_NX_KBD */ diff --git a/nuttx/graphics/nxmu/nx_kbdin.c b/nuttx/graphics/nxmu/nx_kbdin.c new file mode 100644 index 000000000..46229a94e --- /dev/null +++ b/nuttx/graphics/nxmu/nx_kbdin.c @@ -0,0 +1,125 @@ +/**************************************************************************** + * graphics/nxmu/nx_kbdin.c + * + * Copyright (C) 2008 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 "nxfe.h" + +#ifdef CONFIG_NX_KBD + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_kbdin + * + * Description: + * Used by a thread or interrupt handler that manages some kind of keypad + * hardware to report text information to the NX server. That text + * data will be routed by the NX server to the appropriate window client. + * + ****************************************************************************/ + +int int nx_kbdin(NXHANDLE handle, ubyte nch const char *ch) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + FAR struct nxsvrmsg_kbdin_s *outmsg; + int size; + int ret; + int i; + + /* Allocate a bigger message to account for the variable amount of character + * data. + */ + + size = sizeof(struct nxsvrmsg_kbdin_s) + nch - 1; + outmsg = (FAR struct nxsvrmsg_kbdin_s *)malloc(size); + if (!outmsg) + { + errno = ENOMEM; + return ERROR; + } + + /* Inform the server of the new keypad data */ + + outsg->msgid = NX_SVRMSG_KBDIN; + outmsg->nch = nch; + + for (i = 0; i < nch; i+) + { + outmsg->ch[i] = ch[i]; + } + + ret = mq_send(conn->c_cwrmq, outmsg, size, NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + + free(outmsg); + return ret; +} + +#endif /* CONFIG_NX_KBD */ diff --git a/nuttx/graphics/nxmu/nx_lower.c b/nuttx/graphics/nxmu/nx_lower.c new file mode 100644 index 000000000..d5156cf80 --- /dev/null +++ b/nuttx/graphics/nxmu/nx_lower.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * graphics/nxmu/nx_lower.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_raise + * + * Description: + * Lower the specified window to the bottom of the display. + * + * Input parameters: + * hwnd - the window to be lowered + * + * Returned value: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_lower(NXWINDOW hwnd) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_lower_s outmsg; + int ret; + + /* Send the RAISE message */ + + outmsg.msgid = NX_SVRMSG_LOWER; + outmsg.wnd = wnd; + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_lower_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} + diff --git a/nuttx/graphics/nxmu/nx_mousein.c b/nuttx/graphics/nxmu/nx_mousein.c new file mode 100644 index 000000000..7bd33c4a4 --- /dev/null +++ b/nuttx/graphics/nxmu/nx_mousein.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * graphics/nxmu/nx_mousein.c + * + * Copyright (C) 2008 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 "nxfe.h" + +#ifdef CONFIG_NX_MOUSE + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_mousein + * + * Description: + * Used by a thread or interrupt handler that manages some kind of pointing + * hardware to report new positional data to the NX server. That positional + * data will be routed by the NX server to the appropriate window client. + * + ****************************************************************************/ + +int nx_mousein(NXHANDLE handle, nxgl_coord_t x, nxgl_coord_t y, ubyte buttons) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + struct nxsvrmsg_mousein_s outmsg; + int ret; + + /* Inform the server that this client no longer exists */ + + msg.msgid = NX_SVRMSG_MOUSEIN; + msg.pt.x = x; + msg.pt.y = y; + msg.buttons = buttons; + + ret = mq_send(conn->c_cwrmq, &outmsg, sizeof(struct nxsvrmsg_mousein_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} + +#endif /* CONFIG_NX_MOUSE */ diff --git a/nuttx/graphics/nxmu/nx_move.c b/nuttx/graphics/nxmu/nx_move.c new file mode 100644 index 000000000..084a08d0d --- /dev/null +++ b/nuttx/graphics/nxmu/nx_move.c @@ -0,0 +1,121 @@ +/**************************************************************************** + * graphics/nxmu/nx_move.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_move + * + * Description: + * Move a rectangular region within the window + * + * Input Parameters: + * hwnd - The window within which the move is to be done + * rect - Describes the rectangular region to move + * offset - The offset to move the region + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_move(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect, + FAR const struct nxgl_point_s *offset) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_move_s outmsg; + int ret; + +#ifdef CONFIG_DEBUG + if (!wnd || !wnd->conn) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Format the fill command */ + + outmsg.msgid = NX_SVRMSG_FILL; + outmsg.wnd = wnd; + outmsg.offset.x = offset->x; + outmsg.offset.y = offset->y; + + nxgl_rectcopy(&outmsg.rect, rect); + + /* Forward the fill command to the server */ + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_move_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} diff --git a/nuttx/graphics/nxmu/nx_openwindow.c b/nuttx/graphics/nxmu/nx_openwindow.c new file mode 100644 index 000000000..927f5b8fd --- /dev/null +++ b/nuttx/graphics/nxmu/nx_openwindow.c @@ -0,0 +1,127 @@ +/**************************************************************************** + * graphics/nxmu/nx_openwindow.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_openwindow + * + * Description: + * Create a new window. + * + * Input Parameters: + * handle - The handle returned by nx_connect + * wnd - Location to return the handle of the new window + * + * Return: + * Success: A non-NULL handle used with subsequent NX accesses + * Failure: NULL is returned and errno is set appropriately + * + ****************************************************************************/ + +NXWINDOW nx_openwindow(NXHANDLE handle) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + FAR struct nxbe_window_s *wnd; + struct nxsvrmsg_openwindow_s outmsg; + int ret; + + /* Pre-allocate the window structure */ + + wnd = (FAR struct nxbe_window_s *)zalloc(sizeof(struct nxbe_window_s)); + if (!wnd) + { + errno = ENOMEM; + return NULL; + } + + /* Request initialization the new window from the server */ + + outmsg.msgid = NX_SVRMSG_OPENWINDOW; + outmsg.conn = conn; + outmsg.wnd = wnd; + + ret = mq_send(conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_openwindow_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + free(wnd); + return NULL; + } + + /* Return the uninitialized window reference. Since the server + * serializes all operations, we can be assured that the window will + * be initialized before the first operation on the window. + */ + + return (NXWINDOW)wnd; +} + diff --git a/nuttx/graphics/nxmu/nx_raise.c b/nuttx/graphics/nxmu/nx_raise.c new file mode 100644 index 000000000..494eb779c --- /dev/null +++ b/nuttx/graphics/nxmu/nx_raise.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * graphics/nxmu/nx_raise.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_raise + * + * Description: + * Bring the specified window to the top of the display. + * + * Input parameters: + * hwnd - the window to be raised + * + * Returned value: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_raise(NXWINDOW hwnd) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_raise_s outmsg; + int ret; + + /* Send the RAISE message */ + + outmsg.msgid = NX_SVRMSG_RAISE; + outmsg.wnd = wnd; + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_raise_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} + diff --git a/nuttx/graphics/nxmu/nx_setbgcolor.c b/nuttx/graphics/nxmu/nx_setbgcolor.c new file mode 100644 index 000000000..57e3b9445 --- /dev/null +++ b/nuttx/graphics/nxmu/nx_setbgcolor.c @@ -0,0 +1,121 @@ +/**************************************************************************** + * graphics/nxmu/nx_setbgcolor.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_setbgcolor + * + * Description: + * Set the color of the background + * + * Input Parameters: + * handle - The connection handle + * color - The color to use in the background + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_setbgcolor(NXHANDLE handle, + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]) +{ + FAR struct nxfe_conn_s *conn = (FAR struct nxfe_conn_s *)handle; + struct nxsvrmsg_setbgcolor_s outmsg; + int ret; + int i; + +#ifdef CONFIG_DEBUG + if (!conn) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Format the fill command */ + + outmsg.msgid = NX_SVRMSG_SETBGCOLOR; + + for (i = 0; i < CONFIG_NX_NPLANES; i++) + { + outmsg.color[i] = color[i]; + } + + /* Forward the fill command to the server */ + + ret = mq_send(conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_setbgcolor_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + return ret; +} diff --git a/nuttx/graphics/nxmu/nx_setposition.c b/nuttx/graphics/nxmu/nx_setposition.c new file mode 100644 index 000000000..9ffa51e9d --- /dev/null +++ b/nuttx/graphics/nxmu/nx_setposition.c @@ -0,0 +1,117 @@ +/**************************************************************************** + * graphics/nxmu/nx_setposition.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_setposition + * + * Description: + * Set the position and size for the selected window + * + * Input Parameters: + * hwnd - The window handle + * pos - The new position of the window + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_setposition(NXWINDOW hwnd, FAR struct nxgl_point_s *pos) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_setposition_s outmsg; + int ret; + +#ifdef CONFIG_DEBUG + if (!wnd || !pos) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Inform the server of the changed position */ + + outmsg.msgid = NX_SVRMSG_SETPOSITION; + outmsg.wnd = wnd; + outmsg.pos.x = pos->x; + outmsg.pos.y = pos->y; + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_setposition_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + return ERROR; + } + + return OK; +} diff --git a/nuttx/graphics/nxmu/nx_setsize.c b/nuttx/graphics/nxmu/nx_setsize.c new file mode 100644 index 000000000..eeff5969e --- /dev/null +++ b/nuttx/graphics/nxmu/nx_setsize.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * graphics/nxmu/nx_setsize.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_setsize` + * + * Description: + * Set the size of the selected window + * + * Input Parameters: + * hwnd - The window handle + * size - The new size of the window. + * + * Return: + * OK on success; ERROR on failure with errno set appropriately + * + ****************************************************************************/ + +int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_rect_s *size) +{ + FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd; + struct nxsvrmsg_setsize_s outmsg; + int ret; + +#ifdef CONFIG_DEBUG + if (!wnd || !size) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Then inform the server of the changed position */ + + outmsg.msgid = NX_SVRMSG_SETSIZE; + outmsg.wnd = wnd; + nxgl_rectcopy(&outmsg.size, size); + + ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_setsize_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + return ERROR; + } + + return OK; +} diff --git a/nuttx/graphics/nxmu/nxfe.h b/nuttx/graphics/nxmu/nxfe.h new file mode 100644 index 000000000..7ba7ed584 --- /dev/null +++ b/nuttx/graphics/nxmu/nxfe.h @@ -0,0 +1,514 @@ +/**************************************************************************** + * graphics/nxmu/nxfe.h + * + * Copyright (C) 2008 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. + * + ****************************************************************************/ + +#ifndef __GRAPHICS_NXMU_NXFE_H +#define __GRAPHICS_NXMU_NXFE_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "nxbe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_NX_MXSERVERMSGS +# define CONFIG_NX_MXSERVERMSGS 32 /* Number of pending messages in server MQ */ +#endif + +#ifndef CONFIG_NX_MXCLIENTMSGS +# define CONFIG_NX_MXCLIENTMSGS 16 /* Number of pending messages in each client MQ */ +#endif + +/* Used to create unique client MQ name */ + +#define NX_CLIENT_MQNAMEFMT "/dev/nxc%d" +#define NX_CLIENT_MXNAMELEN (16) + +#define NX_MXSVRMSGLEN (64) /* Maximum size of a client->server command */ +#define NX_MXEVENTLEN (64) /* Maximum size of an event */ +#define NX_MXCLIMSGLEN (64) /* Maximum size of a server->client message */ + +/* Handy macros */ + +#define nxmu_semgive(sem) sem_post(sem) /* To match nxmu_semtake() */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Client/Connection structures *********************************************/ + +/* Client state */ + +enum nx_clistate_e +{ + NX_CLISTATE_NOTCONNECTED = 0, /* Waiting for server to acknowledge connection */ + NX_CLISTATE_CONNECTED, /* Connection established (normal state) */ + NX_CLISTATE_DISCONNECT_PENDING, /* Waiting for server to acknowledge disconnect */ +}; + +/* This structure represents a connection between the client and the server */ + +struct nxfe_conn_s +{ + /* This number uniquely identifies the client */ + + int cid; /* Client ID (CID) */ + ubyte state; /* See enum nx_clistate_e */ + + /* These are only usable on the client side of the connection */ + + mqd_t crdmq; /* MQ to read from the server (may be non-blocking) */ + mqd_t cwrmq; /* MQ to write to the server (blocking) */ + FAR const struct nx_callback_s *cb; /* Message handling callbacks */ + + /* These are only usable on the server side of the connection */ + + mqd_t swrmq; /* MQ to write to the client */ +}; + +/* Server state structure ***************************************************/ + +/* This the the server 'front-end' state structure */ + +struct nxfe_state_s +{ + /* The 'back-end' window status. Must be first so that instances of + * struct nxbe_state_s can be simply cast to an instance of struct + * nxfe_state_s + */ + + struct nxbe_state_s be; + + /* This is the server's connection to iself */ + + struct nxfe_conn_s conn; +}; + +/* Message IDs **************************************************************/ + +enum nxmsg_e +{ + /* Server-to-Client Messages **********************************************/ + + NX_CLIMSG_CONNECTED = 1, /* The server has completed the connection and is ready */ + NX_CLIMSG_DISCONNECTED, /* The server has disconnected */ + NX_CLIMSG_REDRAW, /* Re-draw the specified window */ + NX_CLIMSG_NEWPOSITION, /* New window size/position */ + NX_CLIMSG_MOUSEIN, /* New mouse positional data available for window */ + NX_CLIMSG_KBDIN, /* New keypad input available for window */ + + /* Client-to-Server Messages **********************************************/ + + NX_SVRMSG_CONNECT, /* Establish connection with new NX server client */ + NX_SVRMSG_DISCONNECT, /* Tear down connection with terminating client */ + NX_SVRMSG_OPENWINDOW, /* Create a new window */ + NX_SVRMSG_CLOSEWINDOW, /* Close an existing window */ + NX_SVRMSG_SETPOSITION, /* Window position has changed */ + NX_SVRMSG_SETSIZE, /* Window size has changed */ + NX_SVRMSG_GETPOSITION, /* Get the current window position and size */ + NX_SVRMSG_RAISE, /* Move the window to the top */ + NX_SVRMSG_LOWER, /* Move the window to the bottom */ + NX_SVRMSG_FILL, /* Fill a rectangle in the window with a color */ + NX_SVRMSG_FILLTRAP, /* Fill a trapezoidal region in the window with a color */ + NX_SVRMSG_MOVE, /* Move a rectangular region within the window */ + NX_SVRMSG_BITMAP, /* Copy a rectangular bitmap into the window */ + NX_SVRMSG_SETBGCOLOR, /* Set the color of the background */ + NX_SVRMSG_MOUSEIN, /* New mouse report from mouse client */ + NX_SVRMSG_KBDIN, /* New keyboard report from keyboard client */ +}; + +/* Message priorities -- they must all be at the same priority to assure + * FIFO execution. + */ + +#define NX_CLIMSG_PRIO 42 +#define NX_SVRMSG_PRIO 42 + +/* Server-to-Client Message Structures **************************************/ + +/* The generic message structure. All messages begin with this form. Also, messages + * that have no data other than the msgid event use this structure. This includes: + * NX_CLIMSG_CONNECTED and NX_CLIMSG_DISCONNECTED. + */ + +struct nxclimsg_s +{ + uint32 msgid; /* Any of nxclimsg_e */ +}; + +/* This message is received when a requested window has been opened. If wnd is NULL + * then errorcode is the errno value that provides the explanation of the error. + */ + +struct nxclimsg_redraw_s +{ + uint32 msgid; /* NX_CLIMSG_REDRAW */ + FAR struct nxbe_window_s *wnd; /* The handle to the window to redraw in */ + FAR struct nxgl_rect_s rect; /* The rectangle to be redrawn */ + boolean more; /* TRUE: more redraw messages follow */ +}; + +/* This message informs the client of the new size or position of the window */ + +struct nxclimsg_newposition_s +{ + uint32 msgid; /* NX_CLIMSG_NEWPOSITION */ + FAR struct nxbe_window_s *wnd; /* The window whose position/size has changed */ + FAR struct nxgl_rect_s size; /* The current window size */ + FAR struct nxgl_point_s pos; /* The current window position */ +}; + +/* This message reports a new mouse event to a particular window */ + +#ifdef CONFIG_NX_MOUSE +struct nxclimsg_mousein_s +{ + uint32 msgid; /* NX_SVRMSG_MOUSEIN */ + FAR struct nxbe_window_s *wnd; /* The handle of window receiving mouse input */ + struct nxgl_point_s pos; /* Mouse X/Y position */ + ubyte buttons; /* Mouse button set */ +} +#endif + +/* This message reports a new keypad event to a particular window */ + +#ifdef CONFIG_NX_KBDIN +struct nxclimsg_key +{ + uint32 msgid; /* NX_CLIMSG_KBDIN */ + FAR struct nxbe_window_s *wnd; /* The handle of window receiving keypad input */ + ubyte nch /* Number of characters received */ + ubyte ch[1]; /* Array of received characters */ +}; +#endif + +/* Client-to-Server Message Structures **************************************/ + +/* The generic message structure. All server messages begin with this form. Also + * messages that have no additional data fields use this structure. This includes: + * NX_SVRMSG_CONNECT and NX_SVRMSG_DISCONNECT. + */ + +struct nxsvrmsg_s /* Generic server message */ +{ + uint32 msgid; /* One of enum nxsvrmsg_e */ + FAR struct nxfe_conn_s *conn; /* The specific connection sending the message */ +}; + +/* This message requests the server to create a new window */ + +struct nxsvrmsg_openwindow_s +{ + uint32 msgid; /* NX_SVRMSG_OPENWINDOW */ + FAR struct nxfe_conn_s *conn; /* The specific connection sending the message */ + FAR struct nxbe_window_s *wnd; /* The pre-allocated window structure */ +}; + +/* This message informs the server that client wishes to close a window */ + +struct nxsvrmsg_closewindow_s +{ + uint32 msgid; /* NX_SVRMSG_CLOSEWINDOW */ + FAR struct nxbe_window_s *wnd; /* The window to be closed */ +}; + +/* This message informs the server that the size or position of the window has changed */ + +struct nxsvrmsg_setposition_s +{ + uint32 msgid; /* NX_SVRMSG_SETPOSITION */ + FAR struct nxbe_window_s *wnd; /* The window whose position/size has changed */ + FAR struct nxgl_point_s pos; /* The new window position */ +}; + +/* This message informs the server that the size or position of the window has changed */ + +struct nxsvrmsg_setsize_s +{ + uint32 msgid; /* NX_SVRMSG_SETSIZE */ + FAR struct nxbe_window_s *wnd; /* The window whose position/size has changed */ + FAR struct nxgl_rect_s size; /* The new window size */ +}; + +/* This message informs the server that the size or position of the window has changed */ + +struct nxsvrmsg_getposition_s +{ + uint32 msgid; /* NX_SVRMSG_FETPOSITION */ + FAR struct nxbe_window_s *wnd; /* The window whose position/size has changed */ +}; + +/* This message informs the server to raise this window to the top of the display */ + +struct nxsvrmsg_raise_s +{ + uint32 msgid; /* NX_SVRMSG_RAISE */ + FAR struct nxbe_window_s *wnd; /* The window to be raised */ +}; + +/* This message informs the server to lower this window to the bottom of the display */ + +struct nxsvrmsg_lower_s +{ + uint32 msgid; /* NX_SVRMSG_LOWER */ + FAR struct nxbe_window_s *wnd; /* The window to be lowered */ +}; + +/* Fill a rectangle in the window with a color */ + +struct nxsvrmsg_fill_s +{ + uint32 msgid; /* NX_SVRMSG_FILL */ + FAR struct nxbe_window_s *wnd; /* The window to fill */ + struct nxgl_rect_s rect; /* The rectangle in the window to fill */ + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]; /* Color to use in the fill */ +}; + +/* Fill a trapezoidal region in the window with a color */ + +struct nxsvrmsg_filltrapezoid_s +{ + uint32 msgid; /* NX_SVRMSG_FILLTRAP */ + FAR struct nxbe_window_s *wnd; /* The window to fill */ + struct nxgl_trapezoid_s trap; /* The trapezoidal region in the window to fill */ + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]; /* Color to use in the fill */ +}; + +/* Move a rectangular region within the window */ + +struct nxsvrmsg_move_s +{ + uint32 msgid; /* NX_SVRMSG_MOVE */ + FAR struct nxbe_window_s *wnd; /* The window within which the move is done */ + struct nxgl_rect_s rect; /* Describes the rectangular region to move */ + struct nxgl_point_s offset; /* The offset to move the region */ +}; + +/* Copy a rectangular bitmap into the window */ + +struct nxsvrmsg_bitmap_s +{ + uint32 msgid; /* NX_SVRMSG_BITMAP */ + FAR struct nxbe_window_s *wnd; /* The window with will receive the bitmap image */ + struct nxgl_rect_s dest; /* Destination location of the bitmap in the window */ + FAR const void *src[CONFIG_NX_NPLANES]; /* The start of the source image. */ + struct nxgl_point_s origin; /* Offset into the source image data */ + unsigned int stride; /* The width of the full source image in pixels. */ +}; + +/* Set the color of the background */ + +struct nxsvrmsg_setbgcolor_s +{ + uint32 msgid; /* NX_SVRMSG_SETBGCOLOR */ + nxgl_mxpixel_t color[CONFIG_NX_NPLANES]; /* Color to use in the background */ +}; + +/* This message reports a new mouse event from a hardware controller attached to + * the server as a regular client (this message may have even been sent from an + * interrupt handler). + */ + +#ifdef CONFIG_NX_MOUSE +struct nxsvrmsg_mousein_s +{ + uint32 msgid; /* NX_SVRMSG_MOUSEIN */ + struct nx_point_x pt; /* Mouse X/Y position */ + ubyte buttons; /* Mouse button set */ +} +#endif + +/* This message reports a new keyboard event from a hardware controller attached to + * some kind of keypad (this message may have even been sent from an + * interrupt handler). + */ + +#ifdef CONFIG_NX_EXTERNKBD +struct nxsvrmsg_kbdin_s +{ + uint32 msgid; /* NX_SVRMSG_KBDIN */ + ubyte nch /* Number of characters received */ + ubyte ch[1]; /* Array of received characters */ +} +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_semtake + * + * Description: + * Take the semaphore, handling EINTR wakeups. See the nxmu_semgive macro. + * + * Input Parameters: + * sem - the semaphore to be taken. + * + * Return: + * None + * + ****************************************************************************/ + +EXTERN void nxmu_semtake(sem_t *sem); + +/**************************************************************************** + * Name: nxmu_openwindow + * + * Description: + * Create a new window. + * + * Input Parameters: + * conn - The client containing connection information [IN] + * svr - The server state structure [IN] + * wnd - The pre-allocated window structure to be ininitilized [IN/OUT] + * + * Return: + * None + * + ****************************************************************************/ + +EXTERN void nxmu_openwindow(FAR struct nxfe_conn_s *conn, + FAR struct nxbe_state_s *be, + FAR struct nxbe_window_s *wnd); + +/**************************************************************************** + * Name: nxfe_reportposition + * + * Descripton: + * Report the new size/position of the window. + * + ****************************************************************************/ + +EXTERN void nxfe_reportposition(FAR struct nxbe_window_s *wnd); + +/**************************************************************************** + * Name: nxfe_redrawreq + * + * Descripton: + * Request the client that has this window to redraw the rectangular region. + * + ****************************************************************************/ + +EXTERN void nxfe_redrawreq(FAR struct nxbe_window_s *wnd, + FAR const struct nxgl_rect_s *rect); + +/**************************************************************************** + * Name: nxmu_mouseinit + * + * Description: + * Initialize with the mouse in the center of the display + * + ****************************************************************************/ + +#ifdef CONFIG_NX_MOUSE +EXTERN void nxmu_mouseinit(int x, int y); +#endif + +/**************************************************************************** + * Name: nxmu_mousereport + * + * Description: + * Report mouse position info to the specified window + * + ****************************************************************************/ + +#ifdef CONFIG_NX_MOUSE +EXTERN void nxmu_mousereport(struct nxbe_window_s *wnd); +#endif + +/**************************************************************************** + * Name: nxmu_mousein + * + * Description: + * New positional data has been received from the thread or interrupt + * handler that manages some kind of pointing hardware. Route that + * positional data to the appropriate window client. + * + ****************************************************************************/ + +#ifdef CONFIG_NX_MOUSE +EXTERN nxmu_mousein(FAR struct nxfe_state_s *fe, + FAR const struct nxgl_point_s *pos, int button); +#endif + +/**************************************************************************** + * Name: nxmu_kbdin + * + * Descripton: + * New keyboard data has been received from the thread or interrupt + * handler that manages some kind of keyboard/keypad hardware. Route that + * positional data to the appropriate window client. + * + ****************************************************************************/ + +#ifdef CONFIG_NX_KBD +EXTERN void nxmu_kbdin(FAR struct nxs_server_s *svr, ubyte nch, ubyte *ch); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __GRAPHICS_NXMU_NXFE_H */ + diff --git a/nuttx/graphics/nxmu/nxmu_kbdin.c b/nuttx/graphics/nxmu/nxmu_kbdin.c new file mode 100644 index 000000000..35af516ae --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_kbdin.c @@ -0,0 +1,122 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_kbdin.c + * + * Copyright (C) 2008 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 "nxfe.h" + +#ifdef CONFIG_NX_KBD + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_kbdin + * + * Descripton: + * New keyboard data has been received from the thread or interrupt + * handler that manages some kind of keyboard/keypad hardware. Route that + * positional data to the appropriate window client. + * + ****************************************************************************/ + +void nxmu_kbdin(FAR struct nxs_server_s *svr, ubyte nch, ubyte *ch) +{ + struct nxbe_window_s *wnd; + FAR struct nxclimgs_kbdin_s *outmsg; + int size; + int ret; + int i; + + /* Allocate a bigger message to account for the variable amount of + * character data. + */ + + size = sizeof(struct nxclimgs_kbdin_s) + nch - 1; + outmsg = (FAR struct nxclimgs_kbdin_s *)malloc(size); + if (outmsg) + { + /* Give the keypad input only to the top child */ + + outsg->msgid = NX_SVRMSG_KBDIN; + outmsg->wnd = svr->topwnd; + outmsg->nch = nch; + + for (i = 0; i < nch; i+) + { + outmsg->ch[i] = ch[i]; + } + + ret = mq_send(svr->topwnd->conn->swrmq, outmsg, size, NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + free(outmsg); + } +} + +#endif /* CONFIG_NX_KBD */ + diff --git a/nuttx/graphics/nxmu/nxmu_mouse.c b/nuttx/graphics/nxmu/nxmu_mouse.c new file mode 100644 index 000000000..5650c8dd2 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_mouse.c @@ -0,0 +1,178 @@ +/**************************************************************************** + * graphics/nxmu/nxmu__mouse.c + * + * Copyright (C) 2008 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 "nxfe.h" + +#ifdef CONFIG_NX_MOUSE + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct nxgl_point_s g_mpos; +static struct nxgl_rect_s g_mrange; +static struct g_mbutton; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_mouseinit + * + * Description: + * Initialize with the mouse in the center of the display + * + ****************************************************************************/ + +void nxmu_mouseinit(int x, int y) +{ + g_mrange.x = x; + g_mrange.y = y; + g_mpos.x = x / 2; + g_mpos.y = y / 2; + g_mbutton = 0; +} + +/**************************************************************************** + * Name: nxmu_mousereport + * + * Description: + * Report mouse position info to the specified window + * + ****************************************************************************/ + +void nxmu_mousereport(struct nxbe_window_s *wnd) +{ + struct nxclimsg_mousein_s outmsg; + int ret; + + outmsg.msgid = NX_CLIMSG_MOUSEIN; + outmsg.wnd = wnd; + outmsg.pos.x = g_mpos.x; + outmsg.pos.y = g_mpos.y; + outmsg.buttons = g_mbutton; + + ret = mq_send(wnd->conn->swrmq, outmsg, sizeof(struct nxclimsg_mousein_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } +} + +/**************************************************************************** + * Name: nxmu_mousein + * + * Description: + * New positional data has been received from the thread or interrupt + * handler that manages some kind of pointing hardware. Route that + * positional data to the appropriate window client. + * + ****************************************************************************/ + +void nxmu_mousein(FAR struct nxfe_state_s *fe, + FAR const struct nxgl_point_s *pos, int button) +{ + struct nxbe_window_s *wnd; + x_coord_t x = pos->x; + x_coord_t y = pos->y; + + /* Clip x and y to within the bounding rectangle */ + + if (x < 0) + { + x = 0; + } + else if (x >= g_mbound.x) + { + x = g_mbound.x - 1; + } + + if (y < 0) + { + y = 0; + } + else if (y >= g_mbound.y) + { + y = g_mbound.y - 1; + } + + /* Look any change in values */ + + if (x != g_mpos.x || y != g_mpos.y || button != g_mbutton) + { + /* Update the mouse value */ + + g_mpos.x = x; + g_mpos.y = y; + b_mbutton = button; + + /* Pick the window to receive the mouse event */ + + for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) + { + nxmu_mousereport(wnd); + } + } +} + +#endif /* CONFIG_NX_MOUSE */ diff --git a/nuttx/graphics/nxmu/nxmu_openwindow.c b/nuttx/graphics/nxmu/nxmu_openwindow.c new file mode 100644 index 000000000..508ab6ad8 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_openwindow.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_openwindow.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_openwindow + * + * Description: + * Create a new window. + * + * Input Parameters: + * conn - The client containing connection information [IN] + * be - The server state structure [IN] + * wnd - The pre-allocated window structure to be ininitilized [IN/OUT] + * + * Return: + * None + * + ****************************************************************************/ + +void nxsmu_openwindow(FAR struct nxfe_conn_s *conn, + FAR struct nxbe_state_s *be, + FAR struct nxbe_window_s *wnd) +{ + /* The window structure was allocated in nx_openwindow and all fields have + * been set to zero (except sem... see below). We need only initialize the + * the non zero fields and insert the new window. + */ + + wnd->be = be; + wnd->conn = conn; + + /* Now, insert the new window at the top on the display. topwind is + * never NULL (it may point only at the background window, however) + */ + + wnd->above = NULL; + wnd->below = be->topwnd; + + be->topwnd->above = wnd; + be->topwnd = wnd; + + /* Provide the initial mouse settings */ + +#ifdef CONFIG_NX_MOUSE + nxmu_mousereport(wnd); +#endif +} diff --git a/nuttx/graphics/nxmu/nxmu_redrawreq.c b/nuttx/graphics/nxmu/nxmu_redrawreq.c new file mode 100644 index 000000000..7151301d2 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_redrawreq.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_redrawreq.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxfe_redrawreq + * + * Descripton: + * Request the client that has this window to redraw the rectangular region. + * + ****************************************************************************/ + +void nxfe_redrawreq(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s *rect) +{ + struct nxclimsg_redraw_s outmsg; + int ret; + + outmsg.msgid = NX_CLIMSG_REDRAW; + outmsg.wnd = wnd; + outmsg.more = FALSE; + nxgl_rectoffset(&outmsg.rect, rect, -wnd->origin.x, -wnd->origin.y); + + ret = mq_send(wnd->conn->swrmq, &outmsg, sizeof(struct nxclimsg_redraw_s), NX_CLIMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } +} + + diff --git a/nuttx/graphics/nxmu/nxmu_reportposition.c b/nuttx/graphics/nxmu/nxmu_reportposition.c new file mode 100644 index 000000000..64006a6d3 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_reportposition.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_reportposition.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxfe_reportposition + * + * Descripton: + * Report the new size/position of the window. + * + ****************************************************************************/ + +void nxfe_reportposition(FAR struct nxbe_window_s *wnd) +{ + FAR struct nxclimsg_newposition_s outmsg; + int ret; + + /* Send the size/position info */ + + outmsg.msgid = NX_CLIMSG_NEWPOSITION; + outmsg.wnd = wnd; + outmsg.pos.x = wnd->origin.x; + outmsg.pos.y = wnd->origin.y; + + /* Convert the frame rectangle to a window-relative rectangle */ + + nxgl_rectoffset(&outmsg.size, &wnd->bounds, -wnd->origin.x, -wnd->origin.y); + + /* And provide this to the client */ + + ret = mq_send(wnd->conn->swrmq, &outmsg, sizeof(struct nxclimsg_newposition_s), NX_SVRMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } +} diff --git a/nuttx/graphics/nxmu/nxmu_semtake.c b/nuttx/graphics/nxmu/nxmu_semtake.c new file mode 100644 index 000000000..079844621 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_semtake.c @@ -0,0 +1,88 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_semtake.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_semtake + ****************************************************************************/ + +void nxmu_semtake(sem_t *sem) +{ + while (sem_wait(sem) != 0) + { + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} diff --git a/nuttx/graphics/nxmu/nxmu_server.c b/nuttx/graphics/nxmu/nxmu_server.c new file mode 100644 index 000000000..e1fc000e1 --- /dev/null +++ b/nuttx/graphics/nxmu/nxmu_server.c @@ -0,0 +1,499 @@ +/**************************************************************************** + * graphics/nxmu/nxmu_server.c + * + * Copyright (C) 2008 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 "nxfe.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#define NX_NCOLORS 256 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxmu_disconnect + ****************************************************************************/ + +static inline void nxmu_disconnect(FAR struct nxfe_conn_s *conn) +{ + struct nxclimsg_s outmsg; + int ret; + + /* Send the handshake message back to the client */ + + outmsg.msgid = NX_CLIMSG_DISCONNECTED; + + ret = mq_send(conn->swrmq, &outmsg, sizeof(struct nxclimsg_s), NX_CLIMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + + /* Close the outgoing client message queue */ + + (void)mq_close(conn->swrmq); +} + +/**************************************************************************** + * Name: nxmu_connect + ****************************************************************************/ + +static inline void nxmu_connect(FAR struct nxfe_conn_s *conn) +{ + char mqname[NX_CLIENT_MXNAMELEN]; + struct nxclimsg_s outmsg; + int ret; + + /* Create the client MQ name */ + + sprintf(mqname, NX_CLIENT_MQNAMEFMT, conn->cid); + + /* Open the client MQ -- this should have already been created by the client */ + + outmsg.msgid = NX_CLIMSG_CONNECTED; + conn->swrmq = mq_open(mqname, O_WRONLY); + if (conn->swrmq) + { + gdbg("mq_open(%s) failed: %d\n", mqname, errno); + outmsg.msgid = NX_CLIMSG_DISCONNECTED; + } + + /* Send the handshake message back to the client */ + + ret = mq_send(conn->cwrmq, &outmsg, sizeof(struct nxclimsg_s), NX_CLIMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } +} + +/**************************************************************************** + * Name: nxmu_release + ****************************************************************************/ + +static int nxmu_release(FAR struct nxfe_state_s *fe) +{ + FAR struct nxbe_window_s *wnd; + struct nxclimsg_s outmsg; + int ret; + + /* Don't want windows to close while we do this */ + + for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) + { + outmsg.msgid = NX_CLIMSG_DISCONNECTED; + ret = mq_send(wnd->conn->swrmq, &outmsg, sizeof(struct nxclimsg_s), NX_CLIMSG_PRIO); + if (ret < 0) + { + gdbg("mq_send failed: %d\n", errno); + } + } + + return OK; +} + +/**************************************************************************** + * Name: nxmu_shutdown + ****************************************************************************/ + +static inline void nxmu_shutdown(FAR struct nxfe_state_s *fe) +{ + FAR struct nxbe_window_s *wnd; + + /* Inform all of the clients in the window list that the server is + * exit-ting. Notes: (1) that the following loop will probably attempt to + * disconnect clients multiple times because one client may have multiple + * windows: The first disconnect will fail; subsequent will return errors + * that are ignored. (2) The final window to be disconnected will be the + * background window, thus close all of the servers message queues. + */ + + for (wnd = fe->be.topwnd; wnd; wnd = wnd->below) + { + (void)nxmu_disconnect(wnd->conn); + } +} + +/**************************************************************************** + * Name: nxmu_setup + ****************************************************************************/ + +static inline int nxmu_setup(FAR const char *mqname, + FAR struct fb_vtable_s *fb, + FAR struct nxfe_state_s *fe) +{ + struct mq_attr attr; + int ret; + + memset(fe, 0, sizeof(struct nxfe_state_s)); + + /* Configure the framebuffer device */ + + ret = nxbe_fbconfigure(fb, &fe->be); + if (ret < 0) + { + gdbg("nxs_fbconfigure failed: %d\n", -ret); + errno = -ret; + return ERROR; + } + +#if CONFIG_FB_CMAP + ret = nxbe_colormap(fb); + if (ret < 0) + { + gdbg("nx_colormap failed: %d\n", -ret); + errno = -ret; + return ERROR; + } +#endif + + /* Initialize the non-NULL elements of the server connection structure. + * Oddly, this strcture represents the connection between the server and + * itself. + * + * Open the incoming server MQ. The server receives messages on the + * background window's incoming message queue. + */ + + attr.mq_maxmsg = CONFIG_NX_MXSERVERMSGS; + attr.mq_msgsize = NX_MXSVRMSGLEN; + attr.mq_flags = 0; + + fe->conn.crdmq = mq_open(mqname, O_RDONLY|O_CREAT, 0666, &attr); + if (fe->conn.crdmq) + { + gdbg("mq_open(%s) failed: %d\n", mqname, errno); + return ERROR; /* mq_open sets errno */ + } + + /* NOTE that the outgoing client MQ (cwrmq) is not initialized. The + * background window never initiates messages. + */ + + /* Open the outgoing server MQ. This is used to send messages to the + * background window which will, of course, be received and handled by + * the server message loop. + */ + + /* Open the server MQ for writing (same attributes) */ + + fe->conn.cwrmq = mq_open(mqname, O_WRONLY); + if (fe->conn.cwrmq) + { + gdbg("mq_open(%s) failed: %d\n", mqname, errno); + mq_close(fe->conn.crdmq); + return ERROR; /* mq_open sets errno */ + } + + /* The server is now "connected" to itself via the background window */ + + fe->conn.state = NX_CLISTATE_CONNECTED; + + /* Initialize the non-NULL elements of the background window */ + + fe->be.bkgd.conn = &fe->conn; + fe->be.bkgd.be = (FAR struct nxbe_state_s*)fe; + + fe->be.bkgd.bounds.pt2.x = fe->be.vinfo.xres; + fe->be.bkgd.bounds.pt2.y = fe->be.vinfo.yres; + + /* Complete initialization of the server state structure. The + * window list contains only one element: The background window + * with nothing else above or below it + */ + + fe->be.topwnd = &fe->be.bkgd; + + /* Initialize the mouse position */ + +#ifdef CONFIG_NX_MOUSE + nxmu_mouseinit(fe->be.vinfo.xres, fe->be.vinfo.yres); +#endif + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nx_runinstance + * + * Description: + * This is the server entry point. It does not return; the calling thread + * is dedicated to supporting NX server. + * + * NOTE that multiple instances of the NX server may run at the same time, + * each with different callback and message queue names. + * + * Input Parameters: + * mqname - The name for the server incoming message queue + * fb - Vtable "object" of the framebuffer "driver" to use + * + * Return: + * This function usually does not return. If it does return, it will + * return ERROR and errno will be set appropriately. + * + ****************************************************************************/ + +int nx_runinstance(FAR const char *mqname, FAR struct fb_vtable_s *fb) +{ + struct nxfe_state_s fe; + FAR struct nxsvrmsg_s *msg; + ubyte buffer[NX_MXSVRMSGLEN]; + int nbytes; + int ret; + + /* Initialization *********************************************************/ + + /* Sanity checking */ + +#ifdef CONFIG_DEBUG + if (!mqname || !fb) + { + errno = EINVAL; + return ERROR; + } +#endif + + /* Initialize and configure the server */ + + ret = nxmu_setup(mqname, fb, &fe); + if (ret < 0) + { + return ret; /* nxmu_setup sets errno */ + } + + /* Produce the initial, background display */ + + nxbe_redraw(&fe.be, &fe.be.bkgd, &fe.be.bkgd.bounds); + + /* Message Loop ***********************************************************/ + + /* Then loop forever processing incoming messages */ + + for (;;) + { + /* Receive the next server message */ + + nbytes = mq_receive(fe.conn.crdmq, buffer, NX_MXSVRMSGLEN, 0); + if (nbytes < 0) + { + if (errno != EINTR) + { + gdbg("mq_receive failed: %d\n", errno); + goto errout; /* mq_receive sets errno */ + } + continue; + } + + /* Dispatch the message appropriately */ + + DEBUGASSERT(nbytes >= sizeof(struct nxsvrmsg_s)); + msg = (FAR struct nxsvrmsg_s *)buffer; + + gvdbg("Received opcode=%d nbytes=%d\n", msg->msgid, nbytes); + switch (msg->msgid) + { + /* Messages sent from clients to the NX server *********************/ + + case NX_SVRMSG_CONNECT: /* Establish connection with new NX server client */ + { + FAR struct nxsvrmsg_s *connmsg = (FAR struct nxsvrmsg_s *)buffer; + nxmu_connect(connmsg->conn); + } + break; + + case NX_SVRMSG_DISCONNECT: /* Tear down connection with terminating client */ + { + FAR struct nxsvrmsg_s *disconnmsg = (FAR struct nxsvrmsg_s *)buffer; + nxmu_disconnect(disconnmsg->conn); + } + break; + + case NX_SVRMSG_OPENWINDOW: /* Create a new window */ + { + FAR struct nxsvrmsg_openwindow_s *openmsg = (FAR struct nxsvrmsg_openwindow_s *)buffer; + nxmu_openwindow(openmsg->conn, &fe.be, openmsg->wnd); + } + break; + + case NX_SVRMSG_CLOSEWINDOW: /* Close an existing window */ + { + FAR struct nxsvrmsg_closewindow_s *closemsg = (FAR struct nxsvrmsg_closewindow_s *)buffer; + nxbe_closewindow(closemsg->wnd); + } + break; + + case NX_SVRMSG_SETPOSITION: /* Change window position */ + { + FAR struct nxsvrmsg_setposition_s *setposmsg = (FAR struct nxsvrmsg_setposition_s *)buffer; + nxbe_setposition(setposmsg->wnd, &setposmsg->pos); + } + break; + + case NX_SVRMSG_SETSIZE: /* Change window size */ + { + FAR struct nxsvrmsg_setsize_s *setsizemsg = (FAR struct nxsvrmsg_setsize_s *)buffer; + nxbe_setsize(setsizemsg->wnd, &setsizemsg->size); + } + break; + + case NX_SVRMSG_GETPOSITION: /* Get the window size/position */ + { + FAR struct nxsvrmsg_getposition_s *getposmsg = (FAR struct nxsvrmsg_getposition_s *)buffer; + nxfe_reportposition(getposmsg->wnd); + } + break; + + case NX_SVRMSG_RAISE: /* Move the window to the top of the display */ + { + FAR struct nxsvrmsg_raise_s *raisemsg = (FAR struct nxsvrmsg_raise_s *)buffer; + nxbe_raise(raisemsg->wnd); + } + break; + + case NX_SVRMSG_LOWER: /* Lower the window to the bottom of the display */ + { + FAR struct nxsvrmsg_lower_s *lowermsg = (FAR struct nxsvrmsg_lower_s *)buffer; + nxbe_raise(lowermsg->wnd); + } + break; + + case NX_SVRMSG_FILL: /* Fill a rectangular region in the window with a color */ + { + FAR struct nxsvrmsg_fill_s *fillmsg = (FAR struct nxsvrmsg_fill_s *)buffer; + nxbe_fill(fillmsg->wnd, &fillmsg->rect, fillmsg->color); + } + break; + + case NX_SVRMSG_FILLTRAP: /* Fill a trapezoidal region in the window with a color */ + { + FAR struct nxsvrmsg_filltrapezoid_s *trapmsg = (FAR struct nxsvrmsg_filltrapezoid_s *)buffer; + nxbe_filltrapezoid(trapmsg->wnd, &trapmsg->trap, trapmsg->color); + } + break; + case NX_SVRMSG_MOVE: /* Move a rectangular region within the window */ + { + FAR struct nxsvrmsg_move_s *movemsg = (FAR struct nxsvrmsg_move_s *)buffer; + nxbe_move(movemsg->wnd, &movemsg->rect, &movemsg->offset); + } + break; + + case NX_SVRMSG_BITMAP: /* Copy a rectangular bitmap into the window */ + { + FAR struct nxsvrmsg_bitmap_s *bmpmsg = (FAR struct nxsvrmsg_bitmap_s *)buffer; + nxbe_bitmap(bmpmsg->wnd, &bmpmsg->dest, bmpmsg->src, &bmpmsg->origin, bmpmsg->stride); + } + break; + + case NX_SVRMSG_SETBGCOLOR: /* Set the color of the background */ + { + FAR struct nxsvrmsg_setbgcolor_s *bgcolormsg = (FAR struct nxsvrmsg_setbgcolor_s *)buffer; + nxbe_fill(&fe.be.bkgd, &fe.be.bkgd.bounds, bgcolormsg->color); + } + break; + +#ifdef CONFIG_NX_MOUSE + case NX_SVRMSG_MOUSEIN: /* New mouse report from mouse client */ + { + FAR struct nxsvrmsg_mousein_s *mousemsg = (FAR struct nxsvrmsg_mousein_s *)buffer; + nxmu_mousein(&fe.be, &mousemsg->pt, mousemsg->buttons); + } + break; +#endif +#ifdef CONFIG_NX_KBD + case NX_SVRMSG_KBDIN: /* New keyboard report from keyboard client */ + { + FAR struct nxsvrmsg_kbdin_s *kbdmsg = (FAR struct nxsvrmsg_kbdin_s *)buffer; + nxmu_kbdin(&fe.be, kbdmsg->nch, kbdmsg->ch); + } + break; +#endif + + /* Messages sent to the backgound window ***************************/ + + case NX_CLIMSG_REDRAW: /* Re-draw the background window */ + nxbe_redraw(&fe.be, &fe.be.bkgd, &fe.be.bkgd.bounds); + break; + + case NX_CLIMSG_MOUSEIN: /* Ignored */ + case NX_CLIMSG_KBDIN: + break; + + case NX_CLIMSG_CONNECTED: /* Shouldn't happen */ + case NX_CLIMSG_DISCONNECTED: + default: + gdbg("Unrecognized command: %d\n", msg->msgid); + break; + } + } + +errout: + nxmu_shutdown(&fe); + return OK; +} -- cgit v1.2.3