From d890cd67c3ef9e702a71bb5ed2f8a5e9e6d4cfac Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Fri, 24 May 2013 10:00:54 -0600 Subject: Add apps/examples/slcd, Remove USB from STM32L-Discovery, LSE support for the STM32 L family, some STM32L-Discovery LCD debug changes --- apps/ChangeLog.txt | 3 + apps/examples/Kconfig | 1 + apps/examples/Make.defs | 4 + apps/examples/Makefile | 4 +- apps/examples/README.txt | 8 +- apps/examples/slcd/.gitignore | 13 +++ apps/examples/slcd/Kconfig | 26 +++++ apps/examples/slcd/Makefile | 109 ++++++++++++++++++++ apps/examples/slcd/slcd_main.c | 226 +++++++++++++++++++++++++++++++++++++++++ 9 files changed, 391 insertions(+), 3 deletions(-) create mode 100644 apps/examples/slcd/.gitignore create mode 100644 apps/examples/slcd/Kconfig create mode 100644 apps/examples/slcd/Makefile create mode 100644 apps/examples/slcd/slcd_main.c (limited to 'apps') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 474c1fd63..f064a61f6 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -560,3 +560,6 @@ * apps/examples/tcpecho: Added a simple single threaded, poll based TCP echo server based on W. Richard Stevens UNIX Network Programming Book. Contributed by Max Holtberg (2013-5-22). + * apps/examples/slcd: Add an example for testing alphanumeric, + segment LCDs (2013-5-24). + diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig index 97e6ce140..57671ac4c 100644 --- a/apps/examples/Kconfig +++ b/apps/examples/Kconfig @@ -47,6 +47,7 @@ source "$APPSDIR/examples/rgmp/Kconfig" source "$APPSDIR/examples/romfs/Kconfig" source "$APPSDIR/examples/sendmail/Kconfig" source "$APPSDIR/examples/serloop/Kconfig" +source "$APPSDIR/examples/slcd/Kconfig" source "$APPSDIR/examples/flash_test/Kconfig" source "$APPSDIR/examples/smart_test/Kconfig" source "$APPSDIR/examples/smart/Kconfig" diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index 28399192b..bb411d4f8 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -214,6 +214,10 @@ ifeq ($(CONFIG_EXAMPLES_SERLOOP),y) CONFIGURED_APPS += examples/serloop endif +ifeq ($(CONFIG_EXAMPLES_SLCD),y) +CONFIGURED_APPS += examples/slcd +endif + ifeq ($(CONFIG_EXAMPLES_FLASH_TEST),y) CONFIGURED_APPS += examples/flash_test endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 2ffe131c6..906e479ac 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -41,7 +41,7 @@ SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf SUBDIRS += flash_test ftpc ftpd hello helloxx hidkbd igmp json keypadtest SUBDIRS += lcdrw mm modbus mount mtdpart nettest nsh null nx nxconsole nxffs SUBDIRS += nxflat nxhello nximage nxlines nxtext ostest pashello pipe poll -SUBDIRS += posix_spawn pwm qencoder relays rgmp romfs sendmail serloop +SUBDIRS += posix_spawn pwm qencoder relays rgmp romfs sendmail serloop slcd SUBDIRS += smart smart_test tcpecho telnetd thttpd tiff touchscreen udp uip SUBDIRS += usbserial usbstorage usbterm watchdog wget wgetjson xmlrpc @@ -60,7 +60,7 @@ CNTXTDIRS = pwm ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover flash_test ftpd CNTXTDIRS += hello helloxx json keypadtestmodbus mtdpart nettest nxlines relays -CNTXTDIRS += qencoder smart_test tcpecho telnetd watchdog wgetjson +CNTXTDIRS += qencoder slcd smart_test tcpecho telnetd watchdog wgetjson endif ifeq ($(CONFIG_EXAMPLES_LCDRW_BUILTIN),y) diff --git a/apps/examples/README.txt b/apps/examples/README.txt index ac922a703..2e1454b3f 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -1469,13 +1469,19 @@ examples/serloop Use C buffered I/O (getchar/putchar) vs. raw console I/O (read/read). +examples/slcd +^^^^^^^^^^^^^ + A simple test of alphanumeric, segment LCDs (SLCDs). + + * CONFIG_EXAMPLES_SLCD - Enable the SLCD test + examples/smart ^^^^^^^^^^^^^^ This is a test of the SMART file systemt that derives from examples/nxffs. - * CONFIG_EXAMPLES_SMART: -Enable the SMART file system example + * CONFIG_EXAMPLES_SMART: - Enable the SMART file system example * CONFIG_EXAMPLES_SMART_ARCHINIT: The default is to use the RAM MTD device at drivers/mtd/rammtd.c. But an architecture-specific MTD driver can be used instead by defining CONFIG_EXAMPLES_SMART_ARCHINIT. In diff --git a/apps/examples/slcd/.gitignore b/apps/examples/slcd/.gitignore new file mode 100644 index 000000000..4480560f5 --- /dev/null +++ b/apps/examples/slcd/.gitignore @@ -0,0 +1,13 @@ +Make.dep +.depend +.built +*.swp +*.asm +*.rel +*.lst +*.sym +*.adb +*.lib +*.src + + diff --git a/apps/examples/slcd/Kconfig b/apps/examples/slcd/Kconfig new file mode 100644 index 000000000..5f56827fc --- /dev/null +++ b/apps/examples/slcd/Kconfig @@ -0,0 +1,26 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config EXAMPLES_SLCD + bool "Segment LCD test" + default n + ---help--- + Enables a simple test of an alphanumer, segment LCD + +if EXAMPLES_SLCD + +config EXAMPLES_SLCD_DEVNAME + string "SLCD device path" + default "/dev/slcd" + ---help--- + The full path to the SLCD device to be tested + +config EXAMPLES_SLCD_BUFSIZE + int "I/O buffer size" + default 64 + ---help--- + The size of the I/O buffer to use in the test (not a critical setting) + +endif diff --git a/apps/examples/slcd/Makefile b/apps/examples/slcd/Makefile new file mode 100644 index 000000000..c7ac96950 --- /dev/null +++ b/apps/examples/slcd/Makefile @@ -0,0 +1,109 @@ +############################################################################ +# apps/examples/slcd/Makefile +# +# Copyright (C) 2013 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# Hello, World! built-in application info + +APPNAME = slcd +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +# Hello, World! Example + +ASRCS = +CSRCS = slcd_main.c + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + BIN = ..\..\libapps$(LIBEXT) +else +ifeq ($(WINTOOL),y) + BIN = ..\\..\\libapps$(LIBEXT) +else + BIN = ../../libapps$(LIBEXT) +endif +endif + +ROOTDEPPATH = --dep-path . + +# Common build + +VPATH = + +all: .built +.PHONY: clean depend distclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +.built: $(OBJS) + $(call ARCHIVE, $(BIN), $(OBJS)) + @touch .built + +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) +$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat: $(DEPCONFIG) Makefile + $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main) + +context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat +else +context: +endif + +.depend: Makefile $(SRCS) + @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + $(call DELFILE, .built) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/apps/examples/slcd/slcd_main.c b/apps/examples/slcd/slcd_main.c new file mode 100644 index 000000000..8cc88c6fc --- /dev/null +++ b/apps/examples/slcd/slcd_main.c @@ -0,0 +1,226 @@ +/**************************************************************************** + * examples/clcd/slcd_main.c + * + * Copyright (C) 2013 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef EXAMPLES_SLCD_DEVNAME +# define EXAMPLES_SLCD_DEVNAME "/dev/slcd" +#endif + +/**************************************************************************** + * Private Typs + ****************************************************************************/ +/* All state information for this test is kept within the following structure + * in order create a namespace and to minimize the possibility of name + * collisions. + */ + +struct slcd_test_s +{ + struct lib_outstream_s stream; /* Stream to use for all output */ + struct slcd_geometry_s geo; /* Size of the SLCD (rows x columns) */ + int fd; /* File descriptor or the open SLCD device */ + + /* The I/O buffer */ + + char buffer[CONFIG_EXAMPLES_SLCD_BUFSIZE]; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct slcd_test_s g_slcdtest; +static const char g_slcdhello[] = "hello"; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: slcd_putc + ****************************************************************************/ + +static int slcd_flush(FAR struct lib_outstream_s *stream) +{ + FAR struct slcd_test_s *priv = (FAR struct slcd_test_s *)stream; + ssize_t nwritten; + ssize_t remaining; + + /* Loop until all bytes were written (handling both partial and interrupted + * writes). + */ + + remaining = stream->nput; + while (remaining > 0); + { + nwritten = write(priv->fd, priv->buffer, remaining); + if (nwritten < 0) + { + int errcode = errno; + printf("write failed: %d\n", errcode); + + if (errcode != EINTR) + { + exit(EXIT_FAILURE); + } + } + else + { + remaining -= nwritten; + } + } + + /* Reset the stream */ + + stream->nput = 0; + return OK; +} + +/**************************************************************************** + * Name: slcd_putc + ****************************************************************************/ + +static void slcd_putc(FAR struct lib_outstream_s *stream, int ch) +{ + FAR struct slcd_test_s *priv = (FAR struct slcd_test_s *)stream; + + /* Write the character to the buffer */ + + priv->buffer[stream->nput] = ch; + stream->nput++; + priv->buffer[stream->nput] = '\0'; + + /* If the buffer is full, flush it */ + + if (stream->nput >=- CONFIG_EXAMPLES_SLCD_BUFSIZE) + { + (void)slcd_flush(stream); + } +} + +/**************************************************************************** + * Name: slcd_puts + ****************************************************************************/ + +static void slcd_puts(FAR struct lib_outstream_s *outstream, + FAR const char *str) +{ + for (; *str; str++) + { + slcd_put((int)*str, outstream); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * slcd_main + ****************************************************************************/ + +int slcd_main(int argc, char *argv[]) +{ + FAR struct slcd_test_s *priv = &g_slcdtest; + int ret; + + /* Initialize the output stream */ + + memset(priv, 0, sizeof(struct slcd_test_s)); + priv->stream.put = slcd_putc; +#ifdef CONFIG_STDIO_LINEBUFFER + priv->stream.flush = lib_noflush; +#endif + + /* Open the SLCD device */ + + printf("Opening %s for read/write access\n", EXAMPLES_SLCD_DEVNAME); + + priv->fd = open(EXAMPLES_SLCD_DEVNAME, O_RDWR); + if (priv->fd < 0) + { + printf("Failed to open %s: %d\n", EXAMPLES_SLCD_DEVNAME, errno); + goto errout; + } + + /* Get the geometry of the SCLD device */ + + ret = ioctl(priv->fd, SLCDIOC_GEOMETRY, (unsigned long)&priv->geo); + if (ret < 0) + { + printf("Failed to open %s: %d\n", EXAMPLES_SLCD_DEVNAME, errno); + goto errout_with_fd; + } + + printf("Geometry rows: %d columns: %d\n", + priv->geo.nrows, priv->geo.ncolumns); + + /* Home the cursor and clear the display */ + + slcd_encode(SLCDCODE_CLEAR, 0, &priv->stream); + + /* Say hello */ + + slcd_puts(&priv->stream, g_slcdhello); + + /* Normal exit */ + + close(priv->fd); + return 0; + +errout_with_fd: + close(priv->fd); +errout: + exit(EXIT_FAILURE); +} -- cgit v1.2.3