From ee2220174467b0e456446f5faaef1bd1660f786e Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 14 Mar 2011 14:14:54 +0000 Subject: VSN/apps update git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3378 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 10 ++ apps/Makefile | 17 +- apps/README.txt | 12 +- apps/hello/hello.c | 32 +++- nuttx/ChangeLog | 7 +- nuttx/arch/arm/src/stm32/stm32_gpio.c | 205 +++++++++++----------- nuttx/arch/arm/src/stm32/stm32_gpio.h | 4 +- nuttx/arch/arm/src/stm32/stm32_internal.h | 22 ++- nuttx/configs/vsn/include/board.h | 33 ++-- nuttx/configs/vsn/include/power.h | 71 ++++++++ nuttx/configs/vsn/nsh/defconfig | 45 +++-- nuttx/configs/vsn/src/README.txt | 10 ++ nuttx/configs/vsn/src/boot.c | 216 +++++++++++------------ nuttx/configs/vsn/src/leds.c | 18 +- nuttx/configs/vsn/src/power.c | 48 +++++- nuttx/configs/vsn/src/ramtron.c | 7 +- nuttx/configs/vsn/src/sysclock.c | 13 ++ nuttx/configs/vsn/src/vsn.h | 276 +++++++++++++++--------------- nuttx/drivers/net/slip.c | 4 + nuttx/examples/nsh/nsh.h | 3 +- nuttx/examples/nsh/nsh_apps.c | 7 +- 21 files changed, 635 insertions(+), 425 deletions(-) create mode 100755 apps/ChangeLog.txt create mode 100644 nuttx/configs/vsn/include/power.h diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt new file mode 100755 index 000000000..399e4c852 --- /dev/null +++ b/apps/ChangeLog.txt @@ -0,0 +1,10 @@ +5.19 2011-03-12 Gregory Nutt + + * Initial version of the apps/ directory was released as contributed by + Uros Platise. + +5.20 2011-xx-xx Gregory Nutt + + * README cosmetics + * hello world minor changes + * Makefile cosmetics (I am slowly adding the Darjeeling JVM) \ No newline at end of file diff --git a/apps/Makefile b/apps/Makefile index ac07176fb..40cae5a40 100644 --- a/apps/Makefile +++ b/apps/Makefile @@ -42,21 +42,28 @@ endif # Application Directories -BUILTIN_APPS_DIR = +# we use a non-existing .built_always to guarantee that Makefile +# always walks into the sub-directories and asks for build BUILTIN_APPS_BUILT = +BUILTIN_APPS_DIR = ifeq ($(CONFIG_BUILTIN_APPS_NUTTX),y) # Individual application: HELLO ifeq ($(CONFIG_BUILTIN_APPS_HELLO),y) - BUILTIN_APPS_DIR += hello - -# we use a non-existing .built_always to guarantee that Makefile -# always walks into the sub-directories and asks for build BUILTIN_APPS_BUILT += hello/.built_always +endif + +ifeq ($(CONFIG_BUILTIN_APPS_POWEROFF),y) +BUILTIN_APPS_DIR += poweroff +BUILTIN_APPS_BUILT += poweroff/.built_always +endif +ifeq ($(CONFIG_BUILTIN_APPS_JVM),y) +BUILTIN_APPS_DIR += jvm +BUILTIN_APPS_BUILT += jvm/.built_always endif # end of application list diff --git a/apps/README.txt b/apps/README.txt index e7bb212e4..1eda70f9a 100644 --- a/apps/README.txt +++ b/apps/README.txt @@ -5,11 +5,11 @@ Application Folder This folder provides various applications found in sub-directories. Application entry points with their requirements are gathered together in -this folder, in two files: +in two files: - exec_nuttapp_proto.h Entry points, prototype function - exec_nuttapp_list.h Application specific information and requirements -Application information is collected during the make .depend process. +Information is collected during the make .depend process. To execute an application function: exec_nuttapp() is defined in the include/nuttx/nuttapp.h @@ -19,7 +19,7 @@ following option is enabled: CONFIG_EXAMPLES_NSH_BUILTIN_APPS=y To select which application to be included in the build process set your -preferences the nuttx/.config file as: +preferences in the nuttx/.config file as: To include applications under the nuttx apps directory: CONFIG_BUILTIN_APPS_NUTTX=y/n @@ -30,9 +30,9 @@ where each application can be controlled as: When the user defines an option: CONFIG_BUILTIN_APP_START= -Note that application name must be provided in ".." as: "hello" -for the hello application, which starts the immediately after system -starts: +that application shall be invoked immediately after system starts. +Note that application name must be provided in ".." as: "hello", +will call: int hello_main(int argc, char *argv[]) Application skeleton can be found under the hello sub-directory, diff --git a/apps/hello/hello.c b/apps/hello/hello.c index d7818d351..fb94d0ea9 100644 --- a/apps/hello/hello.c +++ b/apps/hello/hello.c @@ -34,6 +34,24 @@ ****************************************************************************/ #include +#include + + +void memtest(void) +{ + char *p; + int i, j; + + for (i=0; i<1000; i++) { + p = malloc(40000); + if (!p) { + printf("No memory\n"); + break; + } + for (j=0; j<40000; j++) p[j] = 0; + free(p); + } +} /** Example of a standalone application @@ -41,7 +59,17 @@ int hello_main(int argc, char *argv[]) { int i; - printf("Hello Builtin Application\nFound argc=%d arguments and are as follows:\n", argc); - for (i=0; i> GPIO_PORT_SHIFT; - if (port < STM32_NGPIO_PORTS) + if (port >= STM32_NGPIO_PORTS) { - /* Get the port base address */ + return ERROR; + } + + /* Get the port base address */ - base = g_gpiobase[port]; + base = g_gpiobase[port]; - /* Get the pin number and select the port configuration register for that pin */ + /* Get the pin number and select the port configuration register for that + * pin + */ - pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; - if (pin < 8) - { - cr = base + STM32_GPIO_CRL_OFFSET; - pos = pin; - } - else - { - cr = base + STM32_GPIO_CRH_OFFSET; - pos = pin - 8; - } + pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT; + if (pin < 8) + { + cr = base + STM32_GPIO_CRL_OFFSET; + pos = pin; + } + else + { + cr = base + STM32_GPIO_CRH_OFFSET; + pos = pin - 8; + } - /* Input or output? */ + /* Input or output? */ - input = ((cfgset & GPIO_INPUT) != 0); + input = ((cfgset & GPIO_INPUT) != 0); - /* Decode the mode and configuration */ + /* Decode the mode and configuration */ - if (input) - { - /* Input.. force mode = INPUT */ + if (input) + { + /* Input.. force mode = INPUT */ - modecnf = 0; - } - else - { - /* Output or alternate function */ + modecnf = 0; + } + else + { + /* Output or alternate function */ - modecnf = (cfgset & GPIO_MODE_MASK) >> GPIO_MODE_SHIFT; - } + modecnf = (cfgset & GPIO_MODE_MASK) >> GPIO_MODE_SHIFT; + } - modecnf |= ((cfgset & GPIO_CNF_MASK) >> GPIO_CNF_SHIFT) << 2; + modecnf |= ((cfgset & GPIO_CNF_MASK) >> GPIO_CNF_SHIFT) << 2; - /* Set the port configuration register */ + /* Set the port configuration register */ - regval = getreg32(cr); - regval &= ~(GPIO_CR_MODECNF_MASK(pos)); - regval |= (modecnf << GPIO_CR_MODECNF_SHIFT(pos)); - putreg32(regval, cr); + regval = getreg32(cr); + regval &= ~(GPIO_CR_MODECNF_MASK(pos)); + regval |= (modecnf << GPIO_CR_MODECNF_SHIFT(pos)); + putreg32(regval, cr); - /* Set or reset the corresponding BRR/BSRR bit */ + /* Set or reset the corresponding BRR/BSRR bit */ - if (!input) + if (!input) + { + /* It is an output or an alternate function. We have to look at the CNF + * bits to know which. + */ + + unsigned int cnf = (cfgset & GPIO_CNF_MASK); + if (cnf != GPIO_CNF_OUTPP && cnf != GPIO_CNF_OUTOD) { - /* It is an output or an alternate function. We have to look at the CNF - * bits to know which. - */ - - unsigned int cnf = (cfgset & GPIO_CNF_MASK); - if (cnf == GPIO_CNF_OUTPP || cnf == GPIO_CNF_OUTOD) - { - - /* Its an output... set the pin to the correct initial state */ - - if ((cfgset & GPIO_OUTPUT_SET) != 0) - { - /* Use the BSRR register to set the output */ - - regaddr = base + STM32_GPIO_BSRR_OFFSET; - } - else - { - /* Use the BRR register to clear */ - - regaddr = base + STM32_GPIO_BRR_OFFSET; - } - } - else - { - /* Its an alternate function pin... we can return early */ - - return OK; - } + /* Its an alternate function pin... we can return early */ + + return OK; } - else + } + else + { + /* It is an input pin... Should it configured as an EXTI interrupt? */ + + if ((cfgset & GPIO_EXTI) != 0) { - /* It is an input pin... Should it configured as an EXTI interrupt? */ - - if ((cfgset & GPIO_EXTI) != 0) - { - int shift; - - /* Yes.. Set the bits in the EXTI CR register */ - - regaddr = STM32_AFIO_EXTICR(pin); - regval = getreg32(regaddr); - shift = AFIO_EXTICR_EXTI_SHIFT(pin); - regval &= ~(AFIO_EXTICR_PORT_MASK << shift); - regval |= (((uint32_t)port) << shift); - putreg32(regval, regaddr); - } - - /* If it is pull-down or pull up, then we need to set the ODR - * appropriately for that function. - */ - - if ((cfgset & GPIO_CNF_MASK) == GPIO_CNF_INPULLUP) - { - /* Set the ODR bit (using BSRR) to one for the PULL-UP functionality */ - - regaddr = base + STM32_GPIO_BSRR_OFFSET; - } - else if ((cfgset & GPIO_CNF_MASK) == GPIO_CNF_INPULLDWN) - { - /* Clear the ODR bit (using BRR) to zero for the PULL-DOWN functionality */ - - regaddr = base + STM32_GPIO_BRR_OFFSET; - } - else - { - /* Neither... we can return early */ - - return OK; - } + int shift; + + /* Yes.. Set the bits in the EXTI CR register */ + + regaddr = STM32_AFIO_EXTICR(pin); + regval = getreg32(regaddr); + shift = AFIO_EXTICR_EXTI_SHIFT(pin); + regval &= ~(AFIO_EXTICR_PORT_MASK << shift); + regval |= (((uint32_t)port) << shift); + putreg32(regval, regaddr); } - regval = getreg32(regaddr); - regval |= (1 << pin); - putreg32(regval, regaddr); - return OK; + if ((cfgset & GPIO_CNF_MASK) != GPIO_CNF_INPULLUD) + { + /* Neither... we can return early */ + + return OK; + } + } + + /* If it is an output... set the pin to the correct initial state. + * If it is pull-down or pull up, then we need to set the ODR + * appropriately for that function. + */ + + if ((cfgset & GPIO_OUTPUT_SET) != 0) + { + /* Use the BSRR register to set the output */ + + regaddr = base + STM32_GPIO_BSRR_OFFSET; } - return ERROR; + else + { + /* Use the BRR register to clear */ + + regaddr = base + STM32_GPIO_BRR_OFFSET; + } + + regval = getreg32(regaddr); + regval |= (1 << pin); + putreg32(regval, regaddr); + return OK; } /**************************************************************************** diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.h b/nuttx/arch/arm/src/stm32/stm32_gpio.h index 43377fce5..3061b6b81 100644 --- a/nuttx/arch/arm/src/stm32/stm32_gpio.h +++ b/nuttx/arch/arm/src/stm32/stm32_gpio.h @@ -199,8 +199,8 @@ #define GPIO_CR_CNF_OUTPP (0) /* 00: General purpose output push-pull */ #define GPIO_CR_CNF_OUTOD (1) /* 01: General purpose output Open-drain */ -#define GPIO_CR_CNF_ALTPP (3) /* 10: Alternate function output Push-pull */ -#define GPIO_CR_CNF_ALTOD (6) /* 11: Alternate function output Open-drain */ +#define GPIO_CR_CNF_ALTPP (2) /* 10: Alternate function output Push-pull */ +#define GPIO_CR_CNF_ALTOD (3) /* 11: Alternate function output Open-drain */ #define GPIO_CR_MODE_INRST (0) /* 00: Input mode (reset state) */ #define GPIO_CR_MODE_OUT10MHz (1) /* 01: Output mode, max speed 10 MHz */ diff --git a/nuttx/arch/arm/src/stm32/stm32_internal.h b/nuttx/arch/arm/src/stm32/stm32_internal.h index f5094d50a..1af627a71 100755 --- a/nuttx/arch/arm/src/stm32/stm32_internal.h +++ b/nuttx/arch/arm/src/stm32/stm32_internal.h @@ -80,6 +80,16 @@ #define GPIO_OUTPUT (0) /* 0=Output or alternate function */ #define GPIO_ALT (0) +/* If the pin is a GPIO digital output, then this identifies the initial output value. + * If the pin is an input, this bit is overloaded to provide the qualifier to\ + * distinquish input pull-up and -down: + * + * .... .... V... .... + */ + +#define GPIO_OUTPUT_SET (1 << 7) /* Bit 7: If output, inital value of output */ +#define GPIO_OUTPUT_CLEAR (0) + /* These bits set the primary function of the pin: * .FF. .... .... .... */ @@ -89,8 +99,9 @@ # define GPIO_CNF_ANALOGIN (0 << GPIO_CNF_SHIFT) /* Analog input */ # define GPIO_CNF_INFLOAT (1 << GPIO_CNF_SHIFT) /* Input floating */ -# define GPIO_CNF_INPULLUP (2 << GPIO_CNF_SHIFT) /* Input pull-up */ -# define GPIO_CNF_INPULLDWN (3 << GPIO_CNF_SHIFT) /* Input pull-down */ +# define GPIO_CNF_INPULLUD (2 << GPIO_CNF_SHIFT) /* Input pull-up/down general bit, since up is composed of two parts */ +# define GPIO_CNF_INPULLDWN (2 << GPIO_CNF_SHIFT) /* Input pull-down */ +# define GPIO_CNF_INPULLUP ((2 << GPIO_CNF_SHIFT) | GPIO_OUTPUT_SET) /* Input pull-up */ # define GPIO_CNF_OUTPP (0 << GPIO_CNF_SHIFT) /* Output push-pull */ # define GPIO_CNF_OUTOD (1 << GPIO_CNF_SHIFT) /* Output open-drain */ @@ -114,13 +125,6 @@ #define GPIO_EXTI (1 << 10) /* Bit 10: Configure as EXTI interrupt */ -/* If the pin is an GPIO digital output, then this identifies the initial output value: - * .... .... V... .... - */ - -#define GPIO_OUTPUT_SET (1 << 7) /* Bit 7: If output, inital value of output */ -#define GPIO_OUTPUT_CLEAR (0) - /* This identifies the GPIO port: * .... .... .PPP .... */ diff --git a/nuttx/configs/vsn/include/board.h b/nuttx/configs/vsn/include/board.h index f4ad540c7..5c07f075e 100644 --- a/nuttx/configs/vsn/include/board.h +++ b/nuttx/configs/vsn/include/board.h @@ -1,5 +1,5 @@ /************************************************************************************ - * configs/vsn-1.2/include/board.h + * configs/vsn/include/board.h * include/arch/board/board.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. @@ -183,10 +183,11 @@ extern "C" { #endif /************************************************************************************ - * Public Function Prototypes + * Board Clock Configuration, called immediatelly after boot ************************************************************************************/ - EXTERN void stm32_board_clockconfig(void); +EXTERN void stm32_board_clockconfig(void); + /************************************************************************************ * Name: stm32_boardinitialize @@ -200,15 +201,9 @@ extern "C" { EXTERN void stm32_boardinitialize(void); + /************************************************************************************ - * Button support. - * - * Description: - * up_buttoninit() must be called to initialize button resources. After that, - * up_buttons() may be called to collect the state of all buttons. up_buttons() - * returns an 8-bit bit set with each bit associated with a button. See the - * BUTTON_* and JOYSTICK_* definitions above for the meaning of each bit. - * + * Button support. (TODO: button is not yet supported) ************************************************************************************/ #ifdef CONFIG_ARCH_BUTTONS @@ -216,11 +211,25 @@ EXTERN void up_buttoninit(void); EXTERN uint8_t up_buttons(void); #endif -/* Other peripherals startup routines, all returning OK on success */ + +/************************************************************************************ + * Memories + * - SDcard is tested to work up to 2 GB + * - RAMTRON has size of 128 kB + ************************************************************************************/ + EXTERN int up_sdcard(void); EXTERN int up_ramtron(void); +/************************************************************************************ + * Public Power Supply Contol + ************************************************************************************/ + +void board_power_reboot(void); +void board_power_off(void); + + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/configs/vsn/include/power.h b/nuttx/configs/vsn/include/power.h new file mode 100644 index 000000000..960c40fb1 --- /dev/null +++ b/nuttx/configs/vsn/include/power.h @@ -0,0 +1,71 @@ +/************************************************************************************ + * configs/vsn/include/power.h + * include/arch/board/power.h + * + * Copyright (C) 2011 Uros Platise. All rights reserved + * + * Authors: Uros Platise + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_POWER_H +#define __ARCH_BOARD_POWER_H + + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Power Supply Contol + ************************************************************************************/ + +void board_power_reboot(void); + +/* If this function returns, it means, that it was not possible to power-off the board */ +void board_power_off(void); + + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_POWER_H */ diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig index e6503f376..0f9496997 100755 --- a/nuttx/configs/vsn/nsh/defconfig +++ b/nuttx/configs/vsn/nsh/defconfig @@ -818,35 +818,50 @@ CONFIG_HEAP_BASE= CONFIG_HEAP_SIZE= +######################################################################## +# STM32 JTAG Options +# +# Full JTAG Enable (Parallel and Serial) +CONFIG_STM32_JTAG_FULL_ENABLE=n + +# Full but without the JNTRST pin +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n + +# Serial (SWJ) dual pin only which, can coexist besides the FRAM on SPI3 +CONFIG_STM32_JTAG_SW_ENABLE=n + + ######################################################################## # # Applications to be included within the NuttX binary as described -# under the apps/README.txt +# under the ../apps/README.txt # -# Set this config parameter above to: CONFIG_TASK_NAME_SIZE=16 -# in order to enable argv[0]= argument. Otherwise argv[0] -# will be noname. +# Set thi config parameter above to: CONFIG_TASK_NAME_SIZE=16 +# In order to enable argv[0]= argument set the option +# CONFIG_TASK_NAME_SIZE=16 # -# Include builtin NuttX application (disabling this option will -# exclude all of the apps found under the nuttx/apps directory, but -# not the apps found under the ../apps directory unless _APPS_USER=n. +# Include builtin NuttX applications (general option) CONFIG_BUILTIN_APPS_NUTTX=y +# Invoke the following application after NuttX starts +#CONFIG_BUILTIN_APP_START="hello" + # Individual selection of built-in applications: + +# Hello world provide a simple skeleton/demo application CONFIG_BUILTIN_APPS_HELLO=y -# Include user (external) applications located under ../apps directory? -CONFIG_BUILTIN_APPS_USER=y +# Provide poweroff command to switch off the board +CONFIG_BUILTIN_APPS_POWEROFF=y -# Invoke the following application after NuttX starts -# (enter app name, as: hello) -CONFIG_BUILTIN_APP_START= +# Provide JAVA Virtual Machine (the Darjeeling JVM) +CONFIG_BUILTIN_APPS_JVM=n -# CONFIG_EXAMPLES_NSH_BUILTIN_APPS - Support for running the builtin -# apps from command line. See apps/README for more information. +# CONFIG_EXAMPLES_NSH_BUILTIN_APPS - Enable invocation of all builtin +# apps from nsh command line. See apps/README for more information. # CONFIG_EXAMPLES_NSH_BUILTIN_APPS=y -CONFIG_SCHED_WAITPID=y + CONFIG_SCHED_WAITPID=y # ######################################################################## diff --git a/nuttx/configs/vsn/src/README.txt b/nuttx/configs/vsn/src/README.txt index bacf82c17..f08e8fe06 100644 --- a/nuttx/configs/vsn/src/README.txt +++ b/nuttx/configs/vsn/src/README.txt @@ -10,3 +10,13 @@ Execution starts in the following order: - boot, performs initial chip and board initialization - ... - nsh, as central application last. + + + + +JTAG options: +============= + +CONFIG_STM32_JTAG_FULL_ENABLE // Complete parallel and serial +CONFIG_STM32_JTAG_NOJNTRST_ENABLE // no JNTRST pin +CONFIG_STM32_JTAG_SW_ENABLE // serial (dual pin) only (can coexist besides the FRAM on SPI3) diff --git a/nuttx/configs/vsn/src/boot.c b/nuttx/configs/vsn/src/boot.c index 2f959333d..eb4ba9ef5 100644 --- a/nuttx/configs/vsn/src/boot.c +++ b/nuttx/configs/vsn/src/boot.c @@ -1,112 +1,104 @@ -/************************************************************************************ - * configs/vsn/src/boot.c - * arch/arm/src/board/boot.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Copyright (c) 2011 Uros Platise. All rights reserved. - * - * Authors: Gregory Nutt - * Uros Platise - * - * 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 "stm32_gpio.h" -#include "up_arch.h" -#include "vsn.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_boardinitialize - * - * Description: - * All STM32 architectures must provide the following entry point. This entry point - * is called early in the intitialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -void stm32_boardinitialize(void) -{ -#ifdef CONFIG_STM32_SPI3 -#warning JTAG Port Disabled as SPI3 NVRAM/FRAM support is enabled - - uint32_t val = getreg32(STM32_AFIO_MAPR); - val &= 0x00FFFFFF; // clear undefined readings ... - val |= AFIO_MAPR_DISAB; // set JTAG-DP and SW-DP Disabled - putreg32(val, STM32_AFIO_MAPR); -#endif - - // Set Board Voltage to 3.3 V - board_power_setbootvoltage(); - - /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function - * stm32_spiinitialize() has been brought into the link. - */ - -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) - if (stm32_spiinitialize) stm32_spiinitialize(); -#endif - - /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not - * disabled, and 3) the weak function stm32_usbinitialize() has been brought - * into the build. - */ - -#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB) - if (stm32_usbinitialize) stm32_usbinitialize(); -#endif - - /* Configure on-board LEDs if LED support has been selected. */ - -#ifdef CONFIG_ARCH_LEDS - up_ledinit(); -#endif -} +/************************************************************************************ + * configs/vsn/src/boot.c + * arch/arm/src/board/boot.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Copyright (c) 2011 Uros Platise. All rights reserved. + * + * Authors: Gregory Nutt + * Uros Platise + * + * 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 "stm32_gpio.h" +#include "up_arch.h" +#include "vsn.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void stm32_boardinitialize(void) +{ + /* Set start-up board voltage */ + + board_power_init(); + + /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function + * stm32_spiinitialize() has been brought into the link. + */ + +#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3) + if (stm32_spiinitialize) stm32_spiinitialize(); +#endif + + /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not + * disabled, and 3) the weak function stm32_usbinitialize() has been brought + * into the build. + */ + +#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB) + if (stm32_usbinitialize) stm32_usbinitialize(); +#endif + + /* Configure on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + up_ledinit(); +#endif +} diff --git a/nuttx/configs/vsn/src/leds.c b/nuttx/configs/vsn/src/leds.c index ef3c87144..c1cc1c573 100644 --- a/nuttx/configs/vsn/src/leds.c +++ b/nuttx/configs/vsn/src/leds.c @@ -43,13 +43,17 @@ #include +#include +#include + #include #include #include -#include +#include "up_arch.h" #include "vsn.h" + /**************************************************************************** * Definitions ****************************************************************************/ @@ -72,6 +76,8 @@ /**************************************************************************** * Private Data ****************************************************************************/ + +irqstate_t irqidle_mask; /**************************************************************************** * Private Functions @@ -101,7 +107,10 @@ void up_ledinit(void) void up_ledon(int led) { - if (led==LED_IDLE) stm32_gpiowrite(GPIO_LED, true); + if (led==LED_IDLE) { + irqidle_mask = irqsave(); + stm32_gpiowrite(GPIO_LED, true); + } } /**************************************************************************** @@ -110,7 +119,10 @@ void up_ledon(int led) void up_ledoff(int led) { - if (led==LED_IDLE) stm32_gpiowrite(GPIO_LED, false); + if (led==LED_IDLE) { + stm32_gpiowrite(GPIO_LED, false); + irqrestore(irqidle_mask); + } } #endif /* CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/vsn/src/power.c b/nuttx/configs/vsn/src/power.c index 2e23ed033..c7c73448a 100644 --- a/nuttx/configs/vsn/src/power.c +++ b/nuttx/configs/vsn/src/power.c @@ -1,6 +1,6 @@ /**************************************************************************** - * config/vsn/src/ramtron.c - * arch/arm/src/board/ramtron.c + * config/vsn/src/power.c + * arch/arm/src/board/power.c * * Copyright (C) 2011 Uros Platise. All rights reserved. * @@ -37,21 +37,57 @@ #include +#include +#include + #include #include #include -#include +#include "stm32_gpio.h" #include "vsn.h" +#include "up_arch.h" + void board_power_register(void); void board_power_adjust(void); void board_power_status(void); -void board_power_setbootvoltage(void) + + +void board_power_init(void) { stm32_configgpio(GPIO_PVS); + stm32_configgpio(GPIO_PST); + stm32_configgpio(GPIO_XPWR); + stm32_configgpio(GPIO_SCTC); + stm32_configgpio(GPIO_PCLR); +} + + +void board_power_reboot(void) +{ + // low-level board reset (not just MCU reset) + // if external power is present, stimulate power-off as board + // will wake-up immediatelly, if power is not present, set an alarm + // before power off the board. } -void board_power_reboot(void); -void board_power_off(void); + +void board_power_off(void) +{ + // Check if external supply is not present, otherwise return + // notifying that it is not possible to power-off the board + + // \todo + + // stop backgorund processes + irqsave(); + + // switch to internal HSI and get the PD0 and PD1 as GPIO + stm32_board_select_hsi(); + + // trigger shutdown with pull-up resistor (not push-pull!) and wait. + stm32_gpiowrite(GPIO_PCLR, true); + for(;;); +} diff --git a/nuttx/configs/vsn/src/ramtron.c b/nuttx/configs/vsn/src/ramtron.c index 24f43d0ff..01cf93311 100644 --- a/nuttx/configs/vsn/src/ramtron.c +++ b/nuttx/configs/vsn/src/ramtron.c @@ -61,6 +61,11 @@ int up_ramtron(void) int retval; /* Get the SPI port */ + +#if defined(CONFIG_STM32_JTAG_FULL_ENABLE) || defined(CONFIG_STM32_JTAG_NOJNTRST_ENABLE) + message("RAMTRON: Cannot open SPI3 port as JTAG is enabled. Switch to Serial JTAG mode.\n"); + return -ENODEV; +#endif spi = up_spiinitialize(3); if (!spi) @@ -70,7 +75,7 @@ int up_ramtron(void) } message("RAMTRON: Initialized SPI3\n"); - mtd = ramtron_initialize(spi); + mtd = (struct mtd_dev_s *)ramtron_initialize(spi); if (!mtd) { message("RAMTRON: Device not found\n"); diff --git a/nuttx/configs/vsn/src/sysclock.c b/nuttx/configs/vsn/src/sysclock.c index f812dd2c1..79cc80ff2 100644 --- a/nuttx/configs/vsn/src/sysclock.c +++ b/nuttx/configs/vsn/src/sysclock.c @@ -39,6 +39,7 @@ #include #include "stm32_rcc.h" +#include "stm32_gpio.h" #include "stm32_flash.h" #include "up_internal.h" #include "up_arch.h" @@ -123,6 +124,11 @@ void stm32_board_select_hsi(void) // Wait until the selected source is used as the system clock source while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS); + + // map port PD0 and PD1 on OSC pins + regval = getreg32(STM32_AFIO_MAPR); + regval |= AFIO_MAPR_PD01_REMAP; + putreg32(regval, STM32_AFIO_MAPR); } @@ -140,6 +146,13 @@ void stm32_board_select_hsi(void) */ int stm32_board_select_hse(void) { + uint32_t regval; + + // be sure to release PD0 and PD1 pins from the OSC pins + regval = getreg32(STM32_AFIO_MAPR); + regval &= ~AFIO_MAPR_PD01_REMAP; + putreg32(regval, STM32_AFIO_MAPR); + // if (is cc1101 9 MHz clock output enabled), otherwise return with -1 // I think that clock register provides HSE valid signal to detect that as well. diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h index c065e1e75..33282c5a1 100644 --- a/nuttx/configs/vsn/src/vsn.h +++ b/nuttx/configs/vsn/src/vsn.h @@ -1,138 +1,138 @@ -/************************************************************************************ - * configs/vsn/src/vsn.h - * arch/arm/src/board/vsn.n - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Copyright (c) 2011 Uros Platise. All rights reserved. - * - * Authors: Gregory Nutt - * Uros Platise - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H -#define __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* LED */ - -#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2) - -/* BUTTON - Note that after a good second button causes hardware reset */ - -#define GPIO_PUSHBUTTON (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5) - -/* Power Management Pins */ - -#define GPIO_PVS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7) - -/* FRAM */ - -#define GPIO_FRAM_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) - - -/* Debug ********************************************************************/ - -#ifdef CONFIG_CPP_HAVE_VARARGS -# ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) -# else -# define message(...) printf(__VA_ARGS__) -# endif -#else -# ifdef CONFIG_DEBUG -# define message lib_lowprintf -# else -# define message printf -# endif -#endif - - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_spiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins for the VSN board. - * - ************************************************************************************/ - -extern void weak_function stm32_spiinitialize(void); - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the VSN board. - * - ************************************************************************************/ - -extern void weak_function stm32_usbinitialize(void); - - -/************************************************************************************ - * Power Module - * - * Description: - * - Provides power related board operations, such as voltage selection, - * proper reboot sequence, and power-off - ************************************************************************************/ - -extern void board_power_setbootvoltage(void); // Default voltage at boot time - - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H */ - +/************************************************************************************ + * configs/vsn/src/vsn.h + * arch/arm/src/board/vsn.n + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Copyright (c) 2011 Uros Platise. All rights reserved. + * + * Authors: Gregory Nutt + * Uros Platise + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H +#define __CONFIGS_VSN_SRC_VSN_INTERNAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* LED */ + +#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN2 |GPIO_OUTPUT_CLEAR) + +/* BUTTON - Note that after a good second button causes hardware reset */ + +#define GPIO_PUSHBUTTON (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5 ) + +/* Power Management Pins */ + +#define GPIO_PVS (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN7 |GPIO_OUTPUT_CLEAR) +#define GPIO_PST (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN13) +#define GPIO_SCTC (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8 ) +#define GPIO_PCLR (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1 ) // by default this pin is OSCOUT, requires REMAP +#define GPIO_XPWR (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4 ) + +/* FRAM */ + +#define GPIO_FRAM_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15|GPIO_OUTPUT_SET) + + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lib_lowprintf(__VA_ARGS__) +# else +# define message(...) printf(__VA_ARGS__) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lib_lowprintf +# else +# define message printf +# endif +#endif + + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the VSN board. + * + ************************************************************************************/ + +extern void weak_function stm32_spiinitialize(void); + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the VSN board. + * + ************************************************************************************/ + +extern void weak_function stm32_usbinitialize(void); + + +/************************************************************************************ + * Init Power Module and set board system voltage + ************************************************************************************/ + +extern void board_power_init(void); + + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_VSN_SRC_VSN_INTERNAL_H */ + diff --git a/nuttx/drivers/net/slip.c b/nuttx/drivers/net/slip.c index c3dcb5e03..899e4e5be 100644 --- a/nuttx/drivers/net/slip.c +++ b/nuttx/drivers/net/slip.c @@ -73,6 +73,10 @@ # error "UIP_LLH_LEN must be set to zero" #endif +#ifdef CONFIG_NET_MULTIBUFFER +# error "Requires CONFIG_NET_MULTIBUFFER" +#endif + #ifndef CONFIG_SLIP_STACKSIZE # define CONFIG_SLIP_STACKSIZE 1024 #endif diff --git a/nuttx/examples/nsh/nsh.h b/nuttx/examples/nsh/nsh.h index 4f6811a6d..a6824f1b7 100644 --- a/nuttx/examples/nsh/nsh.h +++ b/nuttx/examples/nsh/nsh.h @@ -329,7 +329,8 @@ extern int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline); /* Application interface */ #ifdef CONFIG_EXAMPLES_NSH_BUILTIN_APPS -extern int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, const char *cmd, char *argv[]); +extern int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, + FAR char *argv[]); #endif /* I/O interfaces */ diff --git a/nuttx/examples/nsh/nsh_apps.c b/nuttx/examples/nsh/nsh_apps.c index e71ff9d1f..d1ce1d955 100644 --- a/nuttx/examples/nsh/nsh_apps.c +++ b/nuttx/examples/nsh/nsh_apps.c @@ -85,10 +85,11 @@ * Name: nsh_execute ****************************************************************************/ -int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, const char *cmd, char *argv[]) +int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, + FAR char *argv[]) { int ret = OK; - const char * name; + FAR const char * name; /* Try to find command within pre-built application list. */ @@ -101,7 +102,7 @@ int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, const char *cmd, char *argv[]) /* On failure, list the set of available built-in commands */ nsh_output(vtbl, "Builtin Apps: "); - for (i = 0; name = nuttapp_getname(i); i++) + for (i = 0; (name = nuttapp_getname(i)) != NULL; i++) { nsh_output(vtbl, "%s ", name); } -- cgit v1.2.3