aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-26 17:56:46 -0700
committerpx4dev <px4@purgatory.org>2012-08-26 17:56:46 -0700
commite352171029df7a88414adc61d9608dec839fce2d (patch)
treece2d2b7605e0b70ce0b67455959cff6728c40c57 /nuttx
parent22b390a9eb994671191432339b692dabb3b4a0fc (diff)
downloadpx4-firmware-e352171029df7a88414adc61d9608dec839fce2d.tar.gz
px4-firmware-e352171029df7a88414adc61d9608dec839fce2d.tar.bz2
px4-firmware-e352171029df7a88414adc61d9608dec839fce2d.zip
Pull configurations into line with current NuttX layout.
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h2
-rw-r--r--nuttx/configs/px4fmu/nsh/Make.defs2
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig3
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig266
-rw-r--r--nuttx/configs/px4io/io/Make.defs2
-rwxr-xr-xnuttx/configs/px4io/io/defconfig53
6 files changed, 149 insertions, 179 deletions
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 0db8580ba..994a3cfa5 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -106,7 +106,7 @@
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
-#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(7)
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
#define STM32_SYSCLK_FREQUENCY 168000000ul
diff --git a/nuttx/configs/px4fmu/nsh/Make.defs b/nuttx/configs/px4fmu/nsh/Make.defs
index 87508e22e..3e6f88bd3 100644
--- a/nuttx/configs/px4fmu/nsh/Make.defs
+++ b/nuttx/configs/px4fmu/nsh/Make.defs
@@ -1,3 +1,3 @@
include ${TOPDIR}/.config
-include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
+include $(TOPDIR)/configs/px4fmu/common/Make.defs
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 3323d1998..369a40f95 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -62,10 +62,7 @@ CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += uORB
-ifeq ($(CONFIG_MAVLINK),y)
CONFIGURED_APPS += mavlink
-endif
-
CONFIGURED_APPS += gps
CONFIGURED_APPS += commander
#CONFIGURED_APPS += sdlog
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index a87ce7ffa..c2c67bf41 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -1,7 +1,8 @@
############################################################################
# configs/px4fmu/nsh/defconfig
#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# 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
@@ -41,7 +42,7 @@
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
-# specific architecture within the chip familyl.
+# specific architecture within the chip family.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
@@ -51,7 +52,6 @@
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
-# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
@@ -70,17 +70,16 @@
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
-CONFIG_ARCH=arm
+CONFIG_ARCH="arm"
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM4=y
-CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F405RG=y
-CONFIG_ARCH_BOARD=px4fmu
+CONFIG_ARCH_BOARD="px4fmu"
CONFIG_ARCH_BOARD_PX4FMU=y
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_DRAM_SIZE=0x00030000
CONFIG_DRAM_START=0x20000000
-CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=y
CONFIG_ARCH_INTERRUPTSTACK=n
@@ -94,25 +93,8 @@ CONFIG_ARCH_MATH_H=y
CONFIG_ARMV7M_CMNVECTOR=y
-#
-# LIBC printf() options
-#
-# CONFIG_LIBC_FLOATINGPOINT - Enables printf("%f")
-# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
-# 5.1234567
-# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
-#
-CONFIG_LIBC_FLOATINGPOINT=y
-CONFIG_HAVE_LONG_LONG=y
-#CONFIG_LIBC_FIXEDPRECISION=7
-#
-# CMSIS options
-#
-# CONFIG_DSPLIB_TARGET - Target for the CMSIS DSP library, one of
-# CortexM0, CortexM3 or CortexM4 (with fpu)
-#
-CONFIG_CMSIS_DSPLIB_TARGET=CortexM4
+
#
# JTAG Enable settings (by default JTAG-DP and SW-DP are enabled):
@@ -132,6 +114,14 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
+# On-chip CCM SRAM configuration
+#
+# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
+# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
+# being a part of the stack.
+#
+
+#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -181,6 +171,7 @@ CONFIG_STM32_TIM12=y
CONFIG_STM32_TIM13=y
CONFIG_STM32_TIM14=y
CONFIG_STM32_WWDG=y
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI3=y
CONFIG_STM32_USART2=y
@@ -211,40 +202,6 @@ CONFIG_STM32_TIM9=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
-#
-# Configure the ADC
-#
-CONFIG_ADC=y
-# select trigger timer
-CONFIG_STM32_TIM4_ADC3=y
-# select sample frequency 1^=1.5Msamples/second
-# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
-CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
-# select timer channel 0=CC1,...,3=CC4
-CONFIG_STM32_ADC3_TIMTRIG=3
-CONFIG_ADC_DMA=y
-# only 4 places usable!
-CONFIG_ADC_FIFOSIZE=5
-
-#
-# Timer and I2C devices may need to the following to force power to be applied:
-#
-#CONFIG_STM32_FORCEPOWER=y
-
-#
-# I2C configuration
-#
-CONFIG_I2C=y
-CONFIG_I2C_POLLED=y
-CONFIG_I2C_TRANSFER=y
-CONFIG_I2C_WRITEREAD=y
-CONFIG_I2C_TRACE=n
-# Allow 180 us per byte, a wide margin for the 400 KHz clock we're using
-# e.g. 9.6 ms for an EEPROM page write, 0.9 ms for a MAG update
-CONFIG_STM32_I2CTIMEOUS_PER_BYTE=200
-# Constant overhead for generating I2C start / stop conditions
-CONFIG_STM32_I2CTIMEOUS_START_STOP=700
-CONFIG_DEBUG_I2C=n
#
# STM32F40xxx specific serial device driver settings
@@ -357,13 +314,6 @@ CONFIG_PWM_SERVO=n
CONFIG_MULTIPORT=n
#
-# CONFIG_UART2_RTS_CTS_AS_GPIO
-# If set, enables RTS and CTS pins as additional GPIOs 2 and 3
-#
-CONFIG_PX4_UART2_RTS_CTS_AS_GPIO=y
-
-
-#
# STM32F40xxx specific SPI device driver settings
#
CONFIG_SPI_EXCHANGE=y
@@ -375,6 +325,8 @@ CONFIG_SPI_EXCHANGE=y
#
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
+# Standard 11-bit IDs.
# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@@ -383,8 +335,11 @@ CONFIG_SPI_EXCHANGE=y
# mode for testing. The STM32 CAN driver does support loopback mode.
# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+# CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
+# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
#
CONFIG_CAN=n
+CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n
@@ -392,6 +347,42 @@ CONFIG_CAN1_BAUD=700000
CONFIG_CAN2_BAUD=700000
#
+# I2C configuration
+#
+CONFIG_I2C=y
+CONFIG_I2C_POLLED=y
+CONFIG_I2C_TRANSFER=y
+CONFIG_I2C_TRACE=n
+# Allow 180 us per byte, a wide margin for the 400 KHz clock we're using
+# e.g. 9.6 ms for an EEPROM page write, 0.9 ms for a MAG update
+CONFIG_STM32_I2CTIMEOUS_PER_BYTE=200
+# Constant overhead for generating I2C start / stop conditions
+CONFIG_STM32_I2CTIMEOUS_START_STOP=700
+# XXX this is bad and we want it gone
+CONFIG_I2C_WRITEREAD=y
+
+#
+# ADC configuration
+#
+# Enable ADC driver support.
+#
+# CONFIG_ADC=y : Enable the generic ADC infrastructure
+# CONFIG_STM32_TIM1_ADC=y : Indicate that timer 1 will be used to trigger an ADC
+# CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to drive ADC3 sampling
+# CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100 : Select a sampling frequency
+#
+CONFIG_ADC=y
+CONFIG_STM32_TIM4_ADC3=y
+# select sample frequency 1^=1.5Msamples/second
+# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
+CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
+# select timer channel 0=CC1,...,3=CC4
+CONFIG_STM32_ADC3_TIMTRIG=3
+CONFIG_ADC_DMA=y
+# only 4 places usable!
+CONFIG_ADC_FIFOSIZE=5
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
@@ -408,7 +399,7 @@ CONFIG_CAN2_BAUD=700000
# CONFIG_HAVE_LIBM - toolchain supports libm.a
#
CONFIG_RRLOAD_BINARY=n
-CONFIG_INTELHEX_BINARY=y
+CONFIG_INTELHEX_BINARY=n
CONFIG_MOTOROLA_SREC=n
CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=y
@@ -423,6 +414,9 @@ CONFIG_HAVE_LIBM=y
# CONFIG_DEBUG_SYMBOLS - build without optimization and with
# debug symbols (needed for use with a debugger).
# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
# CONFIG_MM_REGIONS - If the architecture includes multiple
# regions of memory to allocate from, this specifies the
# number of memory regions that the memory manager must
@@ -497,7 +491,7 @@ CONFIG_HAVE_LIBM=y
# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
# thread. Default: 50
# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
-# work in units of microseconds. Default: 50*1000 (50 MS).
+# work in units of microseconds. Default: 50000 (50 MS).
# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
@@ -509,14 +503,20 @@ CONFIG_HAVE_LIBM=y
CONFIG_DEBUG=y
CONFIG_DEBUG_VERBOSE=y
CONFIG_DEBUG_SYMBOLS=y
-CONFIG_DEBUG_ANALOG=n
CONFIG_DEBUG_FS=n
CONFIG_DEBUG_GRAPHICS=n
CONFIG_DEBUG_LCD=n
CONFIG_DEBUG_USB=n
CONFIG_DEBUG_NET=n
CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_MSEC_PER_TICK=1
@@ -538,7 +538,7 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WORKQUEUE=y
-CONFIG_SCHED_WORKPRIORITY=199
+CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=(5*1000)
CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SIG_SIGWORK=4
@@ -546,6 +546,38 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SCHED_ATEXIT=n
#
+# System Logging
+#
+# CONFIG_SYSLOG - Enables the System Logging feature.
+# CONFIG_RAMLOG - Enables the RAM logging feature
+# CONFIG_RAMLOG_CONSOLE - Use the RAM logging device as a system console.
+# If this feature is enabled (along with CONFIG_DEV_CONSOLE), then all
+# console output will be re-directed to a circular buffer in RAM. This
+# is useful, for example, if the only console is a Telnet console. Then
+# in that case, console output from non-Telnet threads will go to the
+# circular buffer and can be viewed using the NSH 'dmesg' command.
+# CONFIG_RAMLOG_SYSLOG - Use the RAM logging device for the syslogging
+# interface. If this feature is enabled (along with CONFIG_SYSLOG),
+# then all debug output (only) will be re-directed to the circular
+# buffer in RAM. This RAM log can be view from NSH using the 'dmesg'
+# command.
+# CONFIG_RAMLOG_NPOLLWAITERS - The number of threads than can be waiting
+# for this driver on poll(). Default: 4
+#
+# If CONFIG_RAMLOG_CONSOLE or CONFIG_RAMLOG_SYSLOG is selected, then the
+# following may also be provided:
+#
+# CONFIG_RAMLOG_CONSOLE_BUFSIZE - Size of the console RAM log. Default: 1024
+#
+
+CONFIG_SYSLOG=n
+CONFIG_RAMLOG=n
+CONFIG_RAMLOG_CONSOLE=n
+CONFIG_RAMLOG_SYSLOG=n
+#CONFIG_RAMLOG_NPOLLWAITERS
+#CONFIG_RAMLOG_CONSOLE_BUFSIZE
+
+#
# The following can be used to disable categories of
# APIs supported by the OS. If the compiler supports
# weak functions, then it should not be necessary to
@@ -574,8 +606,14 @@ CONFIG_DISABLE_POLL=n
#
# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
# little smaller if we do not support fieldwidthes
+# CONFIG_LIBC_FLOATINGPOINT - Enables printf("%f")
+# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
+# 5.1234567
+# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
#
CONFIG_NOPRINTF_FIELDWIDTH=n
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_HAVE_LONG_LONG=y
#
# Allow for architecture optimized implementations
@@ -789,42 +827,6 @@ CONFIG_USBDEV_TRACE=n
CONFIG_USBDEV_TRACE_NRECORDS=512
#
-# USB Serial Device Configuration (Prolifics PL2303 emulation)
-#
-# CONFIG_PL2303
-# Enable compilation of the USB serial driver
-# CONFIG_PL2303_EPINTIN
-# The logical 7-bit address of a hardware endpoint that supports
-# interrupt IN operation
-# CONFIG_PL2303_EPBULKOUT
-# The logical 7-bit address of a hardware endpoint that supports
-# bulk OUT operation
-# CONFIG_PL2303_EPBULKIN
-# The logical 7-bit address of a hardware endpoint that supports
-# bulk IN operation
-# # CONFIG_PL2303_NWRREQS and CONFIG_PL2303_NRDREQS
-# The number of write/read requests that can be in flight
-# CONFIG_PL2303_VENDORID and CONFIG_PL2303_VENDORSTR
-# The vendor ID code/string
-# CONFIG_PL2303_PRODUCTID and CONFIG_PL2303_PRODUCTSTR
-# The product ID code/string
-# CONFIG_PL2303_RXBUFSIZE and CONFIG_PL2303_TXBUFSIZE
-# Size of the serial receive/transmit buffers
-#
-CONFIG_PL2303=n
-CONFIG_PL2303_EPINTIN=1
-CONFIG_PL2303_EPBULKOUT=2
-CONFIG_PL2303_EPBULKIN=3
-CONFIG_PL2303_NWRREQS=4
-CONFIG_PL2303_NRDREQS=4
-CONFIG_PL2303_VENDORID=0x067b
-CONFIG_PL2303_PRODUCTID=0x2303
-CONFIG_PL2303_VENDORSTR="Nuttx"
-CONFIG_PL2303_PRODUCTSTR="USBdev Serial"
-CONFIG_PL2303_RXBUFSIZE=512
-CONFIG_PL2303_TXBUFSIZE=512
-
-#
# USB serial device class driver (Standard CDC ACM class)
#
# CONFIG_CDCACM
@@ -896,44 +898,6 @@ CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6"
#CONFIG_CDCACM_RXBUFSIZE
#CONFIG_CDCACM_TXBUFSIZE
-#
-# USB Storage Device Configuration
-#
-# CONFIG_USBMSC
-# Enable compilation of the USB storage driver
-# CONFIG_USBMSC_EP0MAXPACKET
-# Max packet size for endpoint 0
-# CONFIG_USBMSC_EPBULKOUT and CONFIG_USBMSC_EPBULKIN
-# The logical 7-bit address of a hardware endpoints that support
-# bulk OUT and IN operations
-# CONFIG_USBMSC_NWRREQS and CONFIG_USBMSC_NRDREQS
-# The number of write/read requests that can be in flight
-# CONFIG_USBMSC_BULKINREQLEN and CONFIG_USBMSC_BULKOUTREQLEN
-# The size of the buffer in each write/read request. This
-# value needs to be at least as large as the endpoint
-# maxpacket and ideally as large as a block device sector.
-# CONFIG_USBMSC_VENDORID and CONFIG_USBMSC_VENDORSTR
-# The vendor ID code/string
-# CONFIG_USBMSC_PRODUCTID and CONFIG_USBMSC_PRODUCTSTR
-# The product ID code/string
-# CONFIG_USBMSC_REMOVABLE
-# Select if the media is removable
-#
-CONFIG_USBMSC=n
-CONFIG_USBMSC_EP0MAXPACKET=64
-CONFIG_USBMSC_EPBULKOUT=2
-CONFIG_USBMSC_EPBULKIN=5
-CONFIG_USBMSC_NRDREQS=2
-CONFIG_USBMSC_NWRREQS=2
-CONFIG_USBMSC_BULKINREQLEN=256
-CONFIG_USBMSC_BULKOUTREQLEN=256
-CONFIG_USBMSC_VENDORID=0x584e
-CONFIG_USBMSC_VENDORSTR="NuttX"
-CONFIG_USBMSC_PRODUCTID=0x5342
-CONFIG_USBMSC_PRODUCTSTR="USBdev Storage"
-CONFIG_USBMSC_VERSIONNO=0x0399
-CONFIG_USBMSC_REMOVABLE=y
-
#
# Settings for apps/nshlib
@@ -944,7 +908,6 @@ CONFIG_USBMSC_REMOVABLE=y
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
# CONFIG_NSH_STRERROR - Use strerror(errno)
# CONFIG_NSH_LINELEN - Maximum length of one command line
-# CONFIG_NSH_STACKSIZE - Stack size to use for new threads.
# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
# CONFIG_NSH_DISABLEBG - Disable background commands
@@ -989,9 +952,9 @@ CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
CONFIG_NSH_NOMAC=y
-CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
-CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
-CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
+CONFIG_NSH_IPADDR=0x0a000002
+CONFIG_NSH_DRIPADDR=0x0a000001
+CONFIG_NSH_NETMASK=0xffffff00
CONFIG_NSH_ROMFSMOUNTPT="/etc"
CONFIG_NSH_INITSCRIPT="init.d/rcS"
CONFIG_NSH_ROMFSDEVNO=0
@@ -1008,13 +971,6 @@ CONFIG_NSH_MMCSDSPIPORTNO=3
CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDMINOR=0
-#
-# Settings for mavlink
-#
-# CONFIG_MAVLINK - Enable MAVLINK app
-# CONFIG_NSH_BUILTIN_APPS - Build the ADC test as an NSH built-in function.
-# Default: Built as a standalone problem
-CONFIG_MAVLINK=y
#
# Stack and heap information
diff --git a/nuttx/configs/px4io/io/Make.defs b/nuttx/configs/px4io/io/Make.defs
index 87508e22e..369772d03 100644
--- a/nuttx/configs/px4io/io/Make.defs
+++ b/nuttx/configs/px4io/io/Make.defs
@@ -1,3 +1,3 @@
include ${TOPDIR}/.config
-include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
+include $(TOPDIR)/configs/px4io/common/Make.defs
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 8ae6afe3c..6f3131bf1 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -1,7 +1,8 @@
############################################################################
# configs/px4io/nsh/defconfig
#
-# Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# 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
@@ -41,7 +42,7 @@
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
-# specific architecture within the chip familyl.
+# specific architecture within the chip family.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
@@ -51,7 +52,6 @@
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
-# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
@@ -69,17 +69,16 @@
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
-CONFIG_ARCH=arm
+CONFIG_ARCH="arm"
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM3=y
-CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F100C8=y
-CONFIG_ARCH_BOARD=px4io
+CONFIG_ARCH_BOARD="px4io"
CONFIG_ARCH_BOARD_PX4IO=y
CONFIG_BOARD_LOOPSPERMSEC=2000
CONFIG_DRAM_SIZE=0x00002000
CONFIG_DRAM_START=0x20000000
-CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
@@ -109,6 +108,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
# Individual subsystems can be enabled:
+#
# AHB:
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
@@ -140,10 +140,6 @@ CONFIG_STM32_TIM8=n
CONFIG_STM32_USART1=y
CONFIG_STM32_ADC3=n
-#
-# Timer and I2C devices may need to the following to force power to be applied:
-#
-#CONFIG_STM32_FORCEPOWER=y
#
# STM32F100 specific serial device driver settings
@@ -306,9 +302,6 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
# desciptors by task_create() when a new task is started. If
# set, all sockets will appear to be closed in the new task.
-# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
-# This format will support execution of NuttX binaries located
-# in a ROMFS filesystem (see examples/nxflat).
# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
# handle delayed processing from interrupt handlers. This feature
# is required for some drivers but, if there are not complaints,
@@ -327,11 +320,25 @@ CONFIG_HAVE_LIBM=n
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
CONFIG_HAVE_CXX=n
CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=1
@@ -340,9 +347,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2009
-CONFIG_START_MONTH=9
-CONFIG_START_DAY=21
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
@@ -354,12 +361,13 @@ CONFIG_SEM_NNESTPRIO=0
CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
-CONFIG_NXFLAT=n
CONFIG_SCHED_WORKQUEUE=n
CONFIG_SCHED_WORKPRIORITY=50
CONFIG_SCHED_WORKPERIOD=(50*1000)
CONFIG_SCHED_WORKSTACKSIZE=1024
CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=n
+CONFIG_SCHED_ATEXIT=n
#
# The following can be used to disable categories of
@@ -427,6 +435,14 @@ CONFIG_ARCH_BZERO=n
# CONFIG_NAME_MAX - The maximum size of a file name.
# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
# CONFIG_NUNGET_CHARS - Number of characters that can be
# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
@@ -452,6 +468,7 @@ CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=32
CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=n
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32