summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nx/defconfig8
-rwxr-xr-xnuttx/configs/lm3s6965-ek/src/up_oled.c5
-rwxr-xr-xnuttx/drivers/lcd/p14201.c29
-rw-r--r--nuttx/examples/nx/nx_kbdin.c45
-rw-r--r--nuttx/graphics/nxglib/nxglib_fillrun.h6
-rw-r--r--nuttx/graphics/nxtk/nxtk_internal.h4
6 files changed, 73 insertions, 24 deletions
diff --git a/nuttx/configs/lm3s6965-ek/nx/defconfig b/nuttx/configs/lm3s6965-ek/nx/defconfig
index cbc62fa32..14e7338c8 100755
--- a/nuttx/configs/lm3s6965-ek/nx/defconfig
+++ b/nuttx/configs/lm3s6965-ek/nx/defconfig
@@ -560,15 +560,15 @@ CONFIG_NX_DISABLE_8BPP=y
CONFIG_NX_DISABLE_16BPP=y
CONFIG_NX_DISABLE_24BPP=y
CONFIG_NX_DISABLE_32BPP=y
-CONFIG_NX_PACKEDMSFIRST=n
+CONFIG_NX_PACKEDMSFIRST=y
CONFIG_NX_LCDDRIVER=y
CONFIG_LCD_MAXPOWER=1
CONFIG_LCD_MAXCONTRAST=255
CONFIG_NX_MOUSE=y
CONFIG_NX_KBD=y
#CONFIG_NXTK_BORDERWIDTH=4
-#CONFIG_NXTK_BORDERCOLOR1
-#CONFIG_NXTK_BORDERCOLOR2
+CONFIG_NXTK_BORDERCOLOR1=6
+CONFIG_NXTK_BORDERCOLOR2=4
CONFIG_NXTK_AUTORAISE=n
CONFIG_NXFONT_SANS=y
CONFIG_NXFONTS_CHARBITS=7
@@ -697,7 +697,7 @@ CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
# nx_eventnotify(). Default: 4
CONFIG_EXAMPLES_NX_VPLANE=0
CONFIG_EXAMPLES_NX_DEVNO=0
-CONFIG_EXAMPLES_NX_BGCOLOR=4
+CONFIG_EXAMPLES_NX_BGCOLOR=2
CONFIG_EXAMPLES_NX_COLOR1=10
CONFIG_EXAMPLES_NX_COLOR2=12
CONFIG_EXAMPLES_NX_TBCOLOR=8
diff --git a/nuttx/configs/lm3s6965-ek/src/up_oled.c b/nuttx/configs/lm3s6965-ek/src/up_oled.c
index 8c442b0ec..e79b08b34 100755
--- a/nuttx/configs/lm3s6965-ek/src/up_oled.c
+++ b/nuttx/configs/lm3s6965-ek/src/up_oled.c
@@ -47,6 +47,9 @@
#include <nuttx/spi.h>
#include <nuttx/p14201.h>
+#include "lm3s_internal.h"
+#include "lm3s6965ek_internal.h"
+
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -63,7 +66,7 @@
*
************************************************************************************/
-void weak_function lm3s_oledinitialize(void);
+void lm3s_oledinitialize(void)
{
FAR struct spi_dev_s *spi;
int ret;
diff --git a/nuttx/drivers/lcd/p14201.c b/nuttx/drivers/lcd/p14201.c
index abaad4f46..40fd75e4a 100755
--- a/nuttx/drivers/lcd/p14201.c
+++ b/nuttx/drivers/lcd/p14201.c
@@ -124,6 +124,12 @@
# define CONFIG_LCD_MAXPOWER 1
#endif
+/* The leftmost column is contained in bits 7:4 */
+
+#ifndef CONFIG_NX_PACKEDMSFIRST
+# warning "CONFIG_NX_PACKEDMSFIRST needs to be set"
+#endif
+
/* Define the following to enable register-level debug output */
#undef CONFIG_LCD_RITDEBUG
@@ -624,6 +630,10 @@ static inline void rit_clear(FAR struct rit_dev_s *priv)
FAR uint8_t *ptr = g_framebuffer;
unsigned int row;
+ /* Initialize the framebuffer */
+
+ memset(g_framebuffer, (RIT_Y4_BLACK << 4) | RIT_Y4_BLACK, RIT_YRES * RIT_XRES / 2);
+
/* Set a window to fill the entire display */
rit_sndcmd(priv, g_setallcol, sizeof(g_setallcol));
@@ -698,7 +708,7 @@ static int rit_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
/* Get the beginning of the run in the framebuffer */
- run = g_framebuffer + row * RIT_XRES / 2 + start;
+ run = g_framebuffer + row * RIT_XRES / 2;
/* Copy the run into the framebuffer, handling nibble alignment */
@@ -706,14 +716,15 @@ static int rit_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
{
/* Beginning of buffer is properly aligned */
- memcpy(run, buffer, aend - start);
+ memcpy(&run[start], buffer, aend - start);
- /* Handle an final partial byte */
+ /* Handle any final partial byte */
if (aend != end)
{
- /* The leftmost column being contained in bits 7:4 */
-# warning "Missing logic"
+ /* The leftmost column is contained in bits 7:4 */
+
+ run[end] = (run[end] & 0x0f) | (buffer[aend - start] & 0xf0);
}
}
else
@@ -833,8 +844,6 @@ static int rit_getvideoinfo(FAR struct lcd_dev_s *dev,
static int rit_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
FAR struct lcd_planeinfo_s *pinfo)
{
- FAR struct rit_dev_s *priv = (FAR struct rit_dev_s *)dev;
-
DEBUGASSERT(priv && pinfo && planeno == 0);
gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp);
memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s));
@@ -979,12 +988,6 @@ FAR struct lcd_dev_s *rit_initialize(FAR struct spi_dev_s *spi, unsigned int dev
priv->contrast = RIT_CONTRAST;
priv->on = false;
- /* Initialize the framebuffer */
-
-#ifdef CONFIG_P14201_FRAMEBUFFER
- memset(g_framebuffer, (RIT_Y4_BLACK << 4) | RIT_Y4_BLACK, RIT_YRES * RIT_XRES / 2);
-#endif
-
/* Clear the display */
rit_clear(priv);
diff --git a/nuttx/examples/nx/nx_kbdin.c b/nuttx/examples/nx/nx_kbdin.c
index 3088885ba..057f725d2 100644
--- a/nuttx/examples/nx/nx_kbdin.c
+++ b/nuttx/examples/nx/nx_kbdin.c
@@ -154,6 +154,9 @@ nxeg_renderglyph(FAR struct nxeg_state_s *st,
{
FAR struct nxeg_glyph_s *glyph = NULL;
FAR nxgl_mxpixel_t *ptr;
+#if CONFIG_EXAMPLES_NX_BPP < 8
+ nxgl_mxpixel_t pixel;
+#endif
int bmsize;
int row;
int col;
@@ -184,18 +187,54 @@ nxeg_renderglyph(FAR struct nxeg_state_s *st,
{
/* Initialize the glyph memory to the background color */
-#if CONFIG_EXAMPLES_NX_BPP < 8 || CONFIG_EXAMPLES_NX_BPP == 24
-# error "Additional logic is needed here"
-#else
+#if CONFIG_EXAMPLES_NX_BPP < 8
+ pixel = st->color[0];
+# if CONFIG_EXAMPLES_NX_BPP == 1
+ /* Pack 1-bit pixels into a 2-bits */
+
+ pixel &= 0x01;
+ pixel = (pixel) << 1 |pixel;
+# endif
+# if CONFIG_EXAMPLES_NX_BPP < 4
+ /* Pack 2-bit pixels into a nibble */
+
+ pixel &= 0x03;
+ pixel = (pixel) << 2 |pixel;
+# endif
+
+ /* Pack 4-bit nibbles into a byte */
+
+ pixel &= 0x0f;
+ pixel = (pixel) << 4 |pixel;
+
+ ptr = (FAR nxgl_mxpixel_t *)glyph->bitmap;
+ for (row = 0; row < glyph->height; row++)
+ {
+ for (col = 0; col < glyph->stride; col++)
+ {
+ /* Transfer the packed bytes into the buffer */
+
+ *ptr++ = pixel;
+ }
+ }
+
+#elif CONFIG_EXAMPLES_NX_BPP == 24
+# error "Additional logic is needed here for 24bpp support"
+
+#else /* CONFIG_EXAMPLES_NX_BPP = {8,16,32} */
+
ptr = (FAR nxgl_mxpixel_t *)glyph->bitmap;
for (row = 0; row < glyph->height; row++)
{
+ /* Just copy the color value into the glyph memory */
+
for (col = 0; col < glyph->width; col++)
{
*ptr++ = st->color[0];
}
}
#endif
+
/* Then render the glyph into the allocated memory */
ret = RENDERER((FAR nxgl_mxpixel_t*)glyph->bitmap,
diff --git a/nuttx/graphics/nxglib/nxglib_fillrun.h b/nuttx/graphics/nxglib/nxglib_fillrun.h
index d427cd4b3..b1d8a3a7f 100644
--- a/nuttx/graphics/nxglib/nxglib_fillrun.h
+++ b/nuttx/graphics/nxglib/nxglib_fillrun.h
@@ -101,7 +101,7 @@ static inline void nxgl_fillrun_1bpp(FAR uint8_t *run, nxgl_mxpixel_t color,
uint8_t wide = (color & 1) != 0 ? 0xff : 0x00;
/* Fill the run with the color (it is okay to run a fractional byte over
- * the end
+ * the end)
*/
memset(run, wide, nbytes);
@@ -120,7 +120,7 @@ static inline void nxgl_fillrun_2bpp(FAR uint8_t *run, nxgl_mxpixel_t color,
uint8_t wide = g_wide_2bpp[color & 3];
/* Fill the run with the color (it is okay to run a fractional byte over
- * the end
+ * the end)
*/
memset(run, wide, nbytes);
@@ -140,7 +140,7 @@ static inline void nxgl_fillrun_4bpp(FAR uint8_t *run, nxgl_mxpixel_t color,
uint8_t wide = narrow | (narrow << 4);
/* Fill the run with the color (it is okay to run a fractional byte over
- * the end
+ * the end)
*/
memset(run, wide, nbytes);
diff --git a/nuttx/graphics/nxtk/nxtk_internal.h b/nuttx/graphics/nxtk/nxtk_internal.h
index b02bb94ce..fe7792476 100644
--- a/nuttx/graphics/nxtk/nxtk_internal.h
+++ b/nuttx/graphics/nxtk/nxtk_internal.h
@@ -61,6 +61,8 @@
# define CONFIG_NXTK_BORDERCOLOR1 0x00a9a9a9
# elif !defined(CONFIG_NX_DISABLE_16BPP)
# define CONFIG_NXTK_BORDERCOLOR1 0xad55
+# elif !defined(CONFIG_NX_DISABLE_4BPP)
+# define CONFIG_NXTK_BORDERCOLOR1 6
# else
# define CONFIG_NXTK_BORDERCOLOR1 'B'
# endif
@@ -71,6 +73,8 @@
# define CONFIG_NXTK_BORDERCOLOR2 0x00696969
# elif !defined(CONFIG_NX_DISABLE_16BPP)
# define CONFIG_NXTK_BORDERCOLOR2 0x6b4d
+# elif !defined(CONFIG_NX_DISABLE_4BPP)
+# define CONFIG_NXTK_BORDERCOLOR2 4
# else
# define CONFIG_NXTK_BORDERCOLOR2 'b'
# endif