summaryrefslogtreecommitdiff
path: root/nuttx/graphics
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/graphics')
-rw-r--r--nuttx/graphics/nxbe/nxbe.h2
-rw-r--r--nuttx/graphics/nxbe/nxbe_setsize.c15
-rw-r--r--nuttx/graphics/nxglib/Make.defs2
-rw-r--r--nuttx/graphics/nxglib/nxglib_copyrectangle.c4
-rw-r--r--nuttx/graphics/nxglib/nxglib_fillrectangle.c4
-rw-r--r--nuttx/graphics/nxglib/nxglib_filltrapezoid.c4
-rw-r--r--nuttx/graphics/nxglib/nxglib_moverectangle.c4
-rw-r--r--nuttx/graphics/nxglib/nxglib_rectsize.c83
-rw-r--r--nuttx/graphics/nxmu/nx_setsize.c9
-rw-r--r--nuttx/graphics/nxmu/nxfe.h4
-rw-r--r--nuttx/graphics/nxmu/nxmu_reportposition.c12
-rw-r--r--nuttx/graphics/nxmu/nxmu_server.c2
-rw-r--r--nuttx/graphics/nxsu/nx_setsize.c2
-rw-r--r--nuttx/graphics/nxsu/nxsu_reportposition.c6
-rw-r--r--nuttx/graphics/nxtk/nxtk_events.c25
-rw-r--r--nuttx/graphics/nxtk/nxtk_setsize.c10
-rw-r--r--nuttx/graphics/nxtk/nxtk_setsubwindows.c6
17 files changed, 137 insertions, 57 deletions
diff --git a/nuttx/graphics/nxbe/nxbe.h b/nuttx/graphics/nxbe/nxbe.h
index bcfcb3e25..e4b3a923d 100644
--- a/nuttx/graphics/nxbe/nxbe.h
+++ b/nuttx/graphics/nxbe/nxbe.h
@@ -261,7 +261,7 @@ EXTERN void nxbe_setposition(FAR struct nxbe_window_s *wnd,
****************************************************************************/
EXTERN void nxbe_setsize(FAR struct nxbe_window_s *wnd,
- FAR const struct nxgl_rect_s *size);
+ FAR const struct nxgl_size_s *size);
/****************************************************************************
* Name: nxbe_raise
diff --git a/nuttx/graphics/nxbe/nxbe_setsize.c b/nuttx/graphics/nxbe/nxbe_setsize.c
index 77e9653d7..3873807d9 100644
--- a/nuttx/graphics/nxbe/nxbe_setsize.c
+++ b/nuttx/graphics/nxbe/nxbe_setsize.c
@@ -79,7 +79,7 @@
****************************************************************************/
void nxbe_setsize(FAR struct nxbe_window_s *wnd,
- FAR const struct nxgl_rect_s *size)
+ FAR const struct nxgl_size_s *size)
{
struct nxgl_rect_s bounds;
@@ -96,7 +96,12 @@ void nxbe_setsize(FAR struct nxbe_window_s *wnd,
/* Add the window origin to supplied size get the new window bounding box */
- nxgl_rectoffset(&wnd->bounds, size, wnd->origin.x, wnd->origin.y);
+ wnd->bounds.pt2.x = wnd->bounds.pt1.x + size->w - 1;
+ wnd->bounds.pt2.y = wnd->bounds.pt1.y + size->h - 1;
+
+ /* Clip the new bounding box so that lies within the background screen */
+
+ nxgl_rectintersect(&wnd->bounds, &wnd->bounds, &wnd->be->bkgd.bounds);
/* We need to update the larger of the two rectangles. That will be the
* union of the before and after sizes.
@@ -104,12 +109,6 @@ void nxbe_setsize(FAR struct nxbe_window_s *wnd,
nxgl_rectunion(&bounds, &bounds, &wnd->bounds);
- /* Clip the bounding box so that is lies with the screen defined by the
- * background window.
- */
-
- nxgl_rectintersect(&bounds, &bounds, &wnd->be->bkgd.bounds);
-
/* Then redraw this window AND all windows below it. Having resized the
* window, we may have exposed previoulsy obscured portions of windows
* below this one.
diff --git a/nuttx/graphics/nxglib/Make.defs b/nuttx/graphics/nxglib/Make.defs
index 1c66d85a8..86b086e8c 100644
--- a/nuttx/graphics/nxglib/Make.defs
+++ b/nuttx/graphics/nxglib/Make.defs
@@ -54,7 +54,7 @@ RCOPY2_CSRCS = nxglib_copyrectangle_8bpp.c nxglib_copyrectangle_16bpp.c \
RECT_CSRCS = nxglib_rectcopy.c nxglib_rectoffset.c nxglib_vectoradd.c \
nxglib_vectsubtract.c nxglib_rectintersect.c \
nxglib_nonintersecting.c nxglib_rectunion.c nxglib_rectinside.c \
- nxglib_rectoverlap.c nxglib_nullrect.c
+ nxglib_rectoverlap.c nxglib_rectsize.c nxglib_nullrect.c
TRAP_CSRCS = nxglib_runoffset.c nxglib_runcopy.c \
nxglib_trapoffset.c nxglib_trapcopy.c
COLOR_CSRCS = nxglib_colorcopy.c
diff --git a/nuttx/graphics/nxglib/nxglib_copyrectangle.c b/nuttx/graphics/nxglib/nxglib_copyrectangle.c
index 1feb0c7a9..8a13260c6 100644
--- a/nuttx/graphics/nxglib/nxglib_copyrectangle.c
+++ b/nuttx/graphics/nxglib/nxglib_copyrectangle.c
@@ -104,8 +104,8 @@ void NXGL_FUNCNAME(nxgl_copyrectangle,NXGLIB_SUFFIX)
/* Get the dimensions of the rectange to fill: height in rows and width in bytes */
- width = NXGL_SCALEX(dest->pt2.x - dest->pt1.x);
- rows = dest->pt2.y - dest->pt1.y;
+ width = NXGL_SCALEX(dest->pt2.x - dest->pt1.x + 1);
+ rows = dest->pt2.y - dest->pt1.y + 1;
#if NXGLIB_BITSPERPIXEL < 8
# ifdef CONFIG_NXGL_PACKEDMSFIRST
diff --git a/nuttx/graphics/nxglib/nxglib_fillrectangle.c b/nuttx/graphics/nxglib/nxglib_fillrectangle.c
index 2ed923b95..ee8b6dd01 100644
--- a/nuttx/graphics/nxglib/nxglib_fillrectangle.c
+++ b/nuttx/graphics/nxglib/nxglib_fillrectangle.c
@@ -104,8 +104,8 @@ void NXGL_FUNCNAME(nxgl_fillrectangle,NXGLIB_SUFFIX)
/* Get the dimensions of the rectange to fill in pixels */
- width = rect->pt2.x - rect->pt1.x;
- rows = rect->pt2.y - rect->pt1.y;
+ width = rect->pt2.x - rect->pt1.x + 1;
+ rows = rect->pt2.y - rect->pt1.y + 1;
/* Get the address of the first byte in the first line to write */
diff --git a/nuttx/graphics/nxglib/nxglib_filltrapezoid.c b/nuttx/graphics/nxglib/nxglib_filltrapezoid.c
index ff7eb492b..231671735 100644
--- a/nuttx/graphics/nxglib/nxglib_filltrapezoid.c
+++ b/nuttx/graphics/nxglib/nxglib_filltrapezoid.c
@@ -125,8 +125,8 @@ void NXGL_FUNCNAME(nxgl_filltrapezoid,NXGLIB_SUFFIX)(
/* Calculate the slope of the left and right side of the trapezoid */
- dx1dy = b16divi((trap->bot.x1 - x1), nrows);
- dx2dy = b16divi((trap->bot.x2 - x2), nrows);
+ dx1dy = b16divi((trap->bot.x1 - x1), nrows - 1);
+ dx2dy = b16divi((trap->bot.x2 - x2), nrows - 1);
/* Perform vertical clipping */
diff --git a/nuttx/graphics/nxglib/nxglib_moverectangle.c b/nuttx/graphics/nxglib/nxglib_moverectangle.c
index b9579e3f5..c39c1c560 100644
--- a/nuttx/graphics/nxglib/nxglib_moverectangle.c
+++ b/nuttx/graphics/nxglib/nxglib_moverectangle.c
@@ -147,8 +147,8 @@ void NXGL_FUNCNAME(nxgl_moverectangle,NXGLIB_SUFFIX)
/* Get the dimensions of the rectange to fill: height in rows and width in bytes */
- width = NXGL_SCALEX(rect->pt2.x - rect->pt1.x);
- rows = rect->pt2.y - rect->pt1.y;
+ width = NXGL_SCALEX(rect->pt2.x - rect->pt1.x + 1);
+ rows = rect->pt2.y - rect->pt1.y + 1;
#if NXGLIB_BITSPERPIXEL < 8
# ifdef CONFIG_NXGL_PACKEDMSFIRST
diff --git a/nuttx/graphics/nxglib/nxglib_rectsize.c b/nuttx/graphics/nxglib/nxglib_rectsize.c
new file mode 100644
index 000000000..f41a7b9c9
--- /dev/null
+++ b/nuttx/graphics/nxglib/nxglib_rectsize.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * graphics/nxglib/nxglib_rectsize.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 <nuttx/fb.h>
+#include <nuttx/nxglib.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxgl_rectsize
+ *
+ * Description:
+ * Return the size of the specified rectangle.
+ *
+ ****************************************************************************/
+
+void nxgl_rectsize(FAR struct nxgl_size_s *size,
+ FAR const struct nxgl_rect_s *rect)
+{
+ size->w = rect->pt2.x - rect->pt1.x + 1;
+ size->h = rect->pt2.y - rect->pt1.y + 1;
+}
diff --git a/nuttx/graphics/nxmu/nx_setsize.c b/nuttx/graphics/nxmu/nx_setsize.c
index eeff5969e..36169a222 100644
--- a/nuttx/graphics/nxmu/nx_setsize.c
+++ b/nuttx/graphics/nxmu/nx_setsize.c
@@ -85,7 +85,7 @@
*
****************************************************************************/
-int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_rect_s *size)
+int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_size_s *size)
{
FAR struct nxbe_window_s *wnd = (FAR struct nxbe_window_s *)hwnd;
struct nxsvrmsg_setsize_s outmsg;
@@ -101,9 +101,10 @@ int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_rect_s *size)
/* Then inform the server of the changed position */
- outmsg.msgid = NX_SVRMSG_SETSIZE;
- outmsg.wnd = wnd;
- nxgl_rectcopy(&outmsg.size, size);
+ outmsg.msgid = NX_SVRMSG_SETSIZE;
+ outmsg.wnd = wnd;
+ outmsg.size.w = size->w;
+ outmsg.size.h = size->h;
ret = mq_send(wnd->conn->cwrmq, &outmsg, sizeof(struct nxsvrmsg_setsize_s), NX_SVRMSG_PRIO);
if (ret < 0)
diff --git a/nuttx/graphics/nxmu/nxfe.h b/nuttx/graphics/nxmu/nxfe.h
index d5cf3279c..e036bf675 100644
--- a/nuttx/graphics/nxmu/nxfe.h
+++ b/nuttx/graphics/nxmu/nxfe.h
@@ -217,7 +217,7 @@ 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_size_s size; /* The current window size */
FAR struct nxgl_point_s pos; /* The current window position */
FAR struct nxgl_rect_s bounds; /* Size of screen */
};
@@ -307,7 +307,7 @@ 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 */
+ FAR struct nxgl_size_s size; /* The new window size */
};
/* This message informs the server that the size or position of the window has changed */
diff --git a/nuttx/graphics/nxmu/nxmu_reportposition.c b/nuttx/graphics/nxmu/nxmu_reportposition.c
index ed72ca52f..7f8ebb3b7 100644
--- a/nuttx/graphics/nxmu/nxmu_reportposition.c
+++ b/nuttx/graphics/nxmu/nxmu_reportposition.c
@@ -86,14 +86,12 @@ void nxfe_reportposition(FAR struct nxbe_window_s *wnd)
/* 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;
+ outmsg.msgid = NX_CLIMSG_NEWPOSITION;
+ outmsg.wnd = wnd;
+ outmsg.pos.x = wnd->origin.x;
+ outmsg.pos.y = wnd->origin.y;
- /* Convert the window bounding box to a window-relative rectangle */
-
- nxgl_rectoffset(&outmsg.size, &wnd->bounds, -wnd->origin.x, -wnd->origin.y);
+ nxgl_rectsize(&outmsg.size, &wnd->bounds);
/* Provide the background window bounding box which is the screen limits
* It must always have (0,0) as its origin
diff --git a/nuttx/graphics/nxmu/nxmu_server.c b/nuttx/graphics/nxmu/nxmu_server.c
index 113eafe2c..5a592eec7 100644
--- a/nuttx/graphics/nxmu/nxmu_server.c
+++ b/nuttx/graphics/nxmu/nxmu_server.c
@@ -430,7 +430,7 @@ int nx_runinstance(FAR const char *mqname, FAR struct fb_vtable_s *fb)
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);
+ nxbe_lower(lowermsg->wnd);
}
break;
diff --git a/nuttx/graphics/nxsu/nx_setsize.c b/nuttx/graphics/nxsu/nx_setsize.c
index fdacc4741..c15150ae1 100644
--- a/nuttx/graphics/nxsu/nx_setsize.c
+++ b/nuttx/graphics/nxsu/nx_setsize.c
@@ -85,7 +85,7 @@
*
****************************************************************************/
-int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_rect_s *size)
+int nx_setsize(NXWINDOW hwnd, FAR struct nxgl_size_s *size)
{
#ifdef CONFIG_DEBUG
if (!hwnd || !size)
diff --git a/nuttx/graphics/nxsu/nxsu_reportposition.c b/nuttx/graphics/nxsu/nxsu_reportposition.c
index 9ad8197e6..972986f9d 100644
--- a/nuttx/graphics/nxsu/nxsu_reportposition.c
+++ b/nuttx/graphics/nxsu/nxsu_reportposition.c
@@ -81,7 +81,7 @@
void nxfe_reportposition(FAR struct nxbe_window_s *wnd)
{
FAR struct nxbe_state_s *be = wnd->be;
- struct nxgl_rect_s rect;
+ struct nxgl_size_s size;
#ifdef CONFIG_DEBUG
if (!wnd)
@@ -96,9 +96,9 @@ void nxfe_reportposition(FAR struct nxbe_window_s *wnd)
if (wnd->cb->position)
{
- /* Convert the frame rectangle to a window-relative rectangle */
+ /* Get the size of the bounding rectangle */
- nxgl_rectoffset(&rect, &wnd->bounds, -wnd->origin.x, -wnd->origin.y);
+ nxgl_rectsize(&size, &wnd->bounds);
/* And provide this to the client */
diff --git a/nuttx/graphics/nxtk/nxtk_events.c b/nuttx/graphics/nxtk/nxtk_events.c
index 1ecb87524..f8ec80ea0 100644
--- a/nuttx/graphics/nxtk/nxtk_events.c
+++ b/nuttx/graphics/nxtk/nxtk_events.c
@@ -63,7 +63,7 @@
static void nxtk_redraw(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect,
boolean morem, FAR void *arg);
-static void nxtk_position(NXWINDOW hwnd, FAR const struct nxgl_rect_s *size,
+static void nxtk_position(NXWINDOW hwnd, FAR const struct nxgl_size_s *size,
FAR const struct nxgl_point_s *pos,
FAR const struct nxgl_rect_s *bounds,
FAR void *arg);
@@ -155,37 +155,38 @@ static void nxtk_redraw(NXWINDOW hwnd, FAR const struct nxgl_rect_s *rect,
* Name: nxtk_position
****************************************************************************/
-static void nxtk_position(NXWINDOW hwnd, FAR const struct nxgl_rect_s *size,
+static void nxtk_position(NXWINDOW hwnd, FAR const struct nxgl_size_s *size,
FAR const struct nxgl_point_s *pos,
FAR const struct nxgl_rect_s *bounds,
FAR void *arg)
{
FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hwnd;
- struct nxgl_rect_s relrect;
+ struct nxgl_size_s subwindowsize;
- gvdbg("nxtk_position: hwnd=%p size={(%d,%d),(%d,%d)} pos=(%d,%d) bounds={(%d,%d),(%d,%d)}\n",
- hwnd, size->pt1.x, size->pt1.y, size->pt2.x, size->pt2.y,
- pos->x, pos->y,
+ gvdbg("nxtk_position: hwnd=%p size=(%d,%d) pos=(%d,%d) bounds={(%d,%d),(%d,%d)}\n",
+ hwnd, size->w, size->w, pos->x, pos->y,
bounds->pt1.x, bounds->pt1.y, bounds->pt2.x, bounds->pt2.y);
/* Recalculate the dimensions of the toolbar and client windows */
nxtk_setsubwindows(fwnd);
- /* Report the size position of the client sub-window */
+ /* Report the size / position of the client sub-window */
if (fwnd->fwcb->position)
{
- nxgl_rectoffset(&relrect, &fwnd->fwrect, fwnd->fwrect.pt1.x, fwnd->fwrect.pt1.y);
- fwnd->fwcb->position((NXTKWINDOW)fwnd, &relrect, &fwnd->fwrect.pt1, bounds, fwnd->fwarg);
+ nxgl_rectsize(&subwindowsize, &fwnd->fwrect);
+ fwnd->fwcb->position((NXTKWINDOW)fwnd, &subwindowsize,
+ &fwnd->fwrect.pt1, bounds, fwnd->fwarg);
}
- /* Report the size position of the toolbar sub-window */
+ /* Report the size / position of the toolbar sub-window */
if (fwnd->tbcb && fwnd->tbcb->position)
{
- nxgl_rectoffset(&relrect, &fwnd->tbrect, fwnd->tbrect.pt1.x, fwnd->tbrect.pt1.y);
- fwnd->tbcb->position((NXTKWINDOW)fwnd, &relrect, &fwnd->fwrect.pt1, bounds, fwnd->tbarg);
+ nxgl_rectsize(&subwindowsize, &fwnd->tbrect);
+ fwnd->tbcb->position((NXTKWINDOW)fwnd, &subwindowsize,
+ &fwnd->tbrect.pt1, bounds, fwnd->tbarg);
}
}
diff --git a/nuttx/graphics/nxtk/nxtk_setsize.c b/nuttx/graphics/nxtk/nxtk_setsize.c
index a72e8f883..e2917fc34 100644
--- a/nuttx/graphics/nxtk/nxtk_setsize.c
+++ b/nuttx/graphics/nxtk/nxtk_setsize.c
@@ -91,10 +91,10 @@
*
****************************************************************************/
-int nxtk_setsize(NXTKWINDOW hfwnd, FAR struct nxgl_rect_s *size)
+int nxtk_setsize(NXTKWINDOW hfwnd, FAR struct nxgl_size_s *size)
{
FAR struct nxtk_framedwindow_s *fwnd = (FAR struct nxtk_framedwindow_s *)hfwnd;
- struct nxgl_rect_s newsize;
+ struct nxgl_size_s newsize;
#ifdef CONFIG_DEBUG
if (!hfwnd || !size)
@@ -106,10 +106,8 @@ int nxtk_setsize(NXTKWINDOW hfwnd, FAR struct nxgl_rect_s *size)
/* Add the sizes need for the toolbar and the borders */
- newsize.pt1.x = 0;
- newsize.pt1.y = 0;
- newsize.pt2.x = size->pt2.x + 2 * CONFIG_NXTK_BORDERWIDTH;
- newsize.pt2.y = size->pt2.y + fwnd->tbheight + 2 * CONFIG_NXTK_BORDERWIDTH;
+ newsize.w = size->w + 2 * CONFIG_NXTK_BORDERWIDTH;
+ newsize.h = size->w + fwnd->tbheight + 2 * CONFIG_NXTK_BORDERWIDTH;
/* Then set the window size */
diff --git a/nuttx/graphics/nxtk/nxtk_setsubwindows.c b/nuttx/graphics/nxtk/nxtk_setsubwindows.c
index 443fa92c3..57c280c73 100644
--- a/nuttx/graphics/nxtk/nxtk_setsubwindows.c
+++ b/nuttx/graphics/nxtk/nxtk_setsubwindows.c
@@ -142,7 +142,7 @@ void nxtk_setsubwindows(FAR struct nxtk_framedwindow_s *fwnd)
/* Divide up the horizontal dimensions of the window */
- fullwidth = fwnd->wnd.bounds.pt2.x - fwnd->wnd.bounds.pt1.x;
+ fullwidth = fwnd->wnd.bounds.pt2.x - fwnd->wnd.bounds.pt1.x + 1;
bdrwidth = ngl_min(2 * CONFIG_NXTK_BORDERWIDTH, fullwidth);
fwwidth = fullwidth - bdrwidth;
fwleft = fwnd->wnd.origin.x + bdrwidth/2;
@@ -151,11 +151,11 @@ void nxtk_setsubwindows(FAR struct nxtk_framedwindow_s *fwnd)
fwnd->tbrect.pt1.x = fwleft;
fwnd->tbrect.pt1.y = tbtop;
- fwnd->tbrect.pt2.x = fwleft + fwwidth;
+ fwnd->tbrect.pt2.x = fwleft + fwwidth - 1;
fwnd->tbrect.pt2.y = tbtop + tbheight - 1;
fwnd->fwrect.pt1.x = fwleft;
fwnd->fwrect.pt1.y = fwtop;
- fwnd->fwrect.pt2.x = fwleft + fwwidth;
+ fwnd->fwrect.pt2.x = fwleft + fwwidth - 1;
fwnd->fwrect.pt2.y = fwtop + fwheight - 1;
}