configs/stm32f4discovery/nsh converted to use kconfig-frontends

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5573 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-01-27 20:05:29 +00:00
parent b4db7635d8
commit d3e4a31ac5
6 changed files with 693 additions and 754 deletions

View File

@ -309,7 +309,7 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
{
struct sched_param param;
pid_t proxy;
int errcode;
int errcode = OK;
#ifdef CONFIG_SCHED_WAITPID
int status;
#endif

View File

@ -4048,4 +4048,6 @@
* sched/os_start.c: Fix ordering of group initialization.
* configs/stm32f4discovery/usbnsh: Add an NSH STM32F4Discovery
configuration that uses USB CDC/ACM for the NSH console.
* configs/stm32f4discovery/nsh: Converted to use the kconfig-frontends
tools.

View File

@ -1165,14 +1165,30 @@ Where <subdir> is one of the following:
nsh:
---
Configures the NuttShell (nsh) located at apps/examples/nsh. The
Configuration enables both the serial and telnet NSH interfaces.
Default toolchain:
CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux / Mac OS X
Configuration enables the serial interfaces on UART2. Support for
builtin applications is enabled, but in the base configuration no
builtin applications are selected (see NOTES below).
NOTES:
1. This example supports the PWM test (apps/examples/pwm) but this must
1. This configuration uses the mconf-based configuration tool. To
change this configuration using that tool, you should:
a. Build and install the kconfig-mconf tool. See nuttx/README.txt
and misc/tools/
b. Execute 'make menuconfig' in nuttx/ in order to start the
reconfiguration process.
2. By default, this configuration uses the CodeSourcery toolchain
for Windows and builds under Cygwin (or probably MSYS). That
can easily be reconfigured, of course.
CONFIG_HOST_WINDOWS=y : Builds under Windows
CONFIG_WINDOWS_CYGWIN=y : Using Cygwin
CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y : CodeSourcery for Windows
3. This example supports the PWM test (apps/examples/pwm) but this must
be manually enabled by selecting:
CONFIG_PWM=y : Enable the generic PWM infrastructure
@ -1185,24 +1201,25 @@ Where <subdir> is one of the following:
CONFIG_DEBUG_PWM
2. This example supports the Quadrature Encode test (apps/examples/qencoder)
5. This example supports the Quadrature Encode test (apps/examples/qencoder)
but this must be manually enabled by selecting:
CONFIG_EXAMPLES_QENCODER=y : Enable the apps/examples/qencoder
CONFIG_SENSORS=y : Enable support for sensors
CONFIG_QENCODER=y : Enable the generic Quadrature Encoder infrastructure
CONFIG_STM32_TIM8=y : Enable TIM8
CONFIG_STM32_TIM2=n : (Or optionally TIM2)
CONFIG_STM32_TIM8_QE=y : Use TIM8 as the quadrature encoder
CONFIG_STM32_TIM2_QE=y : (Or optionally TIM2)
See also apps/examples/README.txt
Special PWM-only debug options:
See also apps/examples/README.tx. Special PWM-only debug options:
CONFIG_DEBUG_QENCODER
3. This example supports the watchdog timer test (apps/examples/watchdog)
6. This example supports the watchdog timer test (apps/examples/watchdog)
but this must be manually enabled by selecting:
CONFIG_EXAMPLES_WATCHDOG=y : Enable the apps/examples/watchdog
CONFIG_WATCHDOG=y : Enables watchdog timer driver support
CONFIG_STM32_WWDG=y : Enables the WWDG timer facility, OR
CONFIG_STM32_IWDG=y : Enables the IWDG timer facility (but not both)
@ -1216,14 +1233,14 @@ Where <subdir> is one of the following:
The IWDG timer has a range of about 35 seconds and should not be an issue.
4. USB Support (CDC/ACM device)
7. USB Support (CDC/ACM device)
CONFIG_STM32_OTGFS=y : STM32 OTG FS support
CONFIG_USBDEV=y : USB device support must be enabled
CONFIG_CDCACM=y : The CDC/ACM driver must be built
CONFIG_NSH_BUILTIN_APPS=y : NSH built-in application support must be enabled
5. Using the USB console.
8. Using the USB console.
The STM32F4Discovery NSH configuration can be set up to use a USB CDC/ACM
(or PL2303) USB console. The normal way that you would configure the
@ -1268,7 +1285,7 @@ Where <subdir> is one of the following:
you can still use certain kinds of debug output (see include/debug.h, all
of the interfaces based on lib_lowprintf will work in this configuration).
6. USB OTG FS Host Support. The following changes will enable support for
9. USB OTG FS Host Support. The following changes will enable support for
a USB host on the STM32F4Discovery, including support for a mass storage
class driver:

View File

@ -1,67 +0,0 @@
############################################################################
# configs/stm32f4discovery/nsh/appconfig
#
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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.
#
############################################################################
# Path to example in apps/examples containing the user_start entry point
CONFIGURED_APPS += examples/nsh
# The NSH application library
CONFIGURED_APPS += system/readline
CONFIGURED_APPS += nshlib
# Applications configured as an NX built-in commands
ifeq ($(CONFIG_ADC),y)
CONFIGURED_APPS += examples/adc
endif
ifeq ($(CONFIG_PWM),y)
CONFIGURED_APPS += examples/pwm
endif
ifeq ($(CONFIG_QENCODER),y)
CONFIGURED_APPS += examples/qencoder
endif
ifeq ($(CONFIG_USBDEV),y)
ifeq ($(CONFIG_CDCACM),y)
CONFIGURED_APPS += examples/cdcacm
endif
endif
ifeq ($(CONFIG_WATCHDOG),y)
CONFIGURED_APPS += examples/watchdog
endif

File diff suppressed because it is too large Load Diff

View File

@ -635,7 +635,7 @@ CONFIG_NSH_CONSOLE=y
CONFIG_NSH_TELNET=n
CONFIG_NSH_USBCONSOLE=n
CONFIG_NSH_USBCONDEV="/dev/ttyACM0"
CONFIG_NSH_UBSDEV_MINOR=0
CONFIG_NSH_USBDEV_MINOR=0
CONFIG_NSH_USBDEV_TRACEINIT=n
CONFIG_NSH_USBDEV_TRACECLASS=n
CONFIG_NSH_USBDEV_TRACETRANSFERS=n