summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/graphics/nxbe/nxbe_move.c23
-rw-r--r--nuttx/graphics/nxtk/Make.defs10
-rw-r--r--nuttx/graphics/nxtk/nxtk_bitmaptoolbar.c123
-rw-r--r--nuttx/graphics/nxtk/nxtk_bitmapwindow.c123
-rw-r--r--nuttx/graphics/nxtk/nxtk_filltoolbar.c13
-rw-r--r--nuttx/graphics/nxtk/nxtk_fillwindow.c13
-rw-r--r--nuttx/graphics/nxtk/nxtk_internal.h52
-rw-r--r--nuttx/graphics/nxtk/nxtk_lower.c96
-rw-r--r--nuttx/graphics/nxtk/nxtk_movetoolbar.c119
-rw-r--r--nuttx/graphics/nxtk/nxtk_movewindow.c119
-rw-r--r--nuttx/graphics/nxtk/nxtk_opentoolbar.c8
-rw-r--r--nuttx/graphics/nxtk/nxtk_raise.c96
-rw-r--r--nuttx/graphics/nxtk/nxtk_subwindowclip.c116
-rw-r--r--nuttx/graphics/nxtk/nxtk_subwindowmove.c152
-rw-r--r--nuttx/include/nuttx/nx.h2
-rw-r--r--nuttx/include/nuttx/nxtk.h110
16 files changed, 1139 insertions, 36 deletions
diff --git a/nuttx/graphics/nxbe/nxbe_move.c b/nuttx/graphics/nxbe/nxbe_move.c
index 820614ae5..515c2c215 100644
--- a/nuttx/graphics/nxbe/nxbe_move.c
+++ b/nuttx/graphics/nxbe/nxbe_move.c
@@ -58,7 +58,7 @@ struct nxbe_move_s
struct nxbe_clipops_s cops;
struct nxgl_point_s offset;
FAR struct nxbe_window_s *wnd;
- struct nxgl_rect_s srcsize;
+ struct nxgl_rect_s srcrect;
ubyte order;
};
@@ -121,8 +121,8 @@ static void nxbe_clipmoveobscured(FAR struct nxbe_clipops_s *cops,
* Name: nxbe_clipmovedest
*
* Description:
- * Called from nxbe_clipper() to performed the move operation on visible regions
- * of the rectangle.
+ * Called from nxbe_clipper() to performed the move operation on visible
+ * regions of the source rectangle.
*
****************************************************************************/
@@ -143,7 +143,7 @@ static void nxbe_clipmovedest(FAR struct nxbe_clipops_s *cops,
* background window
*/
- nxgl_rectoffset(&tmprect1, &dstdata->srcsize, offset.x, offset.y);
+ nxgl_rectoffset(&tmprect1, &dstdata->srcrect, offset.x, offset.y);
nxgl_rectintersect(&tmprect2, &tmprect1, &wnd->be->bkgd.bounds);
nxgl_nonintersecting(nonintersecting, rect, &tmprect2);
@@ -158,7 +158,7 @@ static void nxbe_clipmovedest(FAR struct nxbe_clipops_s *cops,
/* Cip to determine what is inside the bounds */
nxgl_rectoffset(&tmprect1, rect, -offset.x, -offset.y);
- nxgl_rectintersect(&src, &tmprect1, &dstdata->srcsize);
+ nxgl_rectintersect(&src, &tmprect1, &dstdata->srcrect);
if (!nxgl_nullrect(&src))
{
@@ -199,7 +199,6 @@ void nxbe_move(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s *rect
{
FAR const struct nxgl_rect_s *bounds = &wnd->bounds;
struct nxbe_move_s info;
- struct nxgl_rect_s remaining;
int i;
#ifdef CONFIG_DEBUG
@@ -211,14 +210,14 @@ void nxbe_move(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s *rect
/* Offset the rectangle by the window origin to create a bounding box */
- nxgl_rectoffset(&remaining, rect, wnd->origin.x, wnd->origin.y);
+ nxgl_rectoffset(&info.srcrect, rect, wnd->origin.x, wnd->origin.y);
/* Clip to the limits of the window and of the background screen */
- nxgl_rectintersect(&remaining, &remaining, &wnd->bounds);
- nxgl_rectintersect(&remaining, &remaining, &wnd->be->bkgd.bounds);
+ nxgl_rectintersect(&info.srcrect, &info.srcrect, &wnd->bounds);
+ nxgl_rectintersect(&info.srcrect, &info.srcrect, &wnd->be->bkgd.bounds);
- if (nxgl_nullrect(&remaining))
+ if (nxgl_nullrect(&info.srcrect))
{
return;
}
@@ -252,7 +251,7 @@ void nxbe_move(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s *rect
}
}
- nxgl_rectintersect(&info.srcsize, bounds, &wnd->be->bkgd.bounds);
+ nxgl_rectintersect(&info.srcrect, bounds, &wnd->be->bkgd.bounds);
#if CONFIG_NX_NPLANES > 1
for (i = 0; i < wnd->be->vinfo.nplanes; i++)
@@ -260,7 +259,7 @@ void nxbe_move(FAR struct nxbe_window_s *wnd, FAR const struct nxgl_rect_s *rect
i = 0;
#endif
{
- nxbe_clipper(wnd->above, &remaining, info.order,
+ nxbe_clipper(wnd->above, &info.srcrect, info.order,
&info.cops, &wnd->be->plane[i]);
}
}
diff --git a/nuttx/graphics/nxtk/Make.defs b/nuttx/graphics/nxtk/Make.defs
index df78975b1..b63b11fda 100644
--- a/nuttx/graphics/nxtk/Make.defs
+++ b/nuttx/graphics/nxtk/Make.defs
@@ -35,9 +35,9 @@
NXTK_ASRCS =
NXTKWIN_CSRCS = nxtk_openwindow.c nxtk_closewindow.c nxtk_getposition.c \
- nxtk_setposition.c nxtk_setsize.c nxtk_fillwindow.c \
- nxtk_filltrapwindow.c nxtk_events.c \
- nxtk_setsubwindows.c
+ nxtk_setposition.c nxtk_setsize.c nxtk_raise.c nxtk_lower.c \
+ nxtk_fillwindow.c nxtk_filltrapwindow.c nxtk_movewindow.c \
+ nxtk_bitmapwindow.c nxtk_events.c nxtk_setsubwindows.c
NXTKTB_CSRCS = nxtk_opentoolbar.c nxtk_closetoolbar.c nxtk_filltoolbar.c \
- nxtk_filltraptoolbar.c
-NXTK_CSRCS = $(NXTKWIN_CSRCS) $(NXTKTB_CSRCS) \ No newline at end of file
+ nxtk_filltraptoolbar.c nxtk_movetoolbar.c nxtk_bitmaptoolbar.c
+NXTK_CSRCS = $(NXTKWIN_CSRCS) $(NXTKTB_CSRCS) nxtk_subwindowclip.c nxtk_subwindowmove.c \ No newline at end of file
diff --git a/nuttx/graphics/nxtk/nxtk_bitmaptoolbar.c b/nuttx/graphics/nxtk/nxtk_bitmaptoolbar.c
new file mode 100644
index 000000000..6b5769e88
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_bitmaptoolbar.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_bitmaptoolbar.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_bitmaptoolbar
+ *
+ * Description:
+ * Copy a rectangular region of a larger image into the rectangle in the
+ * specified toolbar sub-window.
+ *
+ * Input Parameters:
+ * htb - The toolbar sub-window that will receive the bitmap image
+ * dest - Describes the rectangular region on in the toolbar sub-window
+ * will receive 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 nxtk_bitmaptoolbar(NXTKWINDOW htb, 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 nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)htb;
+ struct nxgl_rect_s clipdest;
+
+#ifdef CONFIG_DEBUG
+ if (!htb || !dest || !src || !origin)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ /* Clip the rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ */
+
+ nxtk_subwindowclip(fwnd, &clipdest, dest, &fwnd->tbrect);
+
+ /* Then copy the bitmap */
+
+ nx_bitmap((NXWINDOW)htb, &clipdest, src, origin, stride);
+ return OK;
+}
diff --git a/nuttx/graphics/nxtk/nxtk_bitmapwindow.c b/nuttx/graphics/nxtk/nxtk_bitmapwindow.c
new file mode 100644
index 000000000..1410e8c6d
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_bitmapwindow.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_bitmapwindow.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nxtk.h>
+#include <nuttx/nx.h>
+
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_bitmapwindow
+ *
+ * Description:
+ * Copy a rectangular region of a larger image into the rectangle in the
+ * specified client sub-window.
+ *
+ * Input Parameters:
+ * hfwnd The client sub0window that will receive the bitmap image
+ * dest - Describes the rectangular region on in the client sub-window
+ * will receive 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 nxtk_bitmapwindow(NXTKWINDOW hfwnd, 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 nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hfwnd;
+ struct nxgl_rect_s clipdest;
+
+#ifdef CONFIG_DEBUG
+ if (!hfwnd || !dest || !src || !origin)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ /* Clip the rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ */
+
+ nxtk_subwindowclip(fwnd, &clipdest, dest, &fwnd->fwrect);
+
+ /* Then copy the bitmap */
+
+ nx_bitmap((NXWINDOW)hfwnd, &clipdest, src, origin, stride);
+ return OK;
+}
diff --git a/nuttx/graphics/nxtk/nxtk_filltoolbar.c b/nuttx/graphics/nxtk/nxtk_filltoolbar.c
index b216d73b7..73760be24 100644
--- a/nuttx/graphics/nxtk/nxtk_filltoolbar.c
+++ b/nuttx/graphics/nxtk/nxtk_filltoolbar.c
@@ -94,8 +94,7 @@ int nxtk_filltoolbar(NXTKTOOLBAR htb, FAR const struct nxgl_rect_s *rect,
nxgl_mxpixel_t color[CONFIG_NX_NPLANES])
{
FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)htb;
- struct nxgl_rect_s relbounds;
- struct nxgl_rect_s cliprect;
+ struct nxgl_rect_s fillrect;
#ifdef CONFIG_DEBUG
if (!htb || !rect || !color)
@@ -105,12 +104,14 @@ int nxtk_filltoolbar(NXTKTOOLBAR htb, FAR const struct nxgl_rect_s *rect,
}
#endif
- /* Clip the rectangle to lie within the toolbar region */
+ /* Clip the rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ */
- nxgl_rectoffset(&relbounds, &fwnd->tbrect, fwnd->tbrect.pt1.x, fwnd->tbrect.pt1.y);
- nxgl_rectintersect(&cliprect, rect, &relbounds);
+ nxtk_subwindowclip(fwnd, &fillrect, rect, &fwnd->tbrect);
/* Then fill it */
- return nx_fill((NXWINDOW)htb, &cliprect, color);
+ return nx_fill((NXWINDOW)htb, &fillrect, color);
}
diff --git a/nuttx/graphics/nxtk/nxtk_fillwindow.c b/nuttx/graphics/nxtk/nxtk_fillwindow.c
index b4926c49c..f8a645302 100644
--- a/nuttx/graphics/nxtk/nxtk_fillwindow.c
+++ b/nuttx/graphics/nxtk/nxtk_fillwindow.c
@@ -94,8 +94,7 @@ int nxtk_fillwindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
nxgl_mxpixel_t color[CONFIG_NX_NPLANES])
{
FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hfwnd;
- struct nxgl_rect_s relbounds;
- struct nxgl_rect_s cliprect;
+ struct nxgl_rect_s fillrect;
#ifdef CONFIG_DEBUG
if (!hfwnd || !rect || !color)
@@ -105,12 +104,14 @@ int nxtk_fillwindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
}
#endif
- /* Clip the rectangle to lie within the client window region */
+ /* Clip the rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ */
- nxgl_rectoffset(&relbounds, &fwnd->fwrect, fwnd->fwrect.pt1.x, fwnd->fwrect.pt1.y);
- nxgl_rectintersect(&cliprect, rect, &relbounds);
+ nxtk_subwindowclip(fwnd, &fillrect, rect, &fwnd->fwrect);
/* Then fill it */
- return nx_fill((NXWINDOW)hfwnd, &cliprect, color);
+ return nx_fill((NXWINDOW)hfwnd, &fillrect, color);
}
diff --git a/nuttx/graphics/nxtk/nxtk_internal.h b/nuttx/graphics/nxtk/nxtk_internal.h
index b5df23a80..2f9878a99 100644
--- a/nuttx/graphics/nxtk/nxtk_internal.h
+++ b/nuttx/graphics/nxtk/nxtk_internal.h
@@ -121,6 +121,58 @@ extern FAR const struct nx_callback_s g_nxtkcb;
EXTERN void nxtk_setsubwindows(FAR struct nxtk_framedwindow_s *fwnd);
+/****************************************************************************
+ * Name: nxtk_subwindowclip
+ *
+ * Description:
+ * Clip the src rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ *
+ * Input parameters:
+ * fwnd - The framed window to be used
+ * dest - The locaton to put the result
+ * src - The src rectangle in relative sub-window coordinates
+ * bounds - The subwindow bounds in absolute screen coordinates.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+EXTERN void nxtk_subwindowclip(FAR struct nxtk_framedwindow_s *fwnd,
+ FAR struct nxgl_rect_s *dest,
+ FAR const struct nxgl_rect_s *src,
+ FAR const struct nxgl_rect_s *bounds);
+
+/****************************************************************************
+ * Name: nxtk_subwindowmove
+ *
+ * Description:
+ * Perform common clipping operations in preparatons for calling nx_move()
+ *
+ * Input Parameters:
+ * fwnd - The framed window within which the move is to be done.
+ * This must have been previously created by nxtk_openwindow().
+ * destrect - The loccation to receive the clipped rectangle relative
+ * to containing window
+ * destoffset - The location to received the clipped offset.
+ * srcrect - Describes the rectangular region relative to the client
+ * sub-window to move relative to the sub-window
+ * srcoffset - The offset to move the region
+ * bounds - The subwindow bounds in absolute screen coordinates.
+ *
+ * Return:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+EXTERN void nxtk_subwindowmove(FAR struct nxtk_framedwindow_s *fwnd,
+ FAR struct nxgl_rect_s *destrect,
+ FAR struct nxgl_point_s *destoffset,
+ FAR const struct nxgl_rect_s *srcrect,
+ FAR const struct nxgl_point_s *srcoffset,
+ FAR const struct nxgl_rect_s *bounds);
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/graphics/nxtk/nxtk_lower.c b/nuttx/graphics/nxtk/nxtk_lower.c
new file mode 100644
index 000000000..2c66c1185
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_lower.c
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_lower.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_lower
+ *
+ * Description:
+ * Lower the window containing the specified client sub-window to the
+ * bottom of the display.
+ *
+ * Input parameters:
+ * hfwnd - the window to be lowered. This must have been previously created
+ * by nxtk_openwindow().
+ *
+ * Returned value:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+int nxtk_lower(NXTKWINDOW hfwnd)
+{
+ return nx_lower((NXWINDOW)hfwnd);
+}
diff --git a/nuttx/graphics/nxtk/nxtk_movetoolbar.c b/nuttx/graphics/nxtk/nxtk_movetoolbar.c
new file mode 100644
index 000000000..78a20b54e
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_movetoolbar.c
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_movetoolbar.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_movetoolbar
+ *
+ * Description:
+ * Move a rectangular region within the toolbar sub-window of a framed window
+ *
+ * Input Parameters:
+ * htb - The toolbar sub-window within which the move is to be done.
+ * This must have been previously created by nxtk_openwindow().
+ * rect - Describes the rectangular region relative to the toolbar
+ * sub-window to move
+ * offset - The offset to move the region
+ *
+ * Return:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+int nxtk_movetoolbar(NXTKTOOLBAR htb, FAR const struct nxgl_rect_s *rect,
+ FAR const struct nxgl_point_s *offset)
+{
+ FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)htb;
+ struct nxgl_rect_s srcrect;
+ struct nxgl_point_s clipoffset;
+
+#ifdef CONFIG_DEBUG
+ if (!htb || !rect || !offset)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ /* Make sure that both the source and dest rectangle lie within the
+ * toolbar sub-window
+ */
+
+ nxtk_subwindowmove(fwnd, &srcrect, &clipoffset, rect, offset, &fwnd->tbrect);
+
+ /* Then move it within the toolbar window */
+
+ return nx_move((NXTKTOOLBAR)htb, &srcrect, &clipoffset);
+}
diff --git a/nuttx/graphics/nxtk/nxtk_movewindow.c b/nuttx/graphics/nxtk/nxtk_movewindow.c
new file mode 100644
index 000000000..15f3c05c6
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_movewindow.c
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_movewindow.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_movewindow
+ *
+ * Description:
+ * Move a rectangular region within the client sub-window of a framed window
+ *
+ * Input Parameters:
+ * hfwnd - The client sub-window within which the move is to be done.
+ * This must have been previously created by nxtk_openwindow().
+ * rect - Describes the rectangular region relative to the client
+ * sub-window to move
+ * offset - The offset to move the region
+ *
+ * Return:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+int nxtk_movewindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
+ FAR const struct nxgl_point_s *offset)
+{
+ FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hfwnd;
+ struct nxgl_rect_s srcrect;
+ struct nxgl_point_s clipoffset;
+
+#ifdef CONFIG_DEBUG
+ if (!hfwnd || !rect || !offset)
+ {
+ errno = EINVAL;
+ return ERROR;
+ }
+#endif
+
+ /* Make sure that both the source and dest rectangle lie within the
+ * client sub-window
+ */
+
+ nxtk_subwindowmove(fwnd, &srcrect, &clipoffset, rect, offset, &fwnd->fwrect);
+
+ /* Then move it within the client window */
+
+ return nx_move((NXWINDOW)hfwnd, &srcrect, &clipoffset);
+}
diff --git a/nuttx/graphics/nxtk/nxtk_opentoolbar.c b/nuttx/graphics/nxtk/nxtk_opentoolbar.c
index ca8991a07..315e72a5a 100644
--- a/nuttx/graphics/nxtk/nxtk_opentoolbar.c
+++ b/nuttx/graphics/nxtk/nxtk_opentoolbar.c
@@ -81,7 +81,7 @@
* Create a tool bar at the top of the specified framed window
*
* Input Parameters:
- * hwnd - The handle returned by nxtk_openwindow
+ * hfwnd - The handle returned by nxtk_openwindow
* height - The request height of the toolbar in pixels
* cb - Callbacks used to process toolbar events
* arg - User provided value that will be returned with toolbar callbacks.
@@ -92,14 +92,14 @@
*
****************************************************************************/
-NXTKTOOLBAR nxtk_opentoolbar(NXTKWINDOW hwnd, nxgl_coord_t height,
+NXTKTOOLBAR nxtk_opentoolbar(NXTKWINDOW hfwnd, nxgl_coord_t height,
FAR const struct nx_callback_s *cb,
FAR void *arg)
{
- FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hwnd;
+ FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hfwnd;
#ifdef CONFIG_DEBUG
- if (!hwnd || !cb)
+ if (!hfwnd || !cb)
{
errno = EINVAL;
return NULL;
diff --git a/nuttx/graphics/nxtk/nxtk_raise.c b/nuttx/graphics/nxtk/nxtk_raise.c
new file mode 100644
index 000000000..f435c95c3
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_raise.c
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_raise.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_raise
+ *
+ * Description:
+ * Bring the window containing the specified client sub-window to the top
+ * of the display.
+ *
+ * Input parameters:
+ * hfwnd - the window to be raised. This must have been previously created
+ * by nxtk_openwindow().
+ *
+ * Returned value:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+int nxtk_raise(NXTKWINDOW hfwnd)
+{
+ return nx_raise((NXWINDOW)hfwnd);
+}
diff --git a/nuttx/graphics/nxtk/nxtk_subwindowclip.c b/nuttx/graphics/nxtk/nxtk_subwindowclip.c
new file mode 100644
index 000000000..594e7d844
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_subwindowclip.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_subwindowclip.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_subwindowclip
+ *
+ * Description:
+ * Clip the src rectangle so that it lies within the sub-window bounds
+ * then move the rectangle to that it is relative to the containing
+ * window.
+ *
+ * Input parameters:
+ * fwnd - The framed window to be used
+ * dest - The locaton to put the result
+ * src - The src rectangle in relative sub-window coordinates
+ * bounds - The subwindow bounds in absolute screen coordinates.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void nxtk_subwindowclip(FAR struct nxtk_framedwindow_s *fwnd,
+ FAR struct nxgl_rect_s *dest,
+ FAR const struct nxgl_rect_s *src,
+ FAR const struct nxgl_rect_s *bounds)
+{
+ struct nxgl_rect_s tmp;
+
+ /* Temporarily, position the src rectangle in absolute screen coordinates */
+
+ nxgl_rectoffset(&tmp, dest, bounds->pt1.x, bounds->pt1.y);
+
+ /* Clip the dest rectangle to lie within the client window region */
+
+ nxgl_rectintersect(&tmp, &tmp, bounds);
+
+ /* Then move the rectangle so that is relative to the containing window, not the
+ * client subwindow
+ */
+
+ nxgl_rectoffset(dest, &tmp, -fwnd->wnd.bounds.pt1.x, -fwnd->wnd.bounds.pt1.y);
+}
diff --git a/nuttx/graphics/nxtk/nxtk_subwindowmove.c b/nuttx/graphics/nxtk/nxtk_subwindowmove.c
new file mode 100644
index 000000000..8408465d2
--- /dev/null
+++ b/nuttx/graphics/nxtk/nxtk_subwindowmove.c
@@ -0,0 +1,152 @@
+/****************************************************************************
+ * graphics/nxtk/nxtk_subwindowmove.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/nx.h>
+#include <nuttx/nxtk.h>
+
+#include "nxfe.h"
+#include "nxtk_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxtk_subwindowmove
+ *
+ * Description:
+ * Perform common clipping operations in preparatons for calling nx_move()
+ *
+ * Input Parameters:
+ * fwnd - The framed window within which the move is to be done.
+ * This must have been previously created by nxtk_openwindow().
+ * destrect - The loccation to receive the clipped rectangle relative
+ * to containing window
+ * destoffset - The location to received the clipped offset.
+ * srcrect - Describes the rectangular region relative to the client
+ * sub-window to move relative to the sub-window
+ * srcoffset - The offset to move the region
+ * bounds - The subwindow bounds in absolute screen coordinates.
+ *
+ * Return:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+void nxtk_subwindowmove(FAR struct nxtk_framedwindow_s *fwnd,
+ FAR struct nxgl_rect_s *destrect,
+ FAR struct nxgl_point_s *destoffset,
+ FAR const struct nxgl_rect_s *srcrect,
+ FAR const struct nxgl_point_s *srcoffset,
+ FAR const struct nxgl_rect_s *bounds)
+{
+ struct nxgl_rect_s abssrc;
+
+ /* Temporarily, position the src rectangle in absolute screen coordinates */
+
+ nxgl_rectoffset(&abssrc, srcrect, bounds->pt1.x, bounds->pt1.y);
+
+ /* Clip the src rectangle to lie within the client window region */
+
+ nxgl_rectintersect(&abssrc, &abssrc, &fwnd->fwrect);
+
+ /* Clip the offset so that the source rectangle does not move out of the
+ * the client sub-window.
+ */
+
+ destoffset->x = srcoffset->x;
+ if (destoffset->x < 0)
+ {
+ if (abssrc.pt1.x + destoffset->x < bounds->pt1.x)
+ {
+ destoffset->x = bounds->pt1.x - abssrc.pt1.x;
+ }
+ }
+ else if (abssrc.pt2.x + destoffset->x > bounds->pt2.x)
+ {
+ destoffset->x = bounds->pt2.x - abssrc.pt2.x;
+ }
+
+ destoffset->y = srcoffset->y;
+ if (destoffset->y < 0)
+ {
+ if (abssrc.pt1.y + destoffset->y < bounds->pt1.y)
+ {
+ destoffset->y = bounds->pt1.y - abssrc.pt1.y;
+ }
+ }
+ else if (abssrc.pt2.y + destoffset->y > bounds->pt2.y)
+ {
+ destoffset->y = bounds->pt2.y - abssrc.pt2.y;
+ }
+
+
+ /* Then move the rectangle so that is relative to the containing window, not the
+ * client subwindow
+ */
+
+ nxgl_rectoffset(destrect, &abssrc, -fwnd->wnd.bounds.pt1.x, -fwnd->wnd.bounds.pt1.y);
+}
diff --git a/nuttx/include/nuttx/nx.h b/nuttx/include/nuttx/nx.h
index a5614caff..a3ffe1b32 100644
--- a/nuttx/include/nuttx/nx.h
+++ b/nuttx/include/nuttx/nx.h
@@ -598,7 +598,7 @@ EXTERN int nx_fill(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect,
*
* Input Parameters:
* hwnd - The window handle
- * clip - Clipping region (may be null)
+ * clip - Clipping rectangle relative to window (may be null)
* trap - The trapezoidal region to be filled
* color - The color to use in the fill
*
diff --git a/nuttx/include/nuttx/nxtk.h b/nuttx/include/nuttx/nxtk.h
index 4081450e0..117a4cc71 100644
--- a/nuttx/include/nuttx/nxtk.h
+++ b/nuttx/include/nuttx/nxtk.h
@@ -172,6 +172,24 @@ EXTERN int nxtk_setposition(NXTKWINDOW hfwnd, FAR struct nxgl_point_s *pos);
EXTERN int nxtk_setsize(NXTKWINDOW hfwnd, FAR struct nxgl_rect_s *size);
/****************************************************************************
+ * Name: nxtk_raise
+ *
+ * Description:
+ * Bring the window containing the specified client sub-window to the top
+ * of the display.
+ *
+ * Input parameters:
+ * hfwnd - the window to be raised. This must have been previously created
+ * by nxtk_openwindow().
+ *
+ * Returned value:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+EXTERN int nxtk_raise(NXTKWINDOW hfwnd);
+
+/****************************************************************************
* Name: nxtk_fillwindow
*
* Description:
@@ -191,13 +209,82 @@ EXTERN int nxtk_fillwindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
nxgl_mxpixel_t color[CONFIG_NX_NPLANES]);
/****************************************************************************
+ * Name: nxtk_filltrapwindow
+ *
+ * Description:
+ * Fill the specified rectangle in the client window with the specified color
+ *
+ * Input Parameters:
+ * hfwnd - The window handle returned by nxtk_openwindow
+ * 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
+ *
+ ****************************************************************************/
+
+EXTERN int nxtk_filltrapwindow(NXTKWINDOW hfwnd,
+ FAR const struct nxgl_trapezoid_s *trap,
+ nxgl_mxpixel_t color[CONFIG_NX_NPLANES]);
+
+/****************************************************************************
+ * Name: nxtk_movewindow
+ *
+ * Description:
+ * Move a rectangular region within the client sub-window of a framed window
+ *
+ * Input Parameters:
+ * hfwnd - The client sub-window within which the move is to be done.
+ * This must have been previously created by nxtk_openwindow().
+ * rect - Describes the rectangular region relative to the client
+ * sub-window to move
+ * offset - The offset to move the region
+ *
+ * Return:
+ * OK on success; ERROR on failure with errno set appropriately
+ *
+ ****************************************************************************/
+
+EXTERN int nxtk_movewindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
+ FAR const struct nxgl_point_s *offset);
+
+/****************************************************************************
+ * Name: nxtk_bitmapwindow
+ *
+ * Description:
+ * Copy a rectangular region of a larger image into the rectangle in the
+ * specified client sub-window.
+ *
+ * Input Parameters:
+ * hfwnd The client sub0window that will receive the bitmap image
+ * dest - Describes the rectangular region on in the client sub-window
+ * will receive 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
+ *
+ ****************************************************************************/
+
+EXTERN int nxtk_bitmapwindow(NXTKWINDOW hfwnd,
+ FAR const struct nxgl_rect_s *dest,
+ FAR const void *src[CONFIG_NX_NPLANES],
+ FAR const struct nxgl_point_s *origin,
+ unsigned int stride);
+
+/****************************************************************************
* Name: nxtk_opentoolbar
*
* Description:
* Create a tool bar at the top of the specified framed window
*
* Input Parameters:
- * hwnd - The handle returned by nxtk_openwindow
+ * hfwnd - The handle returned by nxtk_openwindow
* height - The request height of the toolbar in pixels
* cb - Callbacks used to process toolbar events
* arg - User provided value that will be returned with toolbar callbacks.
@@ -208,7 +295,7 @@ EXTERN int nxtk_fillwindow(NXTKWINDOW hfwnd, FAR const struct nxgl_rect_s *rect,
*
****************************************************************************/
-EXTERN NXTKTOOLBAR nxtk_opentoolbar(NXTKWINDOW hwnd, nxgl_coord_t height,
+EXTERN NXTKTOOLBAR nxtk_opentoolbar(NXTKWINDOW hfwnd, nxgl_coord_t height,
FAR const struct nx_callback_s *cb,
FAR void *arg);
@@ -246,6 +333,25 @@ EXTERN void nxtk_closetoolbar(NXTKTOOLBAR htb);
EXTERN int nxtk_filltoolbar(NXTKTOOLBAR htb, FAR const struct nxgl_rect_s *rect,
nxgl_mxpixel_t color[CONFIG_NX_NPLANES]);
+
+/****************************************************************************
+ * Name: nxtk_filltraptoolbar
+ *
+ * Description:
+ * Fill the specified rectangle in the toolbar with the specified color
+ *
+ * Input Parameters:
+ * htb - The window handle returned by nxtk_openwindow
+ * 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
+ *
+ ****************************************************************************/
+
+EXTERN int nxtk_filltraptoolbar(NXTKTOOLBAR htb, FAR const struct nxgl_trapezoid_s *trap,
+ nxgl_mxpixel_t color[CONFIG_NX_NPLANES]);
#undef EXTERN
#if defined(__cplusplus)
}