From 2e5809d051121cbb73d92bf98be0a2952f1dbd2e Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 6 Apr 2013 00:04:59 -0700 Subject: Fix the remaining pieces so that we can build a firmware image for FMUv2 --- Images/px4fmuv2.prototype | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 Images/px4fmuv2.prototype (limited to 'Images') diff --git a/Images/px4fmuv2.prototype b/Images/px4fmuv2.prototype new file mode 100644 index 000000000..5109b77d1 --- /dev/null +++ b/Images/px4fmuv2.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 9, + "magic": "PX4FWv1", + "description": "Firmware for the PX4FMUv2 board", + "image": "", + "build_time": 0, + "summary": "PX4FMUv2", + "version": "0.1", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} -- cgit v1.2.3 From 1df5e98aa507c7a89f1491254d7f34f94c04ede6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Apr 2013 14:50:05 +0200 Subject: XXX: WIP: Disabled mixer on IOv2 due to CXX compile issue --- Images/px4iov2.prototype | 12 + apps/drivers/boards/px4iov2/Makefile | 41 -- makefiles/board_px4iov2.mk | 10 + makefiles/config_px4iov2_default.mk | 10 + nuttx/configs/px4fmuv2/nsh/appconfig | 86 ---- nuttx/configs/px4iov2/include/board.h | 11 + nuttx/configs/px4iov2/include/drv_i2c_device.h | 42 -- nuttx/configs/px4iov2/io/appconfig | 8 - nuttx/configs/px4iov2/io/defconfig | 2 +- nuttx/configs/px4iov2/src/drv_i2c_device.c | 618 ------------------------- src/drivers/boards/px4iov2/module.mk | 6 + src/drivers/boards/px4iov2/px4iov2_init.c | 171 +++++++ src/drivers/boards/px4iov2/px4iov2_internal.h | 112 +++++ src/drivers/boards/px4iov2/px4iov2_pwm_servo.c | 123 +++++ 14 files changed, 456 insertions(+), 796 deletions(-) create mode 100644 Images/px4iov2.prototype delete mode 100644 apps/drivers/boards/px4iov2/Makefile create mode 100644 makefiles/board_px4iov2.mk create mode 100644 makefiles/config_px4iov2_default.mk delete mode 100644 nuttx/configs/px4iov2/include/drv_i2c_device.h delete mode 100644 nuttx/configs/px4iov2/src/drv_i2c_device.c create mode 100644 src/drivers/boards/px4iov2/module.mk create mode 100644 src/drivers/boards/px4iov2/px4iov2_init.c create mode 100755 src/drivers/boards/px4iov2/px4iov2_internal.h create mode 100644 src/drivers/boards/px4iov2/px4iov2_pwm_servo.c (limited to 'Images') diff --git a/Images/px4iov2.prototype b/Images/px4iov2.prototype new file mode 100644 index 000000000..af87924e9 --- /dev/null +++ b/Images/px4iov2.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 10, + "magic": "PX4FWv2", + "description": "Firmware for the PX4IOv2 board", + "image": "", + "build_time": 0, + "summary": "PX4IOv2", + "version": "2.0", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/apps/drivers/boards/px4iov2/Makefile b/apps/drivers/boards/px4iov2/Makefile deleted file mode 100644 index 85806fe6f..000000000 --- a/apps/drivers/boards/px4iov2/Makefile +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################ -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# -# 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 PX4 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. -# -############################################################################ - -# -# Board-specific startup code for the PX4IO -# - -INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common -LIBNAME = brd_px4io - -include $(APPDIR)/mk/app.mk diff --git a/makefiles/board_px4iov2.mk b/makefiles/board_px4iov2.mk new file mode 100644 index 000000000..ee6b6125e --- /dev/null +++ b/makefiles/board_px4iov2.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4IOv2 +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM3 + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/config_px4iov2_default.mk b/makefiles/config_px4iov2_default.mk new file mode 100644 index 000000000..f9f35d629 --- /dev/null +++ b/makefiles/config_px4iov2_default.mk @@ -0,0 +1,10 @@ +# +# Makefile for the px4iov2_default configuration +# + +# +# Board support modules +# +MODULES += drivers/stm32 +MODULES += drivers/boards/px4iov2 +MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/nuttx/configs/px4fmuv2/nsh/appconfig b/nuttx/configs/px4fmuv2/nsh/appconfig index d945f3d88..0e18aa8ef 100644 --- a/nuttx/configs/px4fmuv2/nsh/appconfig +++ b/nuttx/configs/px4fmuv2/nsh/appconfig @@ -41,92 +41,6 @@ CONFIGURED_APPS += examples/nsh CONFIGURED_APPS += nshlib CONFIGURED_APPS += system/readline -# System library - utility functions -CONFIGURED_APPS += systemlib -CONFIGURED_APPS += systemlib/mixer - -# Math library -ifneq ($(CONFIG_APM),y) -CONFIGURED_APPS += mathlib -CONFIGURED_APPS += mathlib/CMSIS -CONFIGURED_APPS += examples/math_demo -endif - -# Control library -ifneq ($(CONFIG_APM),y) -CONFIGURED_APPS += controllib -CONFIGURED_APPS += examples/control_demo -CONFIGURED_APPS += examples/kalman_demo -endif - -# System utility commands -CONFIGURED_APPS += systemcmds/reboot -CONFIGURED_APPS += systemcmds/perf -CONFIGURED_APPS += systemcmds/top -CONFIGURED_APPS += systemcmds/boardinfo -CONFIGURED_APPS += systemcmds/mixer -CONFIGURED_APPS += systemcmds/param -CONFIGURED_APPS += systemcmds/pwm -CONFIGURED_APPS += systemcmds/bl_update -CONFIGURED_APPS += systemcmds/preflight_check -CONFIGURED_APPS += systemcmds/delay_test - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/hello_sky -# CONFIGURED_APPS += examples/px4_simple_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/deamon -# CONFIGURED_APPS += examples/px4_deamon_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/debug_values -# CONFIGURED_APPS += examples/px4_mavlink_debug - -# Shared object broker; required by many parts of the system. -CONFIGURED_APPS += uORB - -CONFIGURED_APPS += mavlink -CONFIGURED_APPS += mavlink_onboard -CONFIGURED_APPS += commander -CONFIGURED_APPS += sdlog -CONFIGURED_APPS += sensors - -ifneq ($(CONFIG_APM),y) -CONFIGURED_APPS += multirotor_att_control -CONFIGURED_APPS += multirotor_pos_control -CONFIGURED_APPS += fixedwing_att_control -CONFIGURED_APPS += fixedwing_pos_control -CONFIGURED_APPS += position_estimator -CONFIGURED_APPS += attitude_estimator_ekf -CONFIGURED_APPS += hott_telemetry -endif - -# Hacking tools -# XXX needs updating for new i2c config -#CONFIGURED_APPS += systemcmds/i2c - -# Communication and Drivers -CONFIGURED_APPS += drivers/boards/px4fmuv2 -CONFIGURED_APPS += drivers/device -# XXX needs conversion to SPI -#CONFIGURED_APPS += drivers/ms5611 -# XXX needs conversion to serial -#CONFIGURED_APPS += drivers/px4io -CONFIGURED_APPS += drivers/stm32 -#CONFIGURED_APPS += drivers/led -CONFIGURED_APPS += drivers/blinkm -CONFIGURED_APPS += drivers/stm32/tone_alarm -CONFIGURED_APPS += drivers/stm32/adc -#CONFIGURED_APPS += drivers/px4fmu -CONFIGURED_APPS += drivers/hil -CONFIGURED_APPS += drivers/gps -CONFIGURED_APPS += drivers/mb12xx - -# Testing stuff -CONFIGURED_APPS += px4/sensors_bringup -CONFIGURED_APPS += px4/tests - ifeq ($(CONFIG_CAN),y) #CONFIGURED_APPS += examples/can endif diff --git a/nuttx/configs/px4iov2/include/board.h b/nuttx/configs/px4iov2/include/board.h index b8dc71144..21aacda87 100755 --- a/nuttx/configs/px4iov2/include/board.h +++ b/nuttx/configs/px4iov2/include/board.h @@ -100,12 +100,19 @@ * Some of the USART pins are not available; override the GPIO * definitions with an invalid pin configuration. */ +#undef GPIO_USART2_CTS #define GPIO_USART2_CTS 0xffffffff +#undef GPIO_USART2_RTS #define GPIO_USART2_RTS 0xffffffff +#undef GPIO_USART2_CK #define GPIO_USART2_CK 0xffffffff +#undef GPIO_USART3_TX #define GPIO_USART3_TX 0xffffffff +#undef GPIO_USART3_CK #define GPIO_USART3_CK 0xffffffff +#undef GPIO_USART3_CTS #define GPIO_USART3_CTS 0xffffffff +#undef GPIO_USART3_RTS #define GPIO_USART3_RTS 0xffffffff /* @@ -168,6 +175,10 @@ extern "C" { ************************************************************************************/ EXTERN void stm32_boardinitialize(void); + +#if defined(__cplusplus) +} +#endif #endif /* __ASSEMBLY__ */ #endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx/configs/px4iov2/include/drv_i2c_device.h b/nuttx/configs/px4iov2/include/drv_i2c_device.h deleted file mode 100644 index 02582bc09..000000000 --- a/nuttx/configs/px4iov2/include/drv_i2c_device.h +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * - * 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 PX4 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. - * - ****************************************************************************/ - - /** - * @file A simple, polled I2C slave-mode driver. - * - * The master writes to and reads from a byte buffer, which the caller - * can update inbetween calls to the FSM. - */ - -extern void i2c_fsm_init(uint8_t *buffer, size_t buffer_size); -extern bool i2c_fsm(void); diff --git a/nuttx/configs/px4iov2/io/appconfig b/nuttx/configs/px4iov2/io/appconfig index 628607a51..48a41bcdb 100644 --- a/nuttx/configs/px4iov2/io/appconfig +++ b/nuttx/configs/px4iov2/io/appconfig @@ -30,11 +30,3 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ - -CONFIGURED_APPS += drivers/boards/px4io -CONFIGURED_APPS += drivers/stm32 - -CONFIGURED_APPS += px4io - -# Mixer library from systemlib -CONFIGURED_APPS += systemlib/mixer diff --git a/nuttx/configs/px4iov2/io/defconfig b/nuttx/configs/px4iov2/io/defconfig index bb937cf4e..c73f0df89 100755 --- a/nuttx/configs/px4iov2/io/defconfig +++ b/nuttx/configs/px4iov2/io/defconfig @@ -127,7 +127,7 @@ CONFIG_STM32_WWDG=n CONFIG_STM32_SPI2=n CONFIG_STM32_USART2=y CONFIG_STM32_USART3=y -CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C1=n CONFIG_STM32_I2C2=n CONFIG_STM32_BKP=n CONFIG_STM32_PWR=n diff --git a/nuttx/configs/px4iov2/src/drv_i2c_device.c b/nuttx/configs/px4iov2/src/drv_i2c_device.c deleted file mode 100644 index 1f5931ae5..000000000 --- a/nuttx/configs/px4iov2/src/drv_i2c_device.c +++ /dev/null @@ -1,618 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * - * 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 PX4 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. - * - ****************************************************************************/ - - /** - * @file A simple, polled I2C slave-mode driver. - * - * The master writes to and reads from a byte buffer, which the caller - * can update inbetween calls to the FSM. - */ - -#include - -#include "stm32_i2c.h" - -#include - -/* - * I2C register definitions. - */ -#define I2C_BASE STM32_I2C1_BASE - -#define REG(_reg) (*(volatile uint32_t *)(I2C_BASE + _reg)) - -#define rCR1 REG(STM32_I2C_CR1_OFFSET) -#define rCR2 REG(STM32_I2C_CR2_OFFSET) -#define rOAR1 REG(STM32_I2C_OAR1_OFFSET) -#define rOAR2 REG(STM32_I2C_OAR2_OFFSET) -#define rDR REG(STM32_I2C_DR_OFFSET) -#define rSR1 REG(STM32_I2C_SR1_OFFSET) -#define rSR2 REG(STM32_I2C_SR2_OFFSET) -#define rCCR REG(STM32_I2C_CCR_OFFSET) -#define rTRISE REG(STM32_I2C_TRISE_OFFSET) - -/* - * "event" values (cr2 << 16 | cr1) as described in the ST DriverLib - */ -#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ -#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ -#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ -#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ -#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ -#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ -#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ - -/** - * States implemented by the I2C FSM. - */ -enum fsm_state { - BAD_PHASE, // must be zero, default exit on a bad state transition - - WAIT_FOR_MASTER, - - /* write from master */ - WAIT_FOR_COMMAND, - RECEIVE_COMMAND, - RECEIVE_DATA, - HANDLE_COMMAND, - - /* read from master */ - WAIT_TO_SEND, - SEND_STATUS, - SEND_DATA, - - NUM_STATES -}; - -/** - * Events recognised by the I2C FSM. - */ -enum fsm_event { - /* automatic transition */ - AUTO, - - /* write from master */ - ADDRESSED_WRITE, - BYTE_RECEIVED, - STOP_RECEIVED, - - /* read from master */ - ADDRESSED_READ, - BYTE_SENDABLE, - ACK_FAILED, - - NUM_EVENTS -}; - -/** - * Context for the I2C FSM - */ -static struct fsm_context { - enum fsm_state state; - - /* XXX want to eliminate these */ - uint8_t command; - uint8_t status; - - uint8_t *data_ptr; - uint32_t data_count; - - size_t buffer_size; - uint8_t *buffer; -} context; - -/** - * Structure defining one FSM state and its outgoing transitions. - */ -struct fsm_transition { - void (*handler)(void); - enum fsm_state next_state[NUM_EVENTS]; -}; - -static bool i2c_command_received; - -static void fsm_event(enum fsm_event event); - -static void go_bad(void); -static void go_wait_master(void); - -static void go_wait_command(void); -static void go_receive_command(void); -static void go_receive_data(void); -static void go_handle_command(void); - -static void go_wait_send(void); -static void go_send_status(void); -static void go_send_buffer(void); - -/** - * The FSM state graph. - */ -static const struct fsm_transition fsm[NUM_STATES] = { - [BAD_PHASE] = { - .handler = go_bad, - .next_state = { - [AUTO] = WAIT_FOR_MASTER, - }, - }, - - [WAIT_FOR_MASTER] = { - .handler = go_wait_master, - .next_state = { - [ADDRESSED_WRITE] = WAIT_FOR_COMMAND, - [ADDRESSED_READ] = WAIT_TO_SEND, - }, - }, - - /* write from master*/ - [WAIT_FOR_COMMAND] = { - .handler = go_wait_command, - .next_state = { - [BYTE_RECEIVED] = RECEIVE_COMMAND, - [STOP_RECEIVED] = WAIT_FOR_MASTER, - }, - }, - [RECEIVE_COMMAND] = { - .handler = go_receive_command, - .next_state = { - [BYTE_RECEIVED] = RECEIVE_DATA, - [STOP_RECEIVED] = HANDLE_COMMAND, - }, - }, - [RECEIVE_DATA] = { - .handler = go_receive_data, - .next_state = { - [BYTE_RECEIVED] = RECEIVE_DATA, - [STOP_RECEIVED] = HANDLE_COMMAND, - }, - }, - [HANDLE_COMMAND] = { - .handler = go_handle_command, - .next_state = { - [AUTO] = WAIT_FOR_MASTER, - }, - }, - - /* buffer send */ - [WAIT_TO_SEND] = { - .handler = go_wait_send, - .next_state = { - [BYTE_SENDABLE] = SEND_STATUS, - }, - }, - [SEND_STATUS] = { - .handler = go_send_status, - .next_state = { - [BYTE_SENDABLE] = SEND_DATA, - [ACK_FAILED] = WAIT_FOR_MASTER, - }, - }, - [SEND_DATA] = { - .handler = go_send_buffer, - .next_state = { - [BYTE_SENDABLE] = SEND_DATA, - [ACK_FAILED] = WAIT_FOR_MASTER, - }, - }, -}; - - -/* debug support */ -#if 1 -struct fsm_logentry { - char kind; - uint32_t code; -}; - -#define LOG_ENTRIES 32 -static struct fsm_logentry fsm_log[LOG_ENTRIES]; -int fsm_logptr; -#define LOG_NEXT(_x) (((_x) + 1) % LOG_ENTRIES) -#define LOGx(_kind, _code) \ - do { \ - fsm_log[fsm_logptr].kind = _kind; \ - fsm_log[fsm_logptr].code = _code; \ - fsm_logptr = LOG_NEXT(fsm_logptr); \ - fsm_log[fsm_logptr].kind = 0; \ - } while(0) - -#define LOG(_kind, _code) \ - do {\ - if (fsm_logptr < LOG_ENTRIES) { \ - fsm_log[fsm_logptr].kind = _kind; \ - fsm_log[fsm_logptr].code = _code; \ - fsm_logptr++;\ - }\ - }while(0) - -#else -#define LOG(_kind, _code) -#endif - - -static void i2c_setclock(uint32_t frequency); - -/** - * Initialise I2C - * - */ -void -i2c_fsm_init(uint8_t *buffer, size_t buffer_size) -{ - /* save the buffer */ - context.buffer = buffer; - context.buffer_size = buffer_size; - - // initialise the FSM - context.status = 0; - context.command = 0; - context.state = BAD_PHASE; - fsm_event(AUTO); - -#if 0 - // enable the i2c block clock and reset it - modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN); - modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST); - modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0); - - // configure the i2c GPIOs - stm32_configgpio(GPIO_I2C1_SCL); - stm32_configgpio(GPIO_I2C1_SDA); - - // set the peripheral clock to match the APB clock - rCR2 = STM32_PCLK1_FREQUENCY / 1000000; - - // configure for 100kHz operation - i2c_setclock(100000); - - // enable i2c - rCR1 = I2C_CR1_PE; -#endif -} - -/** - * Run the I2C FSM for some period. - * - * @return True if the buffer has been updated by a command. - */ -bool -i2c_fsm(void) -{ - uint32_t event; - int idle_iterations = 0; - - for (;;) { - // handle bus error states by discarding the current operation - if (rSR1 & I2C_SR1_BERR) { - context.state = WAIT_FOR_MASTER; - rSR1 = ~I2C_SR1_BERR; - } - - // we do not anticipate over/underrun errors as clock-stretching is enabled - - // fetch the most recent event - event = ((rSR2 << 16) | rSR1) & 0x00ffffff; - - // generate FSM events based on I2C events - switch (event) { - case I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED: - LOG('w', 0); - fsm_event(ADDRESSED_WRITE); - break; - - case I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED: - LOG('r', 0); - fsm_event(ADDRESSED_READ); - break; - - case I2C_EVENT_SLAVE_BYTE_RECEIVED: - LOG('R', 0); - fsm_event(BYTE_RECEIVED); - break; - - case I2C_EVENT_SLAVE_STOP_DETECTED: - LOG('s', 0); - fsm_event(STOP_RECEIVED); - break; - - case I2C_EVENT_SLAVE_BYTE_TRANSMITTING: - //case I2C_EVENT_SLAVE_BYTE_TRANSMITTED: - LOG('T', 0); - fsm_event(BYTE_SENDABLE); - break; - - case I2C_EVENT_SLAVE_ACK_FAILURE: - LOG('a', 0); - fsm_event(ACK_FAILED); - break; - - default: - idle_iterations++; -// if ((event) && (event != 0x00020000)) -// LOG('e', event); - break; - } - - /* if we have just received something, drop out and let the caller handle it */ - if (i2c_command_received) { - i2c_command_received = false; - return true; - } - - /* if we have done nothing recently, drop out and let the caller have a slice */ - if (idle_iterations > 1000) - return false; - } -} - -/** - * Update the FSM with an event - * - * @param event New event. - */ -static void -fsm_event(enum fsm_event event) -{ - // move to the next state - context.state = fsm[context.state].next_state[event]; - - LOG('f', context.state); - - // call the state entry handler - if (fsm[context.state].handler) { - fsm[context.state].handler(); - } -} - -static void -go_bad() -{ - LOG('B', 0); - fsm_event(AUTO); -} - -/** - * Wait for the master to address us. - * - */ -static void -go_wait_master() -{ - // We currently don't have a command byte. - // - context.command = '\0'; - - // The data pointer starts pointing to the start of the data buffer. - // - context.data_ptr = context.buffer; - - // The data count is either: - // - the size of the data buffer - // - some value less than or equal the size of the data buffer during a write or a read - // - context.data_count = context.buffer_size; - - // (re)enable the peripheral, clear the stop event flag in - // case we just finished receiving data - rCR1 |= I2C_CR1_PE; - - // clear the ACK failed flag in case we just finished sending data - rSR1 = ~I2C_SR1_AF; -} - -/** - * Prepare to receive a command byte. - * - */ -static void -go_wait_command() -{ - // NOP -} - -/** - * Command byte has been received, save it and prepare to handle the data. - * - */ -static void -go_receive_command() -{ - - // fetch the command byte - context.command = (uint8_t)rDR; - LOG('c', context.command); - -} - -/** - * Receive a data byte. - * - */ -static void -go_receive_data() -{ - uint8_t d; - - // fetch the byte - d = (uint8_t)rDR; - LOG('d', d); - - // if we have somewhere to put it, do so - if (context.data_count) { - *context.data_ptr++ = d; - context.data_count--; - } -} - -/** - * Handle a command once the host is done sending it to us. - * - */ -static void -go_handle_command() -{ - // presume we are happy with the command - context.status = 0; - - // make a note that the buffer contains a fresh command - i2c_command_received = true; - - // kick along to the next state - fsm_event(AUTO); -} - -/** - * Wait to be able to send the status byte. - * - */ -static void -go_wait_send() -{ - // NOP -} - -/** - * Send the status byte. - * - */ -static void -go_send_status() -{ - rDR = context.status; - LOG('?', context.status); -} - -/** - * Send a data or pad byte. - * - */ -static void -go_send_buffer() -{ - if (context.data_count) { - LOG('D', *context.data_ptr); - rDR = *(context.data_ptr++); - context.data_count--; - } else { - LOG('-', 0); - rDR = 0xff; - } -} - -/* cribbed directly from the NuttX master driver */ -static void -i2c_setclock(uint32_t frequency) -{ - uint16_t cr1; - uint16_t ccr; - uint16_t trise; - uint16_t freqmhz; - uint16_t speed; - - /* Disable the selected I2C peripheral to configure TRISE */ - - cr1 = rCR1; - rCR1 &= ~I2C_CR1_PE; - - /* Update timing and control registers */ - - freqmhz = (uint16_t)(STM32_PCLK1_FREQUENCY / 1000000); - ccr = 0; - - /* Configure speed in standard mode */ - - if (frequency <= 100000) { - /* Standard mode speed calculation */ - - speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency << 1)); - - /* The CCR fault must be >= 4 */ - - if (speed < 4) { - /* Set the minimum allowed value */ - - speed = 4; - } - ccr |= speed; - - /* Set Maximum Rise Time for standard mode */ - - trise = freqmhz + 1; - - /* Configure speed in fast mode */ - } else { /* (frequency <= 400000) */ - /* Fast mode speed calculation with Tlow/Thigh = 16/9 */ - -#ifdef CONFIG_I2C_DUTY16_9 - speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25)); - - /* Set DUTY and fast speed bits */ - - ccr |= (I2C_CCR_DUTY|I2C_CCR_FS); -#else - /* Fast mode speed calculation with Tlow/Thigh = 2 */ - - speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 3)); - - /* Set fast speed bit */ - - ccr |= I2C_CCR_FS; -#endif - - /* Verify that the CCR speed value is nonzero */ - - if (speed < 1) { - /* Set the minimum allowed value */ - - speed = 1; - } - ccr |= speed; - - /* Set Maximum Rise Time for fast mode */ - - trise = (uint16_t)(((freqmhz * 300) / 1000) + 1); - } - - /* Write the new values of the CCR and TRISE registers */ - - rCCR = ccr; - rTRISE = trise; - - /* Bit 14 of OAR1 must be configured and kept at 1 */ - - rOAR1 = I2C_OAR1_ONE); - - /* Re-enable the peripheral (or not) */ - - rCR1 = cr1; -} diff --git a/src/drivers/boards/px4iov2/module.mk b/src/drivers/boards/px4iov2/module.mk new file mode 100644 index 000000000..85f94e8be --- /dev/null +++ b/src/drivers/boards/px4iov2/module.mk @@ -0,0 +1,6 @@ +# +# Board-specific startup code for the PX4IOv2 +# + +SRCS = px4iov2_init.c \ + px4iov2_pwm_servo.c diff --git a/src/drivers/boards/px4iov2/px4iov2_init.c b/src/drivers/boards/px4iov2/px4iov2_init.c new file mode 100644 index 000000000..09469d7e8 --- /dev/null +++ b/src/drivers/boards/px4iov2/px4iov2_init.c @@ -0,0 +1,171 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +/** + * @file px4iov2_init.c + * + * PX4FMU-specific early startup code. This file implements the + * nsh_archinitialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "stm32_internal.h" +#include "px4iov2_internal.h" + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lowsyslog(__VA_ARGS__) +# else +# define message(...) printf(__VA_ARGS__) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lowsyslog +# else +# define message printf +# endif +#endif + +/**************************************************************************** + * Protected 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. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + + /* configure GPIOs */ + + /* turn off - all leds are active low */ + stm32_gpiowrite(GPIO_LED1, true); + stm32_gpiowrite(GPIO_LED2, true); + stm32_gpiowrite(GPIO_LED3, true); + stm32_configgpio(GPIO_LED1); + stm32_configgpio(GPIO_LED2); + stm32_configgpio(GPIO_LED3); + + + stm32_configgpio(GPIO_BTN_SAFETY); + + /* spektrum power enable is active high - disable it by default */ + stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, false); + stm32_configgpio(GPIO_SPEKTRUM_PWR_EN); + + /* servo power enable is active low, and has a pull down resistor + * to keep it low during boot (since it may power the whole board.) + */ + stm32_gpiowrite(GPIO_SERVO_PWR_EN, false); + stm32_configgpio(GPIO_SERVO_PWR_EN); + + stm32_configgpio(GPIO_SERVO_FAULT_DETECT); + + stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */ + stm32_configgpio(GPIO_ADC_RSSI); + stm32_configgpio(GPIO_ADC_VSERVO); + + stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */ + + stm32_gpiowrite(GPIO_SBUS_OUTPUT, false); + stm32_configgpio(GPIO_SBUS_OUTPUT); + + /* sbus output enable is active low - disable it by default */ + stm32_gpiowrite(GPIO_SBUS_OENABLE, true); + stm32_configgpio(GPIO_SBUS_OENABLE); + + + stm32_configgpio(GPIO_PPM); /* xxx alternate function */ + + stm32_gpiowrite(GPIO_PWM1, false); + stm32_configgpio(GPIO_PWM1); + + stm32_gpiowrite(GPIO_PWM2, false); + stm32_configgpio(GPIO_PWM2); + + stm32_gpiowrite(GPIO_PWM3, false); + stm32_configgpio(GPIO_PWM3); + + stm32_gpiowrite(GPIO_PWM4, false); + stm32_configgpio(GPIO_PWM4); + + stm32_gpiowrite(GPIO_PWM5, false); + stm32_configgpio(GPIO_PWM5); + + stm32_gpiowrite(GPIO_PWM6, false); + stm32_configgpio(GPIO_PWM6); + + stm32_gpiowrite(GPIO_PWM7, false); + stm32_configgpio(GPIO_PWM7); + + stm32_gpiowrite(GPIO_PWM8, false); + stm32_configgpio(GPIO_PWM8); + +// message("[boot] Successfully initialized px4iov2 gpios\n"); +} diff --git a/src/drivers/boards/px4iov2/px4iov2_internal.h b/src/drivers/boards/px4iov2/px4iov2_internal.h new file mode 100755 index 000000000..c4c592fe4 --- /dev/null +++ b/src/drivers/boards/px4iov2/px4iov2_internal.h @@ -0,0 +1,112 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +/** + * @file px4iov2_internal.h + * + * PX4IOV2 internal definitions + */ + +#pragma once + +/****************************************************************************** + * Included Files + ******************************************************************************/ + +#include +#include +#include + +/* these headers are not C++ safe */ +#include + + +/****************************************************************************** + * Definitions + ******************************************************************************/ +/* Configuration **************************************************************/ + +/****************************************************************************** + * GPIOS + ******************************************************************************/ + +/* LEDS **********************************************************************/ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13) + +#define GPIO_LED_BLUE BOARD_GPIO_LED1 +#define GPIO_LED_AMBER BOARD_GPIO_LED2 +#define GPIO_LED_SAFETY BOARD_GPIO_LED3 + +/* Safety switch button *******************************************************/ + +#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5) + +/* Power switch controls ******************************************************/ + +#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +#define GPIO_SERVO_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15) + +#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13) + + +/* Analog inputs **************************************************************/ + +#define GPIO_ADC_VSERVO (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4) +/* the same rssi signal goes to both an adc and a timer input */ +#define GPIO_ADC_RSSI (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5) +/* floating pin */ +#define GPIO_TIM_RSSI (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12) + +/* PWM pins **************************************************************/ + +#define GPIO_PPM (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8) + +#define GPIO_PWM1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0) +#define GPIO_PWM2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1) +#define GPIO_PWM3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8) +#define GPIO_PWM4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) +#define GPIO_PWM5 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6) +#define GPIO_PWM6 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7) +#define GPIO_PWM7 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0) +#define GPIO_PWM8 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1) + +/* SBUS pins *************************************************************/ + +#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11) +#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4) + diff --git a/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c b/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c new file mode 100644 index 000000000..5e1aafa49 --- /dev/null +++ b/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +/* + * @file px4iov2_pwm_servo.c + * + * Configuration data for the stm32 pwm_servo driver. + * + * Note that these arrays must always be fully-sized. + */ + +#include + +#include + +#include +#include + +#include +#include +#include + +__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = { + { + .base = STM32_TIM2_BASE, + .clock_register = STM32_RCC_APB1ENR, + .clock_bit = RCC_APB1ENR_TIM2EN, + .clock_freq = STM32_APB1_TIM2_CLKIN + }, + { + .base = STM32_TIM3_BASE, + .clock_register = STM32_RCC_APB1ENR, + .clock_bit = RCC_APB1ENR_TIM3EN, + .clock_freq = STM32_APB1_TIM3_CLKIN + }, + { + .base = STM32_TIM4_BASE, + .clock_register = STM32_RCC_APB1ENR, + .clock_bit = RCC_APB1ENR_TIM4EN, + .clock_freq = STM32_APB1_TIM4_CLKIN + } +}; + +__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = { + { + .gpio = GPIO_TIM2_CH1OUT, + .timer_index = 0, + .timer_channel = 1, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM2_CH2OUT, + .timer_index = 0, + .timer_channel = 2, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM4_CH3OUT, + .timer_index = 2, + .timer_channel = 3, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM4_CH4OUT, + .timer_index = 2, + .timer_channel = 4, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM3_CH1OUT, + .timer_index = 1, + .timer_channel = 1, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM3_CH2OUT, + .timer_index = 1, + .timer_channel = 2, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM3_CH3OUT, + .timer_index = 1, + .timer_channel = 3, + .default_value = 1000, + }, + { + .gpio = GPIO_TIM3_CH4OUT, + .timer_index = 1, + .timer_channel = 4, + .default_value = 1000, + } +}; -- cgit v1.2.3 From b4029dd824cec7a0b53c62e960f80d90ddc6e13c Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 7 Jul 2013 17:53:55 -0700 Subject: Pull v2 pieces up to build with the merge --- Images/px4fmu-v2.prototype | 12 + Images/px4fmuv2.prototype | 12 - Images/px4io-v2.prototype | 12 + Makefile | 87 +- makefiles/board_px4fmu-v2.mk | 10 + makefiles/board_px4fmuv2.mk | 10 - makefiles/board_px4io-v2.mk | 10 + makefiles/board_px4iov2.mk | 10 - makefiles/config_px4fmu-v2_default.mk | 122 +++ makefiles/config_px4fmu-v2_test.mk | 40 + makefiles/config_px4fmuv2_default.mk | 122 --- makefiles/config_px4fmuv2_test.mk | 45 - makefiles/config_px4io-v2_default.mk | 10 + makefiles/config_px4iov2_default.mk | 10 - makefiles/setup.mk | 1 - makefiles/upload.mk | 2 +- nuttx-configs/px4fmu-v2/Kconfig | 7 + nuttx-configs/px4fmu-v2/common/Make.defs | 184 ++++ nuttx-configs/px4fmu-v2/common/ld.script | 150 ++++ nuttx-configs/px4fmu-v2/include/board.h | 364 ++++++++ nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h | 42 + nuttx-configs/px4fmu-v2/nsh/Make.defs | 3 + nuttx-configs/px4fmu-v2/nsh/appconfig | 52 ++ nuttx-configs/px4fmu-v2/nsh/defconfig | 1022 ++++++++++++++++++++++ nuttx-configs/px4fmu-v2/nsh/defconfig.prev | 1067 +++++++++++++++++++++++ nuttx-configs/px4fmu-v2/nsh/setenv.sh | 67 ++ nuttx-configs/px4fmu-v2/src/Makefile | 84 ++ nuttx-configs/px4fmu-v2/src/empty.c | 4 + nuttx-configs/px4io-v2/README.txt | 806 ++++++++++++++++++ nuttx-configs/px4io-v2/common/Make.defs | 175 ++++ nuttx-configs/px4io-v2/common/ld.script | 129 +++ nuttx-configs/px4io-v2/common/setenv.sh | 47 + nuttx-configs/px4io-v2/include/README.txt | 1 + nuttx-configs/px4io-v2/include/board.h | 177 ++++ nuttx-configs/px4io-v2/nsh/Make.defs | 3 + nuttx-configs/px4io-v2/nsh/appconfig | 32 + nuttx-configs/px4io-v2/nsh/defconfig | 526 ++++++++++++ nuttx-configs/px4io-v2/nsh/setenv.sh | 47 + nuttx-configs/px4io-v2/src/Makefile | 84 ++ nuttx-configs/px4io-v2/src/README.txt | 1 + nuttx-configs/px4io-v2/src/empty.c | 4 + nuttx-configs/px4io-v2/test/Make.defs | 3 + nuttx-configs/px4io-v2/test/appconfig | 44 + nuttx-configs/px4io-v2/test/defconfig | 544 ++++++++++++ nuttx-configs/px4io-v2/test/setenv.sh | 47 + nuttx/configs/px4fmuv2/Kconfig | 7 - nuttx/configs/px4fmuv2/common/Make.defs | 184 ---- nuttx/configs/px4fmuv2/common/ld.script | 150 ---- nuttx/configs/px4fmuv2/include/board.h | 364 -------- nuttx/configs/px4fmuv2/include/nsh_romfsimg.h | 42 - nuttx/configs/px4fmuv2/nsh/Make.defs | 3 - nuttx/configs/px4fmuv2/nsh/appconfig | 52 -- nuttx/configs/px4fmuv2/nsh/defconfig | 1083 ------------------------ nuttx/configs/px4fmuv2/nsh/setenv.sh | 67 -- nuttx/configs/px4fmuv2/src/Makefile | 84 -- nuttx/configs/px4fmuv2/src/empty.c | 4 - nuttx/configs/px4iov2/README.txt | 806 ------------------ nuttx/configs/px4iov2/common/Make.defs | 175 ---- nuttx/configs/px4iov2/common/ld.script | 129 --- nuttx/configs/px4iov2/common/setenv.sh | 47 - nuttx/configs/px4iov2/include/README.txt | 1 - nuttx/configs/px4iov2/include/board.h | 184 ---- nuttx/configs/px4iov2/io/Make.defs | 3 - nuttx/configs/px4iov2/io/appconfig | 32 - nuttx/configs/px4iov2/io/defconfig | 548 ------------ nuttx/configs/px4iov2/io/setenv.sh | 47 - nuttx/configs/px4iov2/nsh/Make.defs | 3 - nuttx/configs/px4iov2/nsh/appconfig | 44 - nuttx/configs/px4iov2/nsh/defconfig | 567 ------------- nuttx/configs/px4iov2/nsh/setenv.sh | 47 - nuttx/configs/px4iov2/src/Makefile | 84 -- nuttx/configs/px4iov2/src/README.txt | 1 - nuttx/configs/px4iov2/src/empty.c | 4 - src/drivers/boards/px4fmuv2/px4fmu_init.c | 4 +- src/drivers/boards/px4fmuv2/px4fmu_internal.h | 2 +- src/drivers/boards/px4fmuv2/px4fmu_pwm_servo.c | 2 +- src/drivers/boards/px4fmuv2/px4fmu_spi.c | 6 +- src/drivers/boards/px4fmuv2/px4fmu_usb.c | 4 +- src/drivers/boards/px4iov2/px4iov2_init.c | 2 +- src/drivers/boards/px4iov2/px4iov2_internal.h | 2 +- src/drivers/boards/px4iov2/px4iov2_pwm_servo.c | 2 +- src/drivers/drv_gpio.h | 40 +- src/drivers/px4fmu/fmu.cpp | 28 +- src/drivers/px4io/interface_serial.cpp | 1 - src/drivers/px4io/px4io.cpp | 8 +- src/drivers/px4io/uploader.cpp | 4 +- src/drivers/stm32/drv_hrt.c | 8 +- src/drivers/stm32/tone_alarm/tone_alarm.cpp | 4 - src/modules/px4iofirmware/module.mk | 4 +- src/modules/px4iofirmware/px4io.h | 30 +- src/modules/px4iofirmware/registers.c | 2 +- src/modules/px4iofirmware/serial.c | 2 +- 92 files changed, 6044 insertions(+), 5104 deletions(-) create mode 100644 Images/px4fmu-v2.prototype delete mode 100644 Images/px4fmuv2.prototype create mode 100644 Images/px4io-v2.prototype create mode 100644 makefiles/board_px4fmu-v2.mk delete mode 100644 makefiles/board_px4fmuv2.mk create mode 100644 makefiles/board_px4io-v2.mk delete mode 100644 makefiles/board_px4iov2.mk create mode 100644 makefiles/config_px4fmu-v2_default.mk create mode 100644 makefiles/config_px4fmu-v2_test.mk delete mode 100644 makefiles/config_px4fmuv2_default.mk delete mode 100644 makefiles/config_px4fmuv2_test.mk create mode 100644 makefiles/config_px4io-v2_default.mk delete mode 100644 makefiles/config_px4iov2_default.mk create mode 100644 nuttx-configs/px4fmu-v2/Kconfig create mode 100644 nuttx-configs/px4fmu-v2/common/Make.defs create mode 100644 nuttx-configs/px4fmu-v2/common/ld.script create mode 100755 nuttx-configs/px4fmu-v2/include/board.h create mode 100644 nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h create mode 100644 nuttx-configs/px4fmu-v2/nsh/Make.defs create mode 100644 nuttx-configs/px4fmu-v2/nsh/appconfig create mode 100644 nuttx-configs/px4fmu-v2/nsh/defconfig create mode 100755 nuttx-configs/px4fmu-v2/nsh/defconfig.prev create mode 100755 nuttx-configs/px4fmu-v2/nsh/setenv.sh create mode 100644 nuttx-configs/px4fmu-v2/src/Makefile create mode 100644 nuttx-configs/px4fmu-v2/src/empty.c create mode 100755 nuttx-configs/px4io-v2/README.txt create mode 100644 nuttx-configs/px4io-v2/common/Make.defs create mode 100755 nuttx-configs/px4io-v2/common/ld.script create mode 100755 nuttx-configs/px4io-v2/common/setenv.sh create mode 100755 nuttx-configs/px4io-v2/include/README.txt create mode 100755 nuttx-configs/px4io-v2/include/board.h create mode 100644 nuttx-configs/px4io-v2/nsh/Make.defs create mode 100644 nuttx-configs/px4io-v2/nsh/appconfig create mode 100755 nuttx-configs/px4io-v2/nsh/defconfig create mode 100755 nuttx-configs/px4io-v2/nsh/setenv.sh create mode 100644 nuttx-configs/px4io-v2/src/Makefile create mode 100644 nuttx-configs/px4io-v2/src/README.txt create mode 100644 nuttx-configs/px4io-v2/src/empty.c create mode 100644 nuttx-configs/px4io-v2/test/Make.defs create mode 100644 nuttx-configs/px4io-v2/test/appconfig create mode 100755 nuttx-configs/px4io-v2/test/defconfig create mode 100755 nuttx-configs/px4io-v2/test/setenv.sh delete mode 100644 nuttx/configs/px4fmuv2/Kconfig delete mode 100644 nuttx/configs/px4fmuv2/common/Make.defs delete mode 100644 nuttx/configs/px4fmuv2/common/ld.script delete mode 100755 nuttx/configs/px4fmuv2/include/board.h delete mode 100644 nuttx/configs/px4fmuv2/include/nsh_romfsimg.h delete mode 100644 nuttx/configs/px4fmuv2/nsh/Make.defs delete mode 100644 nuttx/configs/px4fmuv2/nsh/appconfig delete mode 100755 nuttx/configs/px4fmuv2/nsh/defconfig delete mode 100755 nuttx/configs/px4fmuv2/nsh/setenv.sh delete mode 100644 nuttx/configs/px4fmuv2/src/Makefile delete mode 100644 nuttx/configs/px4fmuv2/src/empty.c delete mode 100755 nuttx/configs/px4iov2/README.txt delete mode 100644 nuttx/configs/px4iov2/common/Make.defs delete mode 100755 nuttx/configs/px4iov2/common/ld.script delete mode 100755 nuttx/configs/px4iov2/common/setenv.sh delete mode 100755 nuttx/configs/px4iov2/include/README.txt delete mode 100755 nuttx/configs/px4iov2/include/board.h delete mode 100644 nuttx/configs/px4iov2/io/Make.defs delete mode 100644 nuttx/configs/px4iov2/io/appconfig delete mode 100755 nuttx/configs/px4iov2/io/defconfig delete mode 100755 nuttx/configs/px4iov2/io/setenv.sh delete mode 100644 nuttx/configs/px4iov2/nsh/Make.defs delete mode 100644 nuttx/configs/px4iov2/nsh/appconfig delete mode 100755 nuttx/configs/px4iov2/nsh/defconfig delete mode 100755 nuttx/configs/px4iov2/nsh/setenv.sh delete mode 100644 nuttx/configs/px4iov2/src/Makefile delete mode 100644 nuttx/configs/px4iov2/src/README.txt delete mode 100644 nuttx/configs/px4iov2/src/empty.c (limited to 'Images') diff --git a/Images/px4fmu-v2.prototype b/Images/px4fmu-v2.prototype new file mode 100644 index 000000000..5109b77d1 --- /dev/null +++ b/Images/px4fmu-v2.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 9, + "magic": "PX4FWv1", + "description": "Firmware for the PX4FMUv2 board", + "image": "", + "build_time": 0, + "summary": "PX4FMUv2", + "version": "0.1", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/Images/px4fmuv2.prototype b/Images/px4fmuv2.prototype deleted file mode 100644 index 5109b77d1..000000000 --- a/Images/px4fmuv2.prototype +++ /dev/null @@ -1,12 +0,0 @@ -{ - "board_id": 9, - "magic": "PX4FWv1", - "description": "Firmware for the PX4FMUv2 board", - "image": "", - "build_time": 0, - "summary": "PX4FMUv2", - "version": "0.1", - "image_size": 0, - "git_identity": "", - "board_revision": 0 -} diff --git a/Images/px4io-v2.prototype b/Images/px4io-v2.prototype new file mode 100644 index 000000000..af87924e9 --- /dev/null +++ b/Images/px4io-v2.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 10, + "magic": "PX4FWv2", + "description": "Firmware for the PX4IOv2 board", + "image": "", + "build_time": 0, + "summary": "PX4IOv2", + "version": "2.0", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/Makefile b/Makefile index 7f98ffaf2..9905f8a63 100644 --- a/Makefile +++ b/Makefile @@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES) # is taken care of. # $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 - @echo %% Copying $@ + @$(ECHO) %% Copying $@ $(Q) $(COPY) $< $@ $(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@) @@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 $(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@) $(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: - @echo %%%% - @echo %%%% Building $(config) in $(work_dir) - @echo %%%% + @$(ECHO) %%%% + @$(ECHO) %%%% Building $(config) in $(work_dir) + @$(ECHO) %%%% $(Q) mkdir -p $(work_dir) $(Q) make -r -C $(work_dir) \ -f $(PX4_MK_DIR)firmware.mk \ @@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: # XXX Should support fetching/unpacking from a separate directory to permit # downloads of the prebuilt archives as well... # -# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4" -# NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export) .PHONY: archives archives: $(NUTTX_ARCHIVES) @@ -146,16 +144,22 @@ endif $(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@)) $(ARCHIVE_DIR)%.export: configuration = nsh -$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS) - @echo %% Configuring NuttX for $(board) +$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) + @$(ECHO) %% Configuring NuttX for $(board) $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) (cd $(NUTTX_SRC)/configs && ln -sf $(PX4_BASE)/nuttx-configs/* .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) - @echo %% Exporting NuttX for $(board) + @$(ECHO) %% Exporting NuttX for $(board) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export $(Q) mkdir -p $(dir $@) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ +$(NUTTX_SRC): + @$(ECHO) "" + @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." + @$(ECHO) "" + # # Cleanup targets. 'clean' should remove all built products and force # a complete re-compilation, 'distclean' should remove everything @@ -170,46 +174,47 @@ clean: distclean: clean $(Q) $(REMOVE) $(ARCHIVE_DIR)*.export $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) (cd $(NUTTX_SRC)/configs && find . -type l -depth 1 -delete) # # Print some help text # .PHONY: help help: - @echo "" - @echo " PX4 firmware builder" - @echo " ====================" - @echo "" - @echo " Available targets:" - @echo " ------------------" - @echo "" - @echo " archives" - @echo " Build the NuttX RTOS archives that are used by the firmware build." - @echo "" - @echo " all" - @echo " Build all firmware configs: $(CONFIGS)" - @echo " A limited set of configs can be built with CONFIGS=" - @echo "" + @$(ECHO) "" + @$(ECHO) " PX4 firmware builder" + @$(ECHO) " ====================" + @$(ECHO) "" + @$(ECHO) " Available targets:" + @$(ECHO) " ------------------" + @$(ECHO) "" + @$(ECHO) " archives" + @$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build." + @$(ECHO) "" + @$(ECHO) " all" + @$(ECHO) " Build all firmware configs: $(CONFIGS)" + @$(ECHO) " A limited set of configs can be built with CONFIGS=" + @$(ECHO) "" @for config in $(CONFIGS); do \ echo " $$config"; \ echo " Build just the $$config firmware configuration."; \ echo ""; \ done - @echo " clean" - @echo " Remove all firmware build pieces." - @echo "" - @echo " distclean" - @echo " Remove all compilation products, including NuttX RTOS archives." - @echo "" - @echo " upload" - @echo " When exactly one config is being built, add this target to upload the" - @echo " firmware to the board when the build is complete. Not supported for" - @echo " all configurations." - @echo "" - @echo " Common options:" - @echo " ---------------" - @echo "" - @echo " V=1" - @echo " If V is set, more verbose output is printed during the build. This can" - @echo " help when diagnosing issues with the build or toolchain." - @echo "" + @$(ECHO) " clean" + @$(ECHO) " Remove all firmware build pieces." + @$(ECHO) "" + @$(ECHO) " distclean" + @$(ECHO) " Remove all compilation products, including NuttX RTOS archives." + @$(ECHO) "" + @$(ECHO) " upload" + @$(ECHO) " When exactly one config is being built, add this target to upload the" + @$(ECHO) " firmware to the board when the build is complete. Not supported for" + @$(ECHO) " all configurations." + @$(ECHO) "" + @$(ECHO) " Common options:" + @$(ECHO) " ---------------" + @$(ECHO) "" + @$(ECHO) " V=1" + @$(ECHO) " If V is set, more verbose output is printed during the build. This can" + @$(ECHO) " help when diagnosing issues with the build or toolchain." + @$(ECHO) "" diff --git a/makefiles/board_px4fmu-v2.mk b/makefiles/board_px4fmu-v2.mk new file mode 100644 index 000000000..4b3b7e585 --- /dev/null +++ b/makefiles/board_px4fmu-v2.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4FMUv2 +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM4F + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4fmuv2.mk b/makefiles/board_px4fmuv2.mk deleted file mode 100644 index 4b3b7e585..000000000 --- a/makefiles/board_px4fmuv2.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4FMUv2 -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM4F - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io-v2.mk b/makefiles/board_px4io-v2.mk new file mode 100644 index 000000000..ee6b6125e --- /dev/null +++ b/makefiles/board_px4io-v2.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4IOv2 +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM3 + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4iov2.mk b/makefiles/board_px4iov2.mk deleted file mode 100644 index ee6b6125e..000000000 --- a/makefiles/board_px4iov2.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4IOv2 -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM3 - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk new file mode 100644 index 000000000..c4499048c --- /dev/null +++ b/makefiles/config_px4fmu-v2_default.mk @@ -0,0 +1,122 @@ +# +# Makefile for the px4fmu_default configuration +# + +# +# Use the configuration's ROMFS. +# +ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common + +# +# Board support modules +# +MODULES += drivers/device +MODULES += drivers/stm32 +MODULES += drivers/stm32/adc +MODULES += drivers/stm32/tone_alarm +MODULES += drivers/px4fmu +MODULES += drivers/px4io +MODULES += drivers/boards/px4fmuv2 +MODULES += drivers/rgbled +MODULES += drivers/lsm303d +MODULES += drivers/l3gd20 +#MODULES += drivers/mpu6000 +MODULES += drivers/hmc5883 +MODULES += drivers/ms5611 +MODULES += drivers/mb12xx +MODULES += drivers/gps +MODULES += drivers/hil +MODULES += drivers/hott_telemetry +MODULES += drivers/blinkm +MODULES += modules/sensors + +# +# System commands +# +MODULES += systemcmds/ramtron +MODULES += systemcmds/bl_update +MODULES += systemcmds/boardinfo +MODULES += systemcmds/mixer +MODULES += systemcmds/param +MODULES += systemcmds/perf +MODULES += systemcmds/preflight_check +MODULES += systemcmds/pwm +MODULES += systemcmds/reboot +MODULES += systemcmds/top +MODULES += systemcmds/tests + +# +# General system control +# +MODULES += modules/commander +MODULES += modules/mavlink +MODULES += modules/mavlink_onboard + +# +# Estimation modules (EKF / other filters) +# +MODULES += modules/attitude_estimator_ekf +MODULES += modules/position_estimator_mc +MODULES += modules/position_estimator +MODULES += modules/att_pos_estimator_ekf + +# +# Vehicle Control +# +MODULES += modules/fixedwing_backside +MODULES += modules/fixedwing_att_control +MODULES += modules/fixedwing_pos_control +MODULES += modules/multirotor_att_control +MODULES += modules/multirotor_pos_control + +# +# Logging +# +MODULES += modules/sdlog + +# +# Library modules +# +MODULES += modules/systemlib +MODULES += modules/systemlib/mixer +MODULES += modules/mathlib +MODULES += modules/controllib +MODULES += modules/uORB + +# +# Libraries +# +LIBRARIES += modules/mathlib/CMSIS + +# +# Demo apps +# +#MODULES += examples/math_demo +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/hello_sky +#MODULES += examples/px4_simple_app + +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/daemon +#MODULES += examples/px4_daemon_app + +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/debug_values +#MODULES += examples/px4_mavlink_debug + +# +# Transitional support - add commands from the NuttX export archive. +# +# In general, these should move to modules over time. +# +# Each entry here is ... but we use a helper macro +# to make the table a bit more readable. +# +define _B + $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) +endef + +# command priority stack entrypoint +BUILTIN_COMMANDS := \ + $(call _B, sercon, , 2048, sercon_main ) \ + $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk new file mode 100644 index 000000000..9b3013a5b --- /dev/null +++ b/makefiles/config_px4fmu-v2_test.mk @@ -0,0 +1,40 @@ +# +# Makefile for the px4fmu_default configuration +# + +# +# Use the configuration's ROMFS. +# +ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test + +# +# Board support modules +# +MODULES += drivers/device +MODULES += drivers/stm32 +MODULES += drivers/boards/px4fmuv2 +MODULES += systemcmds/perf +MODULES += systemcmds/reboot + +# +# Library modules +# +MODULES += modules/systemlib +MODULES += modules/uORB + +# +# Transitional support - add commands from the NuttX export archive. +# +# In general, these should move to modules over time. +# +# Each entry here is ... but we use a helper macro +# to make the table a bit more readable. +# +define _B + $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) +endef + +# command priority stack entrypoint +BUILTIN_COMMANDS := \ + $(call _B, sercon, , 2048, sercon_main ) \ + $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmuv2_default.mk b/makefiles/config_px4fmuv2_default.mk deleted file mode 100644 index c4499048c..000000000 --- a/makefiles/config_px4fmuv2_default.mk +++ /dev/null @@ -1,122 +0,0 @@ -# -# Makefile for the px4fmu_default configuration -# - -# -# Use the configuration's ROMFS. -# -ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common - -# -# Board support modules -# -MODULES += drivers/device -MODULES += drivers/stm32 -MODULES += drivers/stm32/adc -MODULES += drivers/stm32/tone_alarm -MODULES += drivers/px4fmu -MODULES += drivers/px4io -MODULES += drivers/boards/px4fmuv2 -MODULES += drivers/rgbled -MODULES += drivers/lsm303d -MODULES += drivers/l3gd20 -#MODULES += drivers/mpu6000 -MODULES += drivers/hmc5883 -MODULES += drivers/ms5611 -MODULES += drivers/mb12xx -MODULES += drivers/gps -MODULES += drivers/hil -MODULES += drivers/hott_telemetry -MODULES += drivers/blinkm -MODULES += modules/sensors - -# -# System commands -# -MODULES += systemcmds/ramtron -MODULES += systemcmds/bl_update -MODULES += systemcmds/boardinfo -MODULES += systemcmds/mixer -MODULES += systemcmds/param -MODULES += systemcmds/perf -MODULES += systemcmds/preflight_check -MODULES += systemcmds/pwm -MODULES += systemcmds/reboot -MODULES += systemcmds/top -MODULES += systemcmds/tests - -# -# General system control -# -MODULES += modules/commander -MODULES += modules/mavlink -MODULES += modules/mavlink_onboard - -# -# Estimation modules (EKF / other filters) -# -MODULES += modules/attitude_estimator_ekf -MODULES += modules/position_estimator_mc -MODULES += modules/position_estimator -MODULES += modules/att_pos_estimator_ekf - -# -# Vehicle Control -# -MODULES += modules/fixedwing_backside -MODULES += modules/fixedwing_att_control -MODULES += modules/fixedwing_pos_control -MODULES += modules/multirotor_att_control -MODULES += modules/multirotor_pos_control - -# -# Logging -# -MODULES += modules/sdlog - -# -# Library modules -# -MODULES += modules/systemlib -MODULES += modules/systemlib/mixer -MODULES += modules/mathlib -MODULES += modules/controllib -MODULES += modules/uORB - -# -# Libraries -# -LIBRARIES += modules/mathlib/CMSIS - -# -# Demo apps -# -#MODULES += examples/math_demo -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/hello_sky -#MODULES += examples/px4_simple_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/daemon -#MODULES += examples/px4_daemon_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/debug_values -#MODULES += examples/px4_mavlink_debug - -# -# Transitional support - add commands from the NuttX export archive. -# -# In general, these should move to modules over time. -# -# Each entry here is ... but we use a helper macro -# to make the table a bit more readable. -# -define _B - $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) -endef - -# command priority stack entrypoint -BUILTIN_COMMANDS := \ - $(call _B, sercon, , 2048, sercon_main ) \ - $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmuv2_test.mk b/makefiles/config_px4fmuv2_test.mk deleted file mode 100644 index 0bd6c18e5..000000000 --- a/makefiles/config_px4fmuv2_test.mk +++ /dev/null @@ -1,45 +0,0 @@ -# -# Makefile for the px4fmu_default configuration -# - -# -# Use the configuration's ROMFS. -# -ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test - -# -# Board support modules -# -MODULES += drivers/device -MODULES += drivers/stm32 -MODULES += drivers/px4io -MODULES += drivers/boards/px4fmuv2 -MODULES += systemcmds/perf -MODULES += systemcmds/reboot - -# needed because things use it for logging -MODULES += modules/mavlink - -# -# Library modules -# -MODULES += modules/systemlib -MODULES += modules/systemlib/mixer -MODULES += modules/uORB - -# -# Transitional support - add commands from the NuttX export archive. -# -# In general, these should move to modules over time. -# -# Each entry here is ... but we use a helper macro -# to make the table a bit more readable. -# -define _B - $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) -endef - -# command priority stack entrypoint -BUILTIN_COMMANDS := \ - $(call _B, sercon, , 2048, sercon_main ) \ - $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4io-v2_default.mk b/makefiles/config_px4io-v2_default.mk new file mode 100644 index 000000000..f9f35d629 --- /dev/null +++ b/makefiles/config_px4io-v2_default.mk @@ -0,0 +1,10 @@ +# +# Makefile for the px4iov2_default configuration +# + +# +# Board support modules +# +MODULES += drivers/stm32 +MODULES += drivers/boards/px4iov2 +MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/config_px4iov2_default.mk b/makefiles/config_px4iov2_default.mk deleted file mode 100644 index f9f35d629..000000000 --- a/makefiles/config_px4iov2_default.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Makefile for the px4iov2_default configuration -# - -# -# Board support modules -# -MODULES += drivers/stm32 -MODULES += drivers/boards/px4iov2 -MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 92461fafb..a0e880a0d 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -45,7 +45,6 @@ export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/ export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/ export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/ export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/ -export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/ export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/ export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/ export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/ diff --git a/makefiles/upload.mk b/makefiles/upload.mk index 4b01b447d..c55e3f188 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -27,7 +27,7 @@ all: upload-$(METHOD)-$(BOARD) upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) -upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) +upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) # diff --git a/nuttx-configs/px4fmu-v2/Kconfig b/nuttx-configs/px4fmu-v2/Kconfig new file mode 100644 index 000000000..069b25f9e --- /dev/null +++ b/nuttx-configs/px4fmu-v2/Kconfig @@ -0,0 +1,7 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +if ARCH_BOARD_PX4FMU_V2 +endif diff --git a/nuttx-configs/px4fmu-v2/common/Make.defs b/nuttx-configs/px4fmu-v2/common/Make.defs new file mode 100644 index 000000000..be387dce1 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/common/Make.defs @@ -0,0 +1,184 @@ +############################################################################ +# configs/px4fmu/common/Make.defs +# +# Copyright (C) 2011 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. +# +############################################################################ + +# +# Generic Make.defs for the PX4FMUV2 +# Do not specify/use this file directly - it is included by config-specific +# Make.defs in the per-config directories. +# + +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m4 \ + -mthumb \ + -march=armv7e-m \ + -mfpu=fpv4-sp-d16 \ + -mfloat-abi=hard + + +# enable precise stack overflow tracking +INSTRUMENTATIONDEFINES = -finstrument-functions \ + -ffixed-r10 + +# pull in *just* libm from the toolchain ... this is grody +LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" +EXTRA_LIBS += $(LIBM) + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) \ + -Wno-psabi +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4fmu-v2/common/ld.script b/nuttx-configs/px4fmu-v2/common/ld.script new file mode 100644 index 000000000..1be39fb87 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/common/ld.script @@ -0,0 +1,150 @@ +/**************************************************************************** + * configs/px4fmu/common/ld.script + * + * Copyright (C) 2011 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. + * + ****************************************************************************/ + +/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + /* + * This is a hack to make the newlib libm __errno() call + * use the NuttX get_errno_ptr() function. + */ + __errno = get_errno_ptr; + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h new file mode 100755 index 000000000..a6cdfb4d2 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/include/board.h @@ -0,0 +1,364 @@ +/************************************************************************************ + * configs/px4fmu/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 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. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE. + * + * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 24 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PPQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +//#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (25,000,000 / 25) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#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_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ + +#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY) +#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY) + +/* SDIO dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz + * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz + * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA Channl/Stream Selections *****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * is we set aside more DMA channels/streams. + * + * SDIO DMA + *   DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA + *   DMAMAP_SDIO_2 = Channel 4, Stream 6 + */ + +#define DMAMAP_SDIO DMAMAP_SDIO_1 + +/* High-resolution timer + */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ + +/* Alternate function pin selections ************************************************/ + +/* + * UARTs. + */ +#define GPIO_USART1_RX GPIO_USART1_RX_1 /* console in from IO */ +#define GPIO_USART1_TX 0 /* USART1 is RX-only */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 +#define GPIO_USART2_TX GPIO_USART2_TX_2 +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_USART3_RX GPIO_USART3_RX_3 +#define GPIO_USART3_TX GPIO_USART3_TX_3 +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_UART4_RX GPIO_UART4_RX_1 +#define GPIO_UART4_TX GPIO_UART4_TX_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +#define GPIO_UART7_RX GPIO_UART7_RX_1 +#define GPIO_UART7_TX GPIO_UART7_TX_1 + +/* UART8 has no alternate pin config */ + +/* UART RX DMA configurations */ +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 + +/* + * PWM + * + * Six PWM outputs are configured. + * + * Pins: + * + * CH1 : PE14 : TIM1_CH4 + * CH2 : PE13 : TIM1_CH3 + * CH3 : PE11 : TIM1_CH2 + * CH4 : PE9 : TIM1_CH1 + * CH5 : PD13 : TIM4_CH2 + * CH6 : PD14 : TIM4_CH3 + * + */ +#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 +#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2 +#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2 +#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2 +#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 +#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2 + +/* + * CAN + * + * CAN1 is routed to the onboard transceiver. + * CAN2 is routed to the expansion connector. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 +#define GPIO_CAN2_TX GPIO_CAN2_TX_2 + +/* + * I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) + +/* + * I2C busses + */ +#define PX4_I2C_BUS_EXPANSION 1 +#define PX4_I2C_BUS_LED 2 + +/* + * Devices on the onboard bus. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_LED 0x55 +#define PX4_I2C_OBDEV_HMC5883 0x1e + +/* + * SPI + * + * There are sensors on SPI1, and SPI2 is connected to the FRAM. + */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 + +/* + * Use these in place of the spi_dev_e enumeration to + * select a specific SPI device on SPI1 + */ +#define PX4_SPIDEV_GYRO 1 +#define PX4_SPIDEV_ACCEL_MAG 2 +#define PX4_SPIDEV_BARO 3 + +/* + * Tone alarm output + */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * 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. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h new file mode 100644 index 000000000..15e4e7a8d --- /dev/null +++ b/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +/** + * nsh_romfsetc.h + * + * This file is a stub for 'make export' purposes; the actual ROMFS + * must be supplied by the library client. + */ + +extern unsigned char romfs_img[]; +extern unsigned int romfs_img_len; diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs new file mode 100644 index 000000000..00257d546 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs @@ -0,0 +1,3 @@ +include ${TOPDIR}/.config + +include $(TOPDIR)/configs/px4fmu-v2/common/Make.defs diff --git a/nuttx-configs/px4fmu-v2/nsh/appconfig b/nuttx-configs/px4fmu-v2/nsh/appconfig new file mode 100644 index 000000000..0e18aa8ef --- /dev/null +++ b/nuttx-configs/px4fmu-v2/nsh/appconfig @@ -0,0 +1,52 @@ +############################################################################ +# configs/px4fmu/nsh/appconfig +# +# Copyright (C) 2011 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nsh + +# The NSH application library +CONFIGURED_APPS += nshlib +CONFIGURED_APPS += system/readline + +ifeq ($(CONFIG_CAN),y) +#CONFIGURED_APPS += examples/can +endif + +#ifeq ($(CONFIG_USBDEV),y) +#ifeq ($(CONFIG_CDCACM),y) +CONFIGURED_APPS += examples/cdcacm +#endif +#endif diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig new file mode 100644 index 000000000..efbb883a5 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig @@ -0,0 +1,1022 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +CONFIG_HOST_OSX=y +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +CONFIG_ARCH_MATH_H=y +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +CONFIG_DEBUG_SYMBOLS=y + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARCH_HAVE_FPU=y +CONFIG_ARCH_FPU=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_ARMV7M_STACKCHECK=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SDIO_DMA=y +# CONFIG_SDIO_DMAPRIO is not set +# CONFIG_SDIO_WIDTH_D1_ONLY is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_ARCH_CHIP_STM32F427V=y +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F30XX is not set +CONFIG_STM32_STM32F40XX=y +CONFIG_STM32_STM32F427=y +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_ADC1=y +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKPSRAM=y +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +CONFIG_STM32_CCMDATARAM=y +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +# CONFIG_STM32_I2C3 is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +CONFIG_STM32_SDIO=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI2=y +# CONFIG_STM32_SPI3 is not set +# CONFIG_STM32_SPI4 is not set +# CONFIG_STM32_SPI5 is not set +# CONFIG_STM32_SPI6 is not set +CONFIG_STM32_SYSCFG=y +CONFIG_STM32_TIM1=y +# CONFIG_STM32_TIM2 is not set +CONFIG_STM32_TIM3=y +CONFIG_STM32_TIM4=y +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +CONFIG_STM32_TIM9=y +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_UART4=y +# CONFIG_STM32_UART5 is not set +CONFIG_STM32_USART6=y +CONFIG_STM32_UART7=y +CONFIG_STM32_UART8=y +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_WWDG=y +CONFIG_STM32_ADC=y +CONFIG_STM32_SPI=y +CONFIG_STM32_I2C=y + +# +# Alternate Pin Mapping +# +CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_DMACAPABLE=y +# CONFIG_STM32_TIM1_PWM is not set +# CONFIG_STM32_TIM3_PWM is not set +# CONFIG_STM32_TIM4_PWM is not set +# CONFIG_STM32_TIM9_PWM is not set +# CONFIG_STM32_TIM10_PWM is not set +# CONFIG_STM32_TIM11_PWM is not set +# CONFIG_STM32_TIM1_ADC is not set +# CONFIG_STM32_TIM3_ADC is not set +# CONFIG_STM32_TIM4_ADC is not set +CONFIG_STM32_USART=y + +# +# U[S]ART Configuration +# +# CONFIG_USART1_RS485 is not set +CONFIG_USART1_RXDMA=y +# CONFIG_USART2_RS485 is not set +CONFIG_USART2_RXDMA=y +# CONFIG_USART3_RS485 is not set +CONFIG_USART3_RXDMA=y +# CONFIG_UART4_RS485 is not set +CONFIG_UART4_RXDMA=y +# CONFIG_UART5_RXDMA is not set +# CONFIG_USART6_RS485 is not set +# CONFIG_USART6_RXDMA is not set +# CONFIG_USART7_RXDMA is not set +CONFIG_USART8_RXDMA=y +CONFIG_STM32_USART_SINGLEWIRE=y + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=500 +# CONFIG_STM32_I2C_DUTY16_9 is not set + +# +# SDIO Configuration +# +CONFIG_SDIO_PRI=128 + +# +# USB Host Configuration +# + +# +# USB Device Configuration +# + +# +# External Memory Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=262144 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4FMU_V2=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="px4fmu-v2" + +# +# Common Board Options +# +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +# CONFIG_BOARD_INITIALIZE is not set +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_TASK_NAME_SIZE=24 +# CONFIG_SCHED_HAVE_PARENT is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +# CONFIG_DEV_CONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_SEM_PREALLOCHOLDERS=8 +CONFIG_SEM_NNESTPRIO=8 +# CONFIG_FDCLONE_DISABLE is not set +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_STARTHOOK is not set +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_ATEXIT_MAX=1 +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +# CONFIG_DISABLE_OS_API is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=4 + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=32 +CONFIG_MAX_TASK_ARGS=10 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=25 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PREALLOC_TIMERS=50 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=6000 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +# CONFIG_DISABLE_POLL is not set +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +CONFIG_I2C_TRANSFER=y +# CONFIG_I2C_WRITEREAD is not set +# CONFIG_I2C_POLLED is not set +# CONFIG_I2C_TRACE is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C_RESET=y +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +CONFIG_WATCHDOG=y +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +CONFIG_MTD=y + +# +# MTD Configuration +# +# CONFIG_MTD_PARTITION is not set +# CONFIG_MTD_BYTE_WRITE is not set + +# +# MTD Device Drivers +# +# CONFIG_RAMMTD is not set +# CONFIG_MTD_AT24XX is not set +# CONFIG_MTD_AT45DB is not set +# CONFIG_MTD_M25P is not set +# CONFIG_MTD_SMART is not set +CONFIG_MTD_RAMTRON=y +# CONFIG_MTD_SST25 is not set +# CONFIG_MTD_SST39FV is not set +# CONFIG_MTD_W25 is not set +CONFIG_PIPES=y +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +CONFIG_SERIAL_REMOVABLE=y +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART4=y +CONFIG_ARCH_HAVE_UART7=y +CONFIG_ARCH_HAVE_UART8=y +CONFIG_ARCH_HAVE_USART1=y +CONFIG_ARCH_HAVE_USART2=y +CONFIG_ARCH_HAVE_USART3=y +CONFIG_ARCH_HAVE_USART6=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_SERIAL_NPOLLWAITERS=2 +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_USART2_SERIAL_CONSOLE is not set +# CONFIG_USART3_SERIAL_CONSOLE is not set +# CONFIG_UART4_SERIAL_CONSOLE is not set +# CONFIG_USART6_SERIAL_CONSOLE is not set +# CONFIG_UART7_SERIAL_CONSOLE is not set +# CONFIG_UART8_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=16 +CONFIG_USART1_TXBUFSIZE=16 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=512 +CONFIG_USART2_TXBUFSIZE=512 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=512 +CONFIG_USART3_TXBUFSIZE=512 +CONFIG_USART3_BAUD=115200 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y + +# +# UART4 Configuration +# +CONFIG_UART4_RXBUFSIZE=128 +CONFIG_UART4_TXBUFSIZE=128 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_BITS=8 +CONFIG_UART4_PARITY=0 +CONFIG_UART4_2STOP=0 +# CONFIG_UART4_IFLOWCONTROL is not set +# CONFIG_UART4_OFLOWCONTROL is not set + +# +# USART6 Configuration +# +CONFIG_USART6_RXBUFSIZE=16 +CONFIG_USART6_TXBUFSIZE=16 +CONFIG_USART6_BAUD=115200 +CONFIG_USART6_BITS=8 +CONFIG_USART6_PARITY=0 +CONFIG_USART6_2STOP=0 +# CONFIG_USART6_IFLOWCONTROL is not set +# CONFIG_USART6_OFLOWCONTROL is not set + +# +# UART7 Configuration +# +CONFIG_UART7_RXBUFSIZE=128 +CONFIG_UART7_TXBUFSIZE=128 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_BITS=8 +CONFIG_UART7_PARITY=0 +CONFIG_UART7_2STOP=0 +# CONFIG_UART7_IFLOWCONTROL is not set +# CONFIG_UART7_OFLOWCONTROL is not set + +# +# UART8 Configuration +# +CONFIG_UART8_RXBUFSIZE=128 +CONFIG_UART8_TXBUFSIZE=128 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_BITS=8 +CONFIG_UART8_PARITY=0 +CONFIG_UART8_2STOP=0 +# CONFIG_UART8_IFLOWCONTROL is not set +# CONFIG_UART8_OFLOWCONTROL is not set +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +# CONFIG_USBDEV_SELFPOWERED is not set +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_DMA is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_RXBUFSIZE=256 +CONFIG_CDCACM_TXBUFSIZE=256 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_PRODUCTID=0x0010 +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v2.x" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +CONFIG_FS_FATTIME=y +# CONFIG_FAT_DMAMEMORY is not set +CONFIG_FS_NXFFS=y +CONFIG_NXFFS_PREALLOCATED=y +CONFIG_NXFFS_ERASEDSTATE=0xff +CONFIG_NXFFS_PACKTHRESHOLD=32 +CONFIG_NXFFS_MAXNAMLEN=32 +CONFIG_NXFFS_TAILTHRESHOLD=2048 +CONFIG_FS_ROMFS=y +# CONFIG_FS_SMARTFS is not set +CONFIG_FS_BINFS=y + +# +# System Logging +# +# CONFIG_SYSLOG_ENABLE is not set +CONFIG_SYSLOG=y +CONFIG_SYSLOG_CHAR=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_MULTIHEAP is not set +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +CONFIG_GRAN=y +CONFIG_GRAN_SINGLE=y +CONFIG_GRAN_INTR=y + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_NOPRINTF_FIELDWIDTH is not set +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIB_RAND_ORDER=1 +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 +CONFIG_LIBC_STRERROR=y +# CONFIG_LIBC_STRERROR_SHORT is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y +CONFIG_ARCH_MEMCPY=y +# CONFIG_ARCH_MEMCMP is not set +# CONFIG_ARCH_MEMMOVE is not set +# CONFIG_ARCH_MEMSET is not set +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_ARCH_STRCHR is not set +# CONFIG_ARCH_STRCMP is not set +# CONFIG_ARCH_STRCPY is not set +# CONFIG_ARCH_STRNCPY is not set +# CONFIG_ARCH_STRLEN is not set +# CONFIG_ARCH_STRNLEN is not set +# CONFIG_ARCH_BZERO is not set + +# +# Non-standard Library Support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=5000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKPERIOD=50000 +CONFIG_SCHED_LPWORKSTACKSIZE=2048 +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set + +# +# Basic CXX Support +# +CONFIG_C99_BOOL8=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +CONFIG_EXAMPLES_CDCACM=y +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_MOUNT=y +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=12 +CONFIG_NSH_NESTDEPTH=8 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_ROMFSETC=y +# CONFIG_NSH_ROMFSRC is not set +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT="/tmp" +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set + +# +# USB Trace Support +# +# CONFIG_NSH_CONDEV is not set +CONFIG_NSH_ARCHINIT=y + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# +# CONFIG_SYSTEM_I2CTOOL is not set + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# FLASH Erase-all Command +# + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +CONFIG_SYSTEM_SYSINFO=y + +# +# USB Monitor +# diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig.prev b/nuttx-configs/px4fmu-v2/nsh/defconfig.prev new file mode 100755 index 000000000..42910ce0a --- /dev/null +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig.prev @@ -0,0 +1,1067 @@ +############################################################################ +# configs/px4fmu/nsh/defconfig +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (C) 2011-2012 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. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# 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 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, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# CONFIG_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# 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 +# stack. If defined, this symbol is the size of the interrupt +# stack in bytes. If not defined, the user task stacks will be +# used during interrupt handling. +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. +# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. +# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that +# cause a 100 second delay during boot-up. This 100 second delay +# serves no purpose other than it allows you to calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH="arm" +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32F427V=y +CONFIG_ARCH_BOARD="px4fmu-v2" +CONFIG_ARCH_BOARD_PX4FMU_V2=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_DRAM_SIZE=0x00040000 +CONFIG_DRAM_START=0x20000000 +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_FPU=y +CONFIG_ARCH_INTERRUPTSTACK=n +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=n +CONFIG_ARCH_BUTTONS=n +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=y +CONFIG_ARCH_MATH_H=y + +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_STM32_STM32F427=y + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are enabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG (ignored) +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=n +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=y + +# +# 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. +# +CONFIG_STM32_CCMEXCLUDE=y + +# +# On-board FSMC SRAM configuration +# +# CONFIG_STM32_FSMC - Required. See below +# CONFIG_MM_REGIONS - Required. Must be 2 or 3 (see above) +# +# CONFIG_STM32_FSMC_SRAM=y - Indicates that SRAM is available via the +# FSMC (as opposed to an LCD or FLASH). +# CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space +# CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space +# +#CONFIG_STM32_FSMC_SRAM=n +#CONFIG_HEAP2_BASE=0x64000000 +#CONFIG_HEAP2_END=(0x64000000+(2*1024*1024)) + +# +# Individual subsystems can be enabled: +# +# This set is exhaustive for PX4FMU and should be safe to cut and +# paste into any other config. +# +# AHB1: +CONFIG_STM32_CRC=n +CONFIG_STM32_BKPSRAM=y +CONFIG_STM32_CCMDATARAM=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_ETHMAC=n +CONFIG_STM32_OTGHS=n +# AHB2: +CONFIG_STM32_DCMI=n +CONFIG_STM32_CRYP=n +CONFIG_STM32_HASH=n +CONFIG_STM32_RNG=n +CONFIG_STM32_OTGFS=y +# AHB3: +CONFIG_STM32_FSMC=n +# APB1: +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=y +CONFIG_STM32_TIM4=y +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_TIM12=n +CONFIG_STM32_TIM13=n +CONFIG_STM32_TIM14=n +CONFIG_STM32_WWDG=y +CONFIG_STM32_IWDG=n +CONFIG_STM32_SPI2=y +CONFIG_STM32_SPI3=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_UART4=y +CONFIG_STM32_UART5=n +CONFIG_STM32_UART7=y +CONFIG_STM32_UART8=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_I2C3=n +CONFIG_STM32_CAN1=n +CONFIG_STM32_CAN2=n +CONFIG_STM32_DAC=n +CONFIG_STM32_PWR=y +# APB2: +CONFIG_STM32_TIM1=y +CONFIG_STM32_TIM8=n +CONFIG_STM32_USART1=y +# Mostly owned by the px4io driver, but uploader needs this +CONFIG_STM32_USART6=y +# We use our own driver, but leave this on. +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +CONFIG_STM32_ADC3=n +CONFIG_STM32_SDIO=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SYSCFG=y +CONFIG_STM32_TIM9=y +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y + +# +# Enable single wire support. If this is not defined, then this mode cannot +# be enabled. +# +CONFIG_STM32_USART_SINGLEWIRE=y + +# +# We want the flash prefetch on for max performance. +# +STM32_FLASH_PREFETCH=y + +# +# STM32F40xxx specific serial device driver settings +# +# CONFIG_SERIAL_TERMIOS - Serial driver supports termios.h interfaces (tcsetattr, +# tcflush, etc.). If this is not defined, then the terminal settings (baud, +# parity, etc.) are not configurable at runtime; serial streams cannot be +# flushed, etc. +# CONFIG_SERIAL_CONSOLE_REINIT - re-initializes the console serial port +# immediately after creating the /dev/console device. This is required +# if the console serial port has RX DMA enabled. +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_SERIAL_TERMIOS=y +CONFIG_SERIAL_CONSOLE_REINIT=n +CONFIG_STANDARD_SERIAL=y + +CONFIG_UART8_SERIAL_CONSOLE=y + +#Mavlink messages can be bigger than 128 +CONFIG_USART1_TXBUFSIZE=512 +CONFIG_USART2_TXBUFSIZE=256 +CONFIG_USART3_TXBUFSIZE=256 +CONFIG_UART4_TXBUFSIZE=256 +CONFIG_USART6_TXBUFSIZE=128 +CONFIG_UART7_TXBUFSIZE=256 +CONFIG_UART8_TXBUFSIZE=256 + +CONFIG_USART1_RXBUFSIZE=512 +CONFIG_USART2_RXBUFSIZE=256 +CONFIG_USART3_RXBUFSIZE=256 +CONFIG_UART4_RXBUFSIZE=256 +CONFIG_USART6_RXBUFSIZE=256 +CONFIG_UART7_RXBUFSIZE=256 +CONFIG_UART8_RXBUFSIZE=256 + +CONFIG_USART1_BAUD=115200 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 +CONFIG_UART4_BAUD=115200 +CONFIG_USART6_BAUD=115200 +CONFIG_UART7_BAUD=115200 +CONFIG_UART8_BAUD=57600 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 +CONFIG_UART4_BITS=8 +CONFIG_USART6_BITS=8 +CONFIG_UART7_BITS=8 +CONFIG_UART8_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 +CONFIG_UART4_PARITY=0 +CONFIG_USART6_PARITY=0 +CONFIG_UART7_PARITY=0 +CONFIG_UART8_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 +CONFIG_UART4_2STOP=0 +CONFIG_USART6_2STOP=0 +CONFIG_UART7_2STOP=0 +CONFIG_UART8_2STOP=0 + +CONFIG_USART1_RXDMA=y +CONFIG_USART2_RXDMA=y +CONFIG_USART3_RXDMA=n +CONFIG_UART4_RXDMA=n +CONFIG_USART6_RXDMA=y +CONFIG_UART7_RXDMA=n +CONFIG_UART8_RXDMA=n + +# +# STM32F40xxx specific SPI device driver settings +# +CONFIG_SPI_EXCHANGE=y +# DMA needs more work, not implemented on STM32F4x yet +#CONFIG_STM32_SPI_DMA=y + +# +# STM32F40xxx specific CAN device driver settings +# +# 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. +# Default: 4 +# CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback +# 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 +CONFIG_CAN1_BAUD=700000 +CONFIG_CAN2_BAUD=700000 + + +# XXX remove after integration testing +# 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 + +# +# I2C configuration +# +CONFIG_I2C=y +CONFIG_I2C_POLLED=n +CONFIG_I2C_TRANSFER=y +CONFIG_I2C_TRACE=n +CONFIG_I2C_RESET=y +# XXX fixed per-transaction timeout +CONFIG_STM32_I2CTIMEOMS=10 + +# +# MTD support +# +CONFIG_MTD=y + +# XXX re-enable after integration testing + +# +# I2C configuration +# +#CONFIG_I2C=y +#CONFIG_I2C_POLLED=y +#CONFIG_I2C_TRANSFER=y +#CONFIG_I2C_TRACE=n +#CONFIG_I2C_RESET=y + +# Dynamic timeout +#CONFIG_STM32_I2C_DYNTIMEO=y +#CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP=500 +#CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE=200 + +# Fixed per-transaction timeout +#CONFIG_STM32_I2CTIMEOSEC=0 +#CONFIG_STM32_I2CTIMEOMS=10 + + + + + + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=y + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# 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 +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# 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_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, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker +# thread. Default: 192 +# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for +# work in units of microseconds. Default: 50*1000 (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 +# the worker thread. Default: 4 +# +# CONFIG_SCHED_LPWORK. If CONFIG_SCHED_WORKQUEUE is defined, then a single +# work queue is created by default. If CONFIG_SCHED_LPWORK is also defined +# then an additional, lower-priority work queue will also be created. This +# lower priority work queue is better suited for more extended processing +# (such as file system clean-up operations) +# CONFIG_SCHED_LPWORKPRIORITY - The execution priority of the lower priority +# worker thread. Default: 50 +# CONFIG_SCHED_LPWORKPERIOD - How often the lower priority worker thread +# checks for work in units of microseconds. Default: 50*1000 (50 MS). +# CONFIG_SCHED_LPWORKSTACKSIZE - The stack size allocated for the lower +# priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE. +# CONFIG_SCHED_WAITPID - Enable the waitpid() API +# CONFIG_SCHED_ATEXIT - Enabled the atexit() API +# +CONFIG_USER_ENTRYPOINT="nsh_main" +#CONFIG_APPS_DIR= +CONFIG_DEBUG=y +CONFIG_DEBUG_VERBOSE=y +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=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_MM_REGIONS=2 +CONFIG_ARCH_LOWPUTC=y +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=y +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=8 +CONFIG_FDCLONE_DISABLE=n +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=5000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKPERIOD=50000 +CONFIG_SCHED_LPWORKSTACKSIZE=2048 +CONFIG_SIG_SIGWORK=4 +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 +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n +CONFIG_DISABLE_POLL=n + +# +# Misc libc settings +# +# 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 +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=y +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# 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 +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=32 +CONFIG_MAX_TASK_ARGS=8 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=25 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PREALLOC_TIMERS=50 + +# +# Filesystem configuration +# +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +# CONFIG_FAT_LCNAMES - Enable use of the NT-style upper/lower case 8.3 +# file name support. +# CONFIG_FAT_LFN - Enable FAT long file names. NOTE: Microsoft claims +# patents on FAT long file name technology. Please read the +# disclaimer in the top-level COPYING file and only enable this +# feature if you understand these issues. +# CONFIG_FAT_MAXFNAME - If CONFIG_FAT_LFN is defined, then the +# default, maximum long file name is 255 bytes. This can eat up +# a lot of memory (especially stack space). If you are willing +# to live with some non-standard, short long file names, then +# define this value. A good choice would be the same value as +# selected for CONFIG_NAME_MAX which will limit the visibility +# of longer file names anyway. +# CONFIG_FS_NXFFS: Enable NuttX FLASH file system (NXFF) support. +# CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. +# This must have one of the values of 0xff or 0x00. +# Default: 0xff. +# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, +# don't both with file chunks smaller than this number of data bytes. +# CONFIG_NXFFS_MAXNAMLEN: The maximum size of an NXFFS file name. +# Default: 255. +# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, +# don't both with file chunks smaller than this number of data bytes. +# Default: 32. +# CONFIG_NXFFS_TAILTHRESHOLD: clean-up can either mean +# packing files together toward the end of the file or, if file are +# deleted at the end of the file, clean up can simply mean erasing +# the end of FLASH memory so that it can be re-used again. However, +# doing this can also harm the life of the FLASH part because it can +# mean that the tail end of the FLASH is re-used too often. This +# threshold determines if/when it is worth erased the tail end of FLASH +# and making it available for re-use (and possible over-wear). +# Default: 8192. +# CONFIG_FS_ROMFS - Enable ROMFS filesystem support +# CONFIG_FS_RAMMAP - For file systems that do not support XIP, this +# option will enable a limited form of memory mapping that is +# implemented by copying whole files into memory. +# +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +CONFIG_FS_NXFFS=y +CONFIG_NXFFS_MAXNAMLEN=32 +CONFIG_NXFFS_TAILTHRESHOLD=2048 +CONFIG_NXFFS_PREALLOCATED=y +CONFIG_FS_ROMFS=y +CONFIG_FS_BINFS=y + +# +# SPI-based MMC/SD driver +# +# CONFIG_MMCSD_NSLOTS +# Number of MMC/SD slots supported by the driver +# CONFIG_MMCSD_READONLY +# Provide read-only access (default is read/write) +# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card. +# Default is 20MHz, current setting 24 MHz +# +#CONFIG_MMCSD=n +# XXX need to rejig this for SDIO +#CONFIG_MMCSD_SPI=y +#CONFIG_MMCSD_NSLOTS=1 +#CONFIG_MMCSD_READONLY=n +#CONFIG_MMCSD_SPICLOCK=24000000 + +# +# Maintain legacy build behavior (revisit) +# + +CONFIG_MMCSD=y +#CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SDIO=y +CONFIG_MTD=y + +# +# SPI-based MMC/SD driver +# +#CONFIG_MMCSD_NSLOTS=1 +#CONFIG_MMCSD_READONLY=n +#CONFIG_MMCSD_SPICLOCK=12500000 + +# +# STM32 SDIO-based MMC/SD driver +# +CONFIG_SDIO_DMA=y +#CONFIG_SDIO_PRI=128 +#CONFIG_SDIO_DMAPRIO +#CONFIG_SDIO_WIDTH_D1_ONLY +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +CONFIG_MMCSD_MMCSUPPORT=n +CONFIG_MMCSD_HAVECARDDETECT=n + +# +# Block driver buffering +# +# CONFIG_FS_READAHEAD +# Enable read-ahead buffering +# CONFIG_FS_WRITEBUFFER +# Enable write buffering +# +CONFIG_FS_READAHEAD=n +CONFIG_FS_WRITEBUFFER=n + +# +# RTC Configuration +# +# CONFIG_RTC - Enables general support for a hardware RTC. Specific +# architectures may require other specific settings. +# CONFIG_RTC_DATETIME - There are two general types of RTC: (1) A simple +# battery backed counter that keeps the time when power is down, and (2) +# A full date / time RTC the provides the date and time information, often +# in BCD format. If CONFIG_RTC_DATETIME is selected, it specifies this +# second kind of RTC. In this case, the RTC is used to "seed" the normal +# NuttX timer and the NuttX system timer provides for higher resoution +# time. +# CONFIG_RTC_HIRES - If CONFIG_RTC_DATETIME not selected, then the simple, +# battery backed counter is used. There are two different implementations +# of such simple counters based on the time resolution of the counter: +# The typical RTC keeps time to resolution of 1 second, usually +# supporting a 32-bit time_t value. In this case, the RTC is used to +# "seed" the normal NuttX timer and the NuttX timer provides for higher +# resoution time. If CONFIG_RTC_HIRES is enabled in the NuttX configuration, +# then the RTC provides higher resolution time and completely replaces the +# system timer for purpose of date and time. +# CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the frequency +# of the high resolution RTC must be provided. If CONFIG_RTC_HIRES is +# not defined, CONFIG_RTC_FREQUENCY is assumed to be one. +# CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an +# alarm. A callback function will be executed when the alarm goes off +# +CONFIG_RTC=n +CONFIG_RTC_DATETIME=y +CONFIG_RTC_HIRES=n +CONFIG_RTC_FREQUENCY=n +CONFIG_RTC_ALARM=n + +# +# USB Device Configuration +# +# CONFIG_USBDEV +# Enables USB device support +# CONFIG_USBDEV_ISOCHRONOUS +# Build in extra support for isochronous endpoints +# CONFIG_USBDEV_DUALSPEED +# Hardware handles high and full speed operation (USB 2.0) +# CONFIG_USBDEV_SELFPOWERED +# Will cause USB features to indicate that the device is +# self-powered +# CONFIG_USBDEV_MAXPOWER +# Maximum power consumption in mA +# CONFIG_USBDEV_TRACE +# Enables USB tracing for debug +# CONFIG_USBDEV_TRACE_NRECORDS +# Number of trace entries to remember +# +CONFIG_USBDEV=y +CONFIG_USBDEV_ISOCHRONOUS=n +CONFIG_USBDEV_DUALSPEED=n +CONFIG_USBDEV_SELFPOWERED=y +CONFIG_USBDEV_REMOTEWAKEUP=n +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USBDEV_TRACE=n +CONFIG_USBDEV_TRACE_NRECORDS=512 + +# +# USB serial device class driver (Standard CDC ACM class) +# +# CONFIG_CDCACM +# Enable compilation of the USB serial driver +# CONFIG_CDCACM_CONSOLE +# Configures the CDC/ACM serial port as the console device. +# CONFIG_CDCACM_EP0MAXPACKET +# Endpoint 0 max packet size. Default 64 +# CONFIG_CDCACM_EPINTIN +# The logical 7-bit address of a hardware endpoint that supports +# interrupt IN operation. Default 2. +# CONFIG_CDCACM_EPINTIN_FSSIZE +# Max package size for the interrupt IN endpoint if full speed mode. +# Default 64. +# CONFIG_CDCACM_EPINTIN_HSSIZE +# Max package size for the interrupt IN endpoint if high speed mode. +# Default 64 +# CONFIG_CDCACM_EPBULKOUT +# The logical 7-bit address of a hardware endpoint that supports +# bulk OUT operation. Default 4. +# CONFIG_CDCACM_EPBULKOUT_FSSIZE +# Max package size for the bulk OUT endpoint if full speed mode. +# Default 64. +# CONFIG_CDCACM_EPBULKOUT_HSSIZE +# Max package size for the bulk OUT endpoint if high speed mode. +# Default 512. +# CONFIG_CDCACM_EPBULKIN +# The logical 7-bit address of a hardware endpoint that supports +# bulk IN operation. Default 3. +# CONFIG_CDCACM_EPBULKIN_FSSIZE +# Max package size for the bulk IN endpoint if full speed mode. +# Default 64. +# CONFIG_CDCACM_EPBULKIN_HSSIZE +# Max package size for the bulk IN endpoint if high speed mode. +# Default 512. +# CONFIG_CDCACM_NWRREQS and CONFIG_CDCACM_NRDREQS +# The number of write/read requests that can be in flight. +# Default 256. +# CONFIG_CDCACM_VENDORID and CONFIG_CDCACM_VENDORSTR +# The vendor ID code/string. Default 0x0525 and "NuttX" +# 0x0525 is the Netchip vendor and should not be used in any +# products. This default VID was selected for compatibility with +# the Linux CDC ACM default VID. +# CONFIG_CDCACM_PRODUCTID and CONFIG_CDCACM_PRODUCTSTR +# The product ID code/string. Default 0xa4a7 and "CDC/ACM Serial" +# 0xa4a7 was selected for compatibility with the Linux CDC ACM +# default PID. +# CONFIG_CDCACM_RXBUFSIZE and CONFIG_CDCACM_TXBUFSIZE +# Size of the serial receive/transmit buffers. Default 256. +# +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=n +#CONFIG_CDCACM_EP0MAXPACKET +CONFIG_CDCACM_EPINTIN=1 +#CONFIG_CDCACM_EPINTIN_FSSIZE +#CONFIG_CDCACM_EPINTIN_HSSIZE +CONFIG_CDCACM_EPBULKOUT=3 +#CONFIG_CDCACM_EPBULKOUT_FSSIZE +#CONFIG_CDCACM_EPBULKOUT_HSSIZE +CONFIG_CDCACM_EPBULKIN=2 +#CONFIG_CDCACM_EPBULKIN_FSSIZE +#CONFIG_CDCACM_EPBULKIN_HSSIZE +#CONFIG_CDCACM_NWRREQS +#CONFIG_CDCACM_NRDREQS +CONFIG_CDCACM_VENDORID=0x26AC +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTID=0x0010 +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6" +#CONFIG_CDCACM_RXBUFSIZE +#CONFIG_CDCACM_TXBUFSIZE + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# 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_MAX_ARGUMENTS - Maximum number of arguments for command line +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +# +CONFIG_BUILTIN=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAX_ARGUMENTS=12 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_DISABLESCRIPT=n +CONFIG_NSH_DISABLEBG=n +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_USBCONSOLE=n +#CONFIG_NSH_USBCONDEV="/dev/ttyACM0" +CONFIG_NSH_TELNET=n +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_IOBUFFER_SIZE=512 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=y +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 +CONFIG_NSH_ROMFSSECTSIZE=128 # Default 64, increased to allow for more than 64 folders on the sdcard +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT=/tmp + +# +# Architecture-specific NSH options +# +#CONFIG_NSH_MMCSDSPIPORTNO=3 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDMINOR=0 + + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3240G-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +# Idle thread needs 4096 bytes +# default 1 KB is not enough +# 4096 bytes +CONFIG_IDLETHREAD_STACKSIZE=6000 +# USERMAIN stack size probably needs to be around 4096 bytes +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + +# enable bindir +CONFIG_APPS_BINDIR=y diff --git a/nuttx-configs/px4fmu-v2/nsh/setenv.sh b/nuttx-configs/px4fmu-v2/nsh/setenv.sh new file mode 100755 index 000000000..265520997 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/nsh/setenv.sh @@ -0,0 +1,67 @@ +#!/bin/bash +# configs/stm3240g-eval/nsh/setenv.sh +# +# Copyright (C) 2011 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4fmu-v2/src/Makefile b/nuttx-configs/px4fmu-v2/src/Makefile new file mode 100644 index 000000000..d4276f7fc --- /dev/null +++ b/nuttx-configs/px4fmu-v2/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/px4fmu/src/Makefile +# +# Copyright (C) 2011 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)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep + diff --git a/nuttx-configs/px4fmu-v2/src/empty.c b/nuttx-configs/px4fmu-v2/src/empty.c new file mode 100644 index 000000000..ace900866 --- /dev/null +++ b/nuttx-configs/px4fmu-v2/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ diff --git a/nuttx-configs/px4io-v2/README.txt b/nuttx-configs/px4io-v2/README.txt new file mode 100755 index 000000000..9b1615f42 --- /dev/null +++ b/nuttx-configs/px4io-v2/README.txt @@ -0,0 +1,806 @@ +README +====== + +This README discusses issues unique to NuttX configurations for the +STMicro STM3210E-EVAL development board. + +Contents +======== + + - Development Environment + - GNU Toolchain Options + - IDEs + - NuttX buildroot Toolchain + - DFU and JTAG + - OpenOCD + - LEDs + - Temperature Sensor + - RTC + - STM3210E-EVAL-specific Configuration Options + - Configurations + +Development Environment +======================= + + Either Linux or Cygwin on Windows can be used for the development environment. + The source has been built only using the GNU toolchain (see below). Other + toolchains will likely cause problems. Testing was performed using the Cygwin + environment because the Raisonance R-Link emulatator and some RIDE7 development tools + were used and those tools works only under Windows. + +GNU Toolchain Options +===================== + + The NuttX make system has been modified to support the following different + toolchain options. + + 1. The CodeSourcery GNU toolchain, + 2. The devkitARM GNU toolchain, + 3. Raisonance GNU toolchain, or + 4. The NuttX buildroot Toolchain (see below). + + All testing has been conducted using the NuttX buildroot toolchain. However, + the make system is setup to default to use the devkitARM toolchain. To use + the CodeSourcery, devkitARM or Raisonance GNU toolchain, you simply need to + add one of the following configuration options to your .config (or defconfig) + file: + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_STM32_DEVKITARM=y : devkitARM under Windows + CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows + CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + + If you are not using CONFIG_STM32_BUILDROOT, then you may also have to modify + the PATH in the setenv.h file if your make cannot find the tools. + + NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are + Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot + toolchains are Cygwin and/or Linux native toolchains. There are several limitations + to using a Windows based toolchain in a Cygwin environment. The three biggest are: + + 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are + performed automatically in the Cygwin makefiles using the 'cygpath' utility + but you might easily find some new path problems. If so, check out 'cygpath -w' + + 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links + are used in Nuttx (e.g., include/arch). The make system works around these + problems for the Windows tools by copying directories instead of linking them. + But this can also cause some confusion for you: For example, you may edit + a file in a "linked" directory and find that your changes had no effect. + That is because you are building the copy of the file in the "fake" symbolic + directory. If you use a Windows toolchain, you should get in the habit of + making like this: + + make clean_context all + + An alias in your .bashrc file might make that less painful. + + 3. Dependencies are not made when using Windows versions of the GCC. This is + because the dependencies are generated using Windows pathes which do not + work with the Cygwin make. + + Support has been added for making dependencies with the windows-native toolchains. + That support can be enabled by modifying your Make.defs file as follows: + + - MKDEP = $(TOPDIR)/tools/mknulldeps.sh + + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" + + If you have problems with the dependency build (for example, if you are not + building on C:), then you may need to modify tools/mkdeps.sh + + NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization + level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with + -Os. + + NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that + the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM + path or will get the wrong version of make. + +IDEs +==== + + NuttX is built using command-line make. It can be used with an IDE, but some + effort will be required to create the project (There is a simple RIDE project + in the RIDE subdirectory). + + Makefile Build + -------------- + Under Eclipse, it is pretty easy to set up an "empty makefile project" and + simply use the NuttX makefile to build the system. That is almost for free + under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty + makefile project in order to work with Windows (Google for "Eclipse Cygwin" - + there is a lot of help on the internet). + + Native Build + ------------ + Here are a few tips before you start that effort: + + 1) Select the toolchain that you will be using in your .config file + 2) Start the NuttX build at least one time from the Cygwin command line + before trying to create your project. This is necessary to create + certain auto-generated files and directories that will be needed. + 3) Set up include pathes: You will need include/, arch/arm/src/stm32, + arch/arm/src/common, arch/arm/src/armv7-m, and sched/. + 4) All assembly files need to have the definition option -D __ASSEMBLY__ + on the command line. + + Startup files will probably cause you some headaches. The NuttX startup file + is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX + one time from the Cygwin command line in order to obtain the pre-built + startup object needed by RIDE. + +NuttX buildroot Toolchain +========================= + + A GNU GCC-based toolchain is assumed. The files */setenv.sh should + be modified to point to the correct path to the Cortex-M3 GCC toolchain (if + different from the default in your PATH variable). + + If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX + SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573). + This GNU toolchain builds and executes in the Linux or Cygwin environment. + + 1. You must have already configured Nuttx in /nuttx. + + cd tools + ./configure.sh stm3210e-eval/ + + 2. Download the latest buildroot package into + + 3. unpack the buildroot tarball. The resulting directory may + have versioning information on it like buildroot-x.y.z. If so, + rename /buildroot-x.y.z to /buildroot. + + 4. cd /buildroot + + 5. cp configs/cortexm3-defconfig-4.3.3 .config + + 6. make oldconfig + + 7. make + + 8. Edit setenv.h, if necessary, so that the PATH variable includes + the path to the newly built binaries. + + See the file configs/README.txt in the buildroot source tree. That has more + detailed PLUS some special instructions that you will need to follow if you are + building a Cortex-M3 toolchain for Cygwin under Windows. + +DFU and JTAG +============ + + Enbling Support for the DFU Bootloader + -------------------------------------- + The linker files in these projects can be configured to indicate that you + will be loading code using STMicro built-in USB Device Firmware Upgrade (DFU) + loader or via some JTAG emulator. You can specify the DFU bootloader by + adding the following line: + + CONFIG_STM32_DFU=y + + to your .config file. Most of the configurations in this directory are set + up to use the DFU loader. + + If CONFIG_STM32_DFU is defined, the code will not be positioned at the beginning + of FLASH (0x08000000) but will be offset to 0x08003000. This offset is needed + to make space for the DFU loader and 0x08003000 is where the DFU loader expects + to find new applications at boot time. If you need to change that origin for some + other bootloader, you will need to edit the file(s) ld.script.dfu for each + configuration. + + The DFU SE PC-based software is available from the STMicro website, + http://www.st.com. General usage instructions: + + 1. Convert the NuttX Intel Hex file (nuttx.ihx) into a special DFU + file (nuttx.dfu)... see below for details. + 2. Connect the STM3210E-EVAL board to your computer using a USB + cable. + 3. Start the DFU loader on the STM3210E-EVAL board. You do this by + resetting the board while holding the "Key" button. Windows should + recognize that the DFU loader has been installed. + 3. Run the DFU SE program to load nuttx.dfu into FLASH. + + What if the DFU loader is not in FLASH? The loader code is available + inside of the Demo dirctory of the USBLib ZIP file that can be downloaded + from the STMicro Website. You can build it using RIDE (or other toolchains); + you will need a JTAG emulator to burn it into FLASH the first time. + + In order to use STMicro's built-in DFU loader, you will have to get + the NuttX binary into a special format with a .dfu extension. The + DFU SE PC_based software installation includes a file "DFU File Manager" + conversion program that a file in Intel Hex format to the special DFU + format. When you successfully build NuttX, you will find a file called + nutt.ihx in the top-level directory. That is the file that you should + provide to the DFU File Manager. You will need to rename it to nuttx.hex + in order to find it with the DFU File Manager. You will end up with + a file called nuttx.dfu that you can use with the STMicro DFU SE program. + + Enabling JTAG + ------------- + If you are not using the DFU, then you will probably also need to enable + JTAG support. By default, all JTAG support is disabled but there NuttX + configuration options to enable JTAG in various different ways. + + These configurations effect the setting of the SWJ_CFG[2:0] bits in the AFIO + MAPR register. These bits are used to configure the SWJ and trace alternate function I/Os. The SWJ (SerialWire JTAG) supports JTAG or SWD access to the + Cortex debug port. The default state in this port is for all JTAG support + to be disable. + + CONFIG_STM32_JTAG_FULL_ENABLE - sets SWJ_CFG[2:0] to 000 which enables full + SWJ (JTAG-DP + SW-DP) + + CONFIG_STM32_JTAG_NOJNTRST_ENABLE - sets SWJ_CFG[2:0] to 001 which enable + full SWJ (JTAG-DP + SW-DP) but without JNTRST. + + CONFIG_STM32_JTAG_SW_ENABLE - sets SWJ_CFG[2:0] to 010 which would set JTAG-DP + disabled and SW-DP enabled + + The default setting (none of the above defined) is SWJ_CFG[2:0] set to 100 + which disable JTAG-DP and SW-DP. + +OpenOCD +======= + +I have also used OpenOCD with the STM3210E-EVAL. In this case, I used +the Olimex USB ARM OCD. See the script in configs/stm3210e-eval/tools/oocd.sh +for more information. Using the script: + +1) Start the OpenOCD GDB server + + cd + configs/stm3210e-eval/tools/oocd.sh $PWD + +2) Load Nuttx + + cd + arm-none-eabi-gdb nuttx + gdb> target remote localhost:3333 + gdb> mon reset + gdb> mon halt + gdb> load nuttx + +3) Running NuttX + + gdb> mon reset + gdb> c + +LEDs +==== + +The STM3210E-EVAL board has four LEDs labeled LD1, LD2, LD3 and LD4 on the +board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is +defined. In that case, the usage by the board port is defined in +include/board.h and src/up_leds.c. The LEDs are used to encode OS-related +events as follows: + + SYMBOL Meaning LED1* LED2 LED3 LED4 + ---------------- ----------------------- ----- ----- ----- ----- + LED_STARTED NuttX has been started ON OFF OFF OFF + LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF + LED_IRQSENABLED Interrupts enabled ON ON OFF OFF + LED_STACKCREATED Idle stack created OFF OFF ON OFF + LED_INIRQ In an interrupt** ON N/C N/C OFF + LED_SIGNAL In a signal handler*** N/C ON N/C OFF + LED_ASSERTION An assertion failed ON ON N/C OFF + LED_PANIC The system has crashed N/C N/C N/C ON + LED_IDLE STM32 is is sleep mode (Optional, not used) + + * If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot + and these LEDs will give you some indication of where the failure was + ** The normal state is LED3 ON and LED1 faintly glowing. This faint glow + is because of timer interupts that result in the LED being illuminated + on a small proportion of the time. +*** LED2 may also flicker normally if signals are processed. + +Temperature Sensor +================== + +Support for the on-board LM-75 temperature sensor is available. This supported +has been verified, but has not been included in any of the available the +configurations. To set up the temperature sensor, add the following to the +NuttX configuration file + + CONFIG_I2C=y + CONFIG_I2C_LM75=y + +Then you can implement logic like the following to use the temperature sensor: + + #include + #include + + ret = stm32_lm75initialize("/dev/temp"); /* Register the temperature sensor */ + fd = open("/dev/temp", O_RDONLY); /* Open the temperature sensor device */ + ret = ioctl(fd, SNIOC_FAHRENHEIT, 0); /* Select Fahrenheit */ + bytesread = read(fd, buffer, 8*sizeof(b16_t)); /* Read temperature samples */ + +More complex temperature sensor operations are also available. See the IOCTAL +commands enumerated in include/nuttx/sensors/lm75.h. Also read the descriptions +of the stm32_lm75initialize() and stm32_lm75attach() interfaces in the +arch/board/board.h file (sames as configs/stm3210e-eval/include/board.h). + +RTC +=== + + The STM32 RTC may configured using the following settings. + + CONFIG_RTC - Enables general support for a hardware RTC. Specific + architectures may require other specific settings. + CONFIG_RTC_HIRES - The typical RTC keeps time to resolution of 1 + second, usually supporting a 32-bit time_t value. In this case, + the RTC is used to "seed" the normal NuttX timer and the + NuttX timer provides for higher resoution time. If CONFIG_RTC_HIRES + is enabled in the NuttX configuration, then the RTC provides higher + resolution time and completely replaces the system timer for purpose of + date and time. + CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the + frequency of the high resolution RTC must be provided. If CONFIG_RTC_HIRES + is not defined, CONFIG_RTC_FREQUENCY is assumed to be one. + CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an alarm. + A callback function will be executed when the alarm goes off + + In hi-res mode, the STM32 RTC operates only at 16384Hz. Overflow interrupts + are handled when the 32-bit RTC counter overflows every 3 days and 43 minutes. + A BKP register is incremented on each overflow interrupt creating, effectively, + a 48-bit RTC counter. + + In the lo-res mode, the RTC operates at 1Hz. Overflow interrupts are not handled + (because the next overflow is not expected until the year 2106. + + WARNING: Overflow interrupts are lost whenever the STM32 is powered down. The + overflow interrupt may be lost even if the STM32 is powered down only momentarily. + Therefore hi-res solution is only useful in systems where the power is always on. + +STM3210E-EVAL-specific Configuration Options +============================================ + + CONFIG_ARCH - Identifies the arch/ subdirectory. This should + be set to: + + CONFIG_ARCH=arm + + CONFIG_ARCH_family - For use in C code: + + CONFIG_ARCH_ARM=y + + CONFIG_ARCH_architecture - For use in C code: + + CONFIG_ARCH_CORTEXM3=y + + CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory + + CONFIG_ARCH_CHIP=stm32 + + CONFIG_ARCH_CHIP_name - For use in C code to identify the exact + chip: + + CONFIG_ARCH_CHIP_STM32F103ZET6 + + CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock + configuration features. + + CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n + + CONFIG_ARCH_BOARD - Identifies the configs subdirectory and + hence, the board that supports the particular chip or SoC. + + CONFIG_ARCH_BOARD=stm3210e_eval (for the STM3210E-EVAL development board) + + CONFIG_ARCH_BOARD_name - For use in C code + + CONFIG_ARCH_BOARD_STM3210E_EVAL=y + + CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation + of delay loops + + CONFIG_ENDIAN_BIG - define if big endian (default is little + endian) + + CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): + + CONFIG_DRAM_SIZE=0x00010000 (64Kb) + + CONFIG_DRAM_START - The start address of installed DRAM + + CONFIG_DRAM_START=0x20000000 + + CONFIG_DRAM_END - Last address+1 of installed RAM + + CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) + + CONFIG_ARCH_IRQPRIO - The STM32F103Z supports interrupt prioritization + + CONFIG_ARCH_IRQPRIO=y + + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that + have LEDs + + CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt + stack. If defined, this symbol is the size of the interrupt + stack in bytes. If not defined, the user task stacks will be + used during interrupt handling. + + CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions + + CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. + + CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that + cause a 100 second delay during boot-up. This 100 second delay + serves no purpose other than it allows you to calibratre + CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure + the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until + the delay actually is 100 seconds. + + Individual subsystems can be enabled: + AHB + --- + CONFIG_STM32_DMA1 + CONFIG_STM32_DMA2 + CONFIG_STM32_CRC + CONFIG_STM32_FSMC + CONFIG_STM32_SDIO + + APB1 + ---- + CONFIG_STM32_TIM2 + CONFIG_STM32_TIM3 + CONFIG_STM32_TIM4 + CONFIG_STM32_TIM5 + CONFIG_STM32_TIM6 + CONFIG_STM32_TIM7 + CONFIG_STM32_WWDG + CONFIG_STM32_SPI2 + CONFIG_STM32_SPI4 + CONFIG_STM32_USART2 + CONFIG_STM32_USART3 + CONFIG_STM32_UART4 + CONFIG_STM32_UART5 + CONFIG_STM32_I2C1 + CONFIG_STM32_I2C2 + CONFIG_STM32_USB + CONFIG_STM32_CAN + CONFIG_STM32_BKP + CONFIG_STM32_PWR + CONFIG_STM32_DAC1 + CONFIG_STM32_DAC2 + CONFIG_STM32_USB + + APB2 + ---- + CONFIG_STM32_ADC1 + CONFIG_STM32_ADC2 + CONFIG_STM32_TIM1 + CONFIG_STM32_SPI1 + CONFIG_STM32_TIM8 + CONFIG_STM32_USART1 + CONFIG_STM32_ADC3 + + Timer and I2C devices may need to the following to force power to be applied + unconditionally at power up. (Otherwise, the device is powered when it is + initialized). + + CONFIG_STM32_FORCEPOWER + + Timer devices may be used for different purposes. One special purpose is + to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn + is defined (as above) then the following may also be defined to indicate that + the timer is intended to be used for pulsed output modulation, ADC conversion, + or DAC conversion. Note that ADC/DAC require two definition: Not only do you have + to assign the timer (n) for used by the ADC or DAC, but then you also have to + configure which ADC or DAC (m) it is assigned to. + + CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,8 + CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,8 + CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,8, m=1,..,3 + CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,8 + CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,8, m=1,..,2 + + For each timer that is enabled for PWM usage, we need the following additional + configuration settings: + + CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4} + + NOTE: The STM32 timers are each capable of generating different signals on + each of the four channels with different duty cycles. That capability is + not supported by this driver: Only one output channel per timer. + + Alternate pin mappings (should not be used with the STM3210E-EVAL board): + + CONFIG_STM32_TIM1_FULL_REMAP + CONFIG_STM32_TIM1_PARTIAL_REMAP + CONFIG_STM32_TIM2_FULL_REMAP + CONFIG_STM32_TIM2_PARTIAL_REMAP_1 + CONFIG_STM32_TIM2_PARTIAL_REMAP_2 + CONFIG_STM32_TIM3_FULL_REMAP + CONFIG_STM32_TIM3_PARTIAL_REMAP + CONFIG_STM32_TIM4_REMAP + CONFIG_STM32_USART1_REMAP + CONFIG_STM32_USART2_REMAP + CONFIG_STM32_USART3_FULL_REMAP + CONFIG_STM32_USART3_PARTIAL_REMAP + CONFIG_STM32_SPI1_REMAP + CONFIG_STM32_SPI3_REMAP + CONFIG_STM32_I2C1_REMAP + CONFIG_STM32_CAN1_FULL_REMAP + CONFIG_STM32_CAN1_PARTIAL_REMAP + CONFIG_STM32_CAN2_REMAP + + JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): + CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) + but without JNTRST. + CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled + + STM32F103Z specific device driver settings + + CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART + m (m=4,5) for the console and ttys0 (default is the USART1). + CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. + This specific the size of the receive buffer + CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before + being sent. This specific the size of the transmit buffer + CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be + CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. + CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity + CONFIG_U[S]ARTn_2STOP - Two stop bits + + CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI + support. Non-interrupt-driven, poll-waiting is recommended if the + interrupt rate would be to high in the interrupt driven case. + CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance. + Cannot be used with CONFIG_STM32_SPI_INTERRUPT. + + CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO + and CONFIG_STM32_DMA2. + CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128 + CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority. + Default: Medium + CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: + 4-bit transfer mode. + + STM3210E-EVAL CAN Configuration + + 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. + Default: 4 + CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback + 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_REGDEBUG - If CONFIG_DEBUG is set, this will generate an + dump of all CAN registers. + + STM3210E-EVAL LCD Hardware Configuration + + CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape" + support. Default is this 320x240 "landscape" orientation + (this setting is informative only... not used). + CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait" + orientation support. In this orientation, the STM3210E-EVAL's + LCD ribbon cable is at the bottom of the display. Default is + 320x240 "landscape" orientation. + CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse + portrait" orientation support. In this orientation, the + STM3210E-EVAL's LCD ribbon cable is at the top of the display. + Default is 320x240 "landscape" orientation. + CONFIG_LCD_BACKLIGHT - Define to support a backlight. + CONFIG_LCD_PWM - If CONFIG_STM32_TIM1 is also defined, then an + adjustable backlight will be provided using timer 1 to generate + various pulse widthes. The granularity of the settings is + determined by CONFIG_LCD_MAXPOWER. If CONFIG_LCD_PWM (or + CONFIG_STM32_TIM1) is not defined, then a simple on/off backlight + is provided. + CONFIG_LCD_RDSHIFT - When reading 16-bit gram data, there appears + to be a shift in the returned data. This value fixes the offset. + Default 5. + + The LCD driver dynamically selects the LCD based on the reported LCD + ID value. However, code size can be reduced by suppressing support for + individual LCDs using: + + CONFIG_STM32_AM240320_DISABLE + CONFIG_STM32_SPFD5408B_DISABLE + CONFIG_STM32_R61580_DISABLE + +Configurations +============== + +Each STM3210E-EVAL configuration is maintained in a sudirectory and +can be selected as follow: + + cd tools + ./configure.sh stm3210e-eval/ + cd - + . ./setenv.sh + +Where is one of the following: + + buttons: + -------- + + Uses apps/examples/buttons to exercise STM3210E-EVAL buttons and + button interrupts. + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + + composite + --------- + + This configuration exercises a composite USB interface consisting + of a CDC/ACM device and a USB mass storage device. This configuration + uses apps/examples/composite. + + nsh and nsh2: + ------------ + Configure the NuttShell (nsh) located at examples/nsh. + + Differences between the two NSH configurations: + + =========== ======================= ================================ + nsh nsh2 + =========== ======================= ================================ + Toolchain: NuttX buildroot for Codesourcery for Windows (1) + Linux or Cygwin (1,2) + ----------- ----------------------- -------------------------------- + Loader: DfuSe DfuSe + ----------- ----------------------- -------------------------------- + Serial Debug output: USART1 Debug output: USART1 + Console: NSH output: USART1 NSH output: USART1 (3) + ----------- ----------------------- -------------------------------- + microSD Yes Yes + Support + ----------- ----------------------- -------------------------------- + FAT FS CONFIG_FAT_LCNAME=y CONFIG_FAT_LCNAME=y + Config CONFIG_FAT_LFN=n CONFIG_FAT_LFN=y (4) + ----------- ----------------------- -------------------------------- + Support for No Yes + Built-in + Apps + ----------- ----------------------- -------------------------------- + Built-in None apps/examples/nx + Apps apps/examples/nxhello + apps/examples/usbstorage (5) + =========== ======================= ================================ + + (1) You will probably need to modify nsh/setenv.sh or nsh2/setenv.sh + to set up the correct PATH variable for whichever toolchain you + may use. + (2) Since DfuSe is assumed, this configuration may only work under + Cygwin without modification. + (3) When any other device other than /dev/console is used for a user + interface, (1) linefeeds (\n) will not be expanded to carriage return + / linefeeds \r\n). You will need to configure your terminal program + to account for this. And (2) input is not automatically echoed so + you will have to turn local echo on. + (4) Microsoft holds several patents related to the design of + long file names in the FAT file system. Please refer to the + details in the top-level COPYING file. Please do not use FAT + long file name unless you are familiar with these patent issues. + (5) When built as an NSH add-on command (CONFIG_EXAMPLES_USBMSC_BUILTIN=y), + Caution should be used to assure that the SD drive is not in use when + the USB storage device is configured. Specifically, the SD driver + should be unmounted like: + + nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Card is mounted in NSH + ... + nsh> umount /mnd/sdcard # Unmount before connecting USB!!! + nsh> msconn # Connect the USB storage device + ... + nsh> msdis # Disconnect USB storate device + nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Restore the mount + + Failure to do this could result in corruption of the SD card format. + + nx: + --- + An example using the NuttX graphics system (NX). This example + focuses on general window controls, movement, mouse and keyboard + input. + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait + + nxlines: + ------ + Another example using the NuttX graphics system (NX). This + example focuses on placing lines on the background in various + orientations. + + CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait + + nxtext: + ------ + Another example using the NuttX graphics system (NX). This + example focuses on placing text on the background while pop-up + windows occur. Text should continue to update normally with + or without the popup windows present. + + CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait + + NOTE: When I tried building this example with the CodeSourcery + tools, I got a hardfault inside of its libgcc. I haven't + retested since then, but beware if you choose to change the + toolchain. + + ostest: + ------ + This configuration directory, performs a simple OS test using + examples/ostest. By default, this project assumes that you are + using the DFU bootloader. + + CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + + RIDE + ---- + This configuration builds a trivial bring-up binary. It is + useful only because it words with the RIDE7 IDE and R-Link debugger. + + CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows + + usbserial: + --------- + This configuration directory exercises the USB serial class + driver at examples/usbserial. See examples/README.txt for + more information. + + CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + + USB debug output can be enabled as by changing the following + settings in the configuration file: + + -CONFIG_DEBUG=n + -CONFIG_DEBUG_VERBOSE=n + -CONFIG_DEBUG_USB=n + +CONFIG_DEBUG=y + +CONFIG_DEBUG_VERBOSE=y + +CONFIG_DEBUG_USB=y + + -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n + -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n + -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n + -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n + -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n + +CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=y + +CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=y + +CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=y + +CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=y + +CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=y + + By default, the usbserial example uses the Prolific PL2303 + serial/USB converter emulation. The example can be modified + to use the CDC/ACM serial class by making the following changes + to the configuration file: + + -CONFIG_PL2303=y + +CONFIG_PL2303=n + + -CONFIG_CDCACM=n + +CONFIG_CDCACM=y + + The example can also be converted to use the alternative + USB serial example at apps/examples/usbterm by changing the + following: + + -CONFIGURED_APPS += examples/usbserial + +CONFIGURED_APPS += examples/usbterm + + In either the original appconfig file (before configuring) + or in the final apps/.config file (after configuring). + + usbstorage: + ---------- + This configuration directory exercises the USB mass storage + class driver at examples/usbstorage. See examples/README.txt for + more information. + + CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin + diff --git a/nuttx-configs/px4io-v2/common/Make.defs b/nuttx-configs/px4io-v2/common/Make.defs new file mode 100644 index 000000000..7f782b5b2 --- /dev/null +++ b/nuttx-configs/px4io-v2/common/Make.defs @@ -0,0 +1,175 @@ +############################################################################ +# configs/px4fmu/common/Make.defs +# +# Copyright (C) 2011 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. +# +############################################################################ + +# +# Generic Make.defs for the PX4FMU +# Do not specify/use this file directly - it is included by config-specific +# Make.defs in the per-config directories. +# + +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m3 \ + -mthumb \ + -march=armv7-m + +# enable precise stack overflow tracking +#INSTRUMENTATIONDEFINES = -finstrument-functions \ +# -ffixed-r10 + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4io-v2/common/ld.script b/nuttx-configs/px4io-v2/common/ld.script new file mode 100755 index 000000000..69c2f9cb2 --- /dev/null +++ b/nuttx-configs/px4io-v2/common/ld.script @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/stm3210e-eval/nsh/ld.script + * + * Copyright (C) 2009, 2011 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. + * + ****************************************************************************/ + +/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and + * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +OUTPUT_ARCH(arm) +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32F100CB has 8Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4io-v2/common/setenv.sh b/nuttx-configs/px4io-v2/common/setenv.sh new file mode 100755 index 000000000..ff9a4bf8a --- /dev/null +++ b/nuttx-configs/px4io-v2/common/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# Copyright (C) 2009 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi + +WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4io-v2/include/README.txt b/nuttx-configs/px4io-v2/include/README.txt new file mode 100755 index 000000000..2264a80aa --- /dev/null +++ b/nuttx-configs/px4io-v2/include/README.txt @@ -0,0 +1 @@ +This directory contains header files unique to the PX4IO board. diff --git a/nuttx-configs/px4io-v2/include/board.h b/nuttx-configs/px4io-v2/include/board.h new file mode 100755 index 000000000..b93ad4220 --- /dev/null +++ b/nuttx-configs/px4io-v2/include/board.h @@ -0,0 +1,177 @@ +/************************************************************************************ + * configs/px4io/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * 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_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +#endif +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* On-board crystal frequency is 24MHz (HSE) */ + +#define STM32_BOARD_XTAL 24000000ul + +/* Use the HSE output as the system clock */ + +#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE +#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE +#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL + +/* AHB clock (HCLK) is SYSCLK (24MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB2 clock (PCLK2) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */ + +/* APB2 timer 1 will receive PCLK2. */ + +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) + +/* APB1 clock (PCLK1) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* All timers run off PCLK */ + +#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY) + +/* + * Some of the USART pins are not available; override the GPIO + * definitions with an invalid pin configuration. + */ +#undef GPIO_USART2_CTS +#define GPIO_USART2_CTS 0xffffffff +#undef GPIO_USART2_RTS +#define GPIO_USART2_RTS 0xffffffff +#undef GPIO_USART2_CK +#define GPIO_USART2_CK 0xffffffff +#undef GPIO_USART3_TX +#define GPIO_USART3_TX 0xffffffff +#undef GPIO_USART3_CK +#define GPIO_USART3_CK 0xffffffff +#undef GPIO_USART3_CTS +#define GPIO_USART3_CTS 0xffffffff +#undef GPIO_USART3_RTS +#define GPIO_USART3_RTS 0xffffffff + +/* + * High-resolution timer + */ +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ + +/* + * PPM + * + * PPM input is handled by the HRT timer. + * + * Pin is PA8, timer 1, channel 1 + */ +#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN GPIO_TIM1_CH1IN + +/* LED definitions ******************************************************************/ +/* PX4 has two LEDs that we will encode as: */ + +#define LED_STARTED 0 /* LED? */ +#define LED_HEAPALLOCATE 1 /* LED? */ +#define LED_IRQSENABLED 2 /* LED? + LED? */ +#define LED_STACKCREATED 3 /* LED? */ +#define LED_INIRQ 4 /* LED? + LED? */ +#define LED_SIGNAL 5 /* LED? + LED? */ +#define LED_ASSERTION 6 /* LED? + LED? + LED? */ +#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * 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. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx-configs/px4io-v2/nsh/Make.defs b/nuttx-configs/px4io-v2/nsh/Make.defs new file mode 100644 index 000000000..bdfc4e3e2 --- /dev/null +++ b/nuttx-configs/px4io-v2/nsh/Make.defs @@ -0,0 +1,3 @@ +include ${TOPDIR}/.config + +include $(TOPDIR)/configs/px4io-v2/common/Make.defs diff --git a/nuttx-configs/px4io-v2/nsh/appconfig b/nuttx-configs/px4io-v2/nsh/appconfig new file mode 100644 index 000000000..48a41bcdb --- /dev/null +++ b/nuttx-configs/px4io-v2/nsh/appconfig @@ -0,0 +1,32 @@ +############################################################################ +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# +# 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 PX4 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. +# +############################################################################ diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig new file mode 100755 index 000000000..846ea8fb9 --- /dev/null +++ b/nuttx-configs/px4io-v2/nsh/defconfig @@ -0,0 +1,526 @@ +############################################################################ +# configs/px4io/nsh/defconfig +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (C) 2011-2012 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. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# 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 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, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# CONFIG_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# 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 +# stack in bytes. If not defined, the user task stacks will be +# used during interrupt handling. +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. +# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. +# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that +# cause a 100 second delay during boot-up. This 100 second delay +# serves no purpose other than it allows you to calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH="arm" +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32F100C8=y +CONFIG_ARCH_BOARD="px4io-v2" +CONFIG_ARCH_BOARD_PX4IO_V2=y +CONFIG_BOARD_LOOPSPERMSEC=2000 +CONFIG_DRAM_SIZE=0x00002000 +CONFIG_DRAM_START=0x20000000 +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_INTERRUPTSTACK=n +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=n +CONFIG_ARCH_BUTTONS=n +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=y +CONFIG_ARCH_MATH_H=y + +CONFIG_ARMV7M_CMNVECTOR=y + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=n + +# +# Individual subsystems can be enabled: +# +# AHB: +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=n +CONFIG_STM32_CRC=n +# APB1: +# Timers 2,3 and 4 are owned by the PWM driver +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=n +CONFIG_STM32_TIM4=n +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_WWDG=n +CONFIG_STM32_SPI2=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_I2C1=n +CONFIG_STM32_I2C2=n +CONFIG_STM32_BKP=n +CONFIG_STM32_PWR=n +CONFIG_STM32_DAC=n +# APB2: +# We use our own ADC driver, but leave this on for clocking purposes. +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +# TIM1 is owned by the HRT +CONFIG_STM32_TIM1=n +CONFIG_STM32_SPI1=n +CONFIG_STM32_TIM8=n +CONFIG_STM32_USART1=y +CONFIG_STM32_ADC3=n + + +# +# STM32F100 specific serial device driver settings +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_SERIAL_TERMIOS=y +CONFIG_STANDARD_SERIAL=y + +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART2_SERIAL_CONSOLE=n +CONFIG_USART3_SERIAL_CONSOLE=n + +CONFIG_USART1_TXBUFSIZE=64 +CONFIG_USART2_TXBUFSIZE=64 +CONFIG_USART3_TXBUFSIZE=64 + +CONFIG_USART1_RXBUFSIZE=64 +CONFIG_USART2_RXBUFSIZE=64 +CONFIG_USART3_RXBUFSIZE=64 + +CONFIG_USART1_BAUD=115200 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 + +CONFIG_USART1_RXDMA=y +SERIAL_HAVE_CONSOLE_DMA=y +# Conflicts with I2C1 DMA +CONFIG_USART2_RXDMA=n +CONFIG_USART3_RXDMA=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# 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 +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# 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_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, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# 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). +# 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 +# the worker thread. Default: 4 +# CONFIG_SCHED_WAITPID - Enable the waitpid() API +# CONFIG_SCHED_ATEXIT - Enabled the atexit() API +# +CONFIG_USER_ENTRYPOINT="user_start" +#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_MSEC_PER_TICK=1 +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_MM_REGIONS=1 +CONFIG_MM_SMALL=y +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=8 +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +# this eats ~1KiB of RAM ... work out why +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=n +CONFIG_SCHED_WORKPRIORITY=50 +CONFIG_SCHED_WORKPERIOD=50000 +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 +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_DISABLE_SIGNALS=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# 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 +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=4 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=2 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=0 +CONFIG_NAME_MAX=12 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=n +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=0 + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# 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_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# + +# Disable NSH completely +CONFIG_NSH_CONSOLE=n + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3210E-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1200 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=1024 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx-configs/px4io-v2/nsh/setenv.sh b/nuttx-configs/px4io-v2/nsh/setenv.sh new file mode 100755 index 000000000..ff9a4bf8a --- /dev/null +++ b/nuttx-configs/px4io-v2/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# Copyright (C) 2009 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi + +WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4io-v2/src/Makefile b/nuttx-configs/px4io-v2/src/Makefile new file mode 100644 index 000000000..bb9539d16 --- /dev/null +++ b/nuttx-configs/px4io-v2/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/stm3210e-eval/src/Makefile +# +# Copyright (C) 2009-2010 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)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/nuttx-configs/px4io-v2/src/README.txt b/nuttx-configs/px4io-v2/src/README.txt new file mode 100644 index 000000000..d4eda82fd --- /dev/null +++ b/nuttx-configs/px4io-v2/src/README.txt @@ -0,0 +1 @@ +This directory contains drivers unique to the STMicro STM3210E-EVAL development board. diff --git a/nuttx-configs/px4io-v2/src/empty.c b/nuttx-configs/px4io-v2/src/empty.c new file mode 100644 index 000000000..ace900866 --- /dev/null +++ b/nuttx-configs/px4io-v2/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ diff --git a/nuttx-configs/px4io-v2/test/Make.defs b/nuttx-configs/px4io-v2/test/Make.defs new file mode 100644 index 000000000..87508e22e --- /dev/null +++ b/nuttx-configs/px4io-v2/test/Make.defs @@ -0,0 +1,3 @@ +include ${TOPDIR}/.config + +include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs diff --git a/nuttx-configs/px4io-v2/test/appconfig b/nuttx-configs/px4io-v2/test/appconfig new file mode 100644 index 000000000..3cfc41b43 --- /dev/null +++ b/nuttx-configs/px4io-v2/test/appconfig @@ -0,0 +1,44 @@ +############################################################################ +# configs/stm3210e-eval/nsh/appconfig +# +# Copyright (C) 2011-2012 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. +# +############################################################################ + +# Path to example in apps/examples containing the user_start entry point + +CONFIGURED_APPS += examples/nsh + +CONFIGURED_APPS += system/readline +CONFIGURED_APPS += nshlib +CONFIGURED_APPS += reboot + +CONFIGURED_APPS += drivers/boards/px4iov2 diff --git a/nuttx-configs/px4io-v2/test/defconfig b/nuttx-configs/px4io-v2/test/defconfig new file mode 100755 index 000000000..19dfefdf8 --- /dev/null +++ b/nuttx-configs/px4io-v2/test/defconfig @@ -0,0 +1,544 @@ +############################################################################ +# configs/px4io/nsh/defconfig +# +# Copyright (C) 2009-2012 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. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# 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. +# 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, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# 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 +# stack in bytes. If not defined, the user task stacks will be +# used during interrupt handling. +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. +# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. +# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that +# cause a 100 second delay during boot-up. This 100 second delay +# serves no purpose other than it allows you to calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH=arm +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_CHIP=stm32 +CONFIG_ARCH_CHIP_STM32F100C8=y +CONFIG_ARCH_BOARD=px4iov2 +CONFIG_ARCH_BOARD_PX4IO_V2=y +CONFIG_BOARD_LOOPSPERMSEC=24000 +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 +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=n +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=n +CONFIG_ARMV7M_CMNVECTOR=y + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=n + +# +# Individual subsystems can be enabled: +# AHB: +CONFIG_STM32_DMA1=n +CONFIG_STM32_DMA2=n +CONFIG_STM32_CRC=n +# APB1: +# Timers 2,3 and 4 are owned by the PWM driver +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=n +CONFIG_STM32_TIM4=n +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_WWDG=n +CONFIG_STM32_SPI2=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=n +CONFIG_STM32_BKP=n +CONFIG_STM32_PWR=n +CONFIG_STM32_DAC=n +# APB2: +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +# TIM1 is owned by the HRT +CONFIG_STM32_TIM1=n +CONFIG_STM32_SPI1=n +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 +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART2_SERIAL_CONSOLE=n +CONFIG_USART3_SERIAL_CONSOLE=n + +CONFIG_USART1_TXBUFSIZE=64 +CONFIG_USART2_TXBUFSIZE=64 +CONFIG_USART3_TXBUFSIZE=64 + +CONFIG_USART1_RXBUFSIZE=64 +CONFIG_USART2_RXBUFSIZE=64 +CONFIG_USART3_RXBUFSIZE=64 + +CONFIG_USART1_BAUD=57600 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# 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 +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# 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, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# 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). +# 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 +# the worker thread. Default: 4 +# +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=n +CONFIG_MM_REGIONS=1 +CONFIG_MM_SMALL=y +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_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +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=512 +CONFIG_SIG_SIGWORK=4 + +CONFIG_USER_ENTRYPOINT="nsh_main" +# +# 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 +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# 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_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 +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=4 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=2 +CONFIG_NFILE_DESCRIPTORS=6 +CONFIG_NFILE_STREAMS=4 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=1 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=3 +CONFIG_PREALLOC_TIMERS=1 + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# 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_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# +# If CONFIG_NSH_TELNET is selected: +# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size +# CONFIG_NSH_DHCPC - Obtain address using DHCP +# CONFIG_NSH_IPADDR - Provides static IP address +# CONFIG_NSH_DRIPADDR - Provides static router IP address +# CONFIG_NSH_NETMASK - Provides static network mask +# CONFIG_NSH_NOMAC - Use a bogus MAC address +# +# If CONFIG_NSH_ROMFSETC is selected: +# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint +# CONFIG_NSH_INITSCRIPT - Relative path to init script +# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor +# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size +# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor +# CONFIG_NSH_FATSECTSIZE - FAT FS sector size +# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors +# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint +# +CONFIG_BUILTIN=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=64 +CONFIG_NSH_STRERROR=n +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=1 +CONFIG_NSH_DISABLESCRIPT=y +CONFIG_NSH_DISABLEBG=n +CONFIG_NSH_ROMFSETC=n +CONFIG_NSH_CONSOLE=y +CONFIG_NSH_TELNET=n +CONFIG_NSH_ARCHINIT=n +CONFIG_NSH_IOBUFFER_SIZE=256 +CONFIG_NSH_STACKSIZE=1024 +CONFIG_NSH_DHCPC=n +CONFIG_NSH_NOMAC=n +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_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=64 +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT=/tmp + +# +# Architecture-specific NSH options +# +CONFIG_NSH_MMCSDSPIPORTNO=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDMINOR=0 + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3210E-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +CONFIG_IDLETHREAD_STACKSIZE=800 +CONFIG_USERMAIN_STACKSIZE=1024 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=512 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx-configs/px4io-v2/test/setenv.sh b/nuttx-configs/px4io-v2/test/setenv.sh new file mode 100755 index 000000000..d83685192 --- /dev/null +++ b/nuttx-configs/px4io-v2/test/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# Copyright (C) 2009 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. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi + +WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/configs/px4fmuv2/Kconfig b/nuttx/configs/px4fmuv2/Kconfig deleted file mode 100644 index a10a02ba4..000000000 --- a/nuttx/configs/px4fmuv2/Kconfig +++ /dev/null @@ -1,7 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -if ARCH_BOARD_PX4FMUV2 -endif diff --git a/nuttx/configs/px4fmuv2/common/Make.defs b/nuttx/configs/px4fmuv2/common/Make.defs deleted file mode 100644 index be387dce1..000000000 --- a/nuttx/configs/px4fmuv2/common/Make.defs +++ /dev/null @@ -1,184 +0,0 @@ -############################################################################ -# configs/px4fmu/common/Make.defs -# -# Copyright (C) 2011 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. -# -############################################################################ - -# -# Generic Make.defs for the PX4FMUV2 -# Do not specify/use this file directly - it is included by config-specific -# Make.defs in the per-config directories. -# - -include ${TOPDIR}/tools/Config.mk - -# -# We only support building with the ARM bare-metal toolchain from -# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. -# -CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI - -include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs - -CC = $(CROSSDEV)gcc -CXX = $(CROSSDEV)g++ -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump - -MAXOPTIMIZATION = -O3 -ARCHCPUFLAGS = -mcpu=cortex-m4 \ - -mthumb \ - -march=armv7e-m \ - -mfpu=fpv4-sp-d16 \ - -mfloat-abi=hard - - -# enable precise stack overflow tracking -INSTRUMENTATIONDEFINES = -finstrument-functions \ - -ffixed-r10 - -# pull in *just* libm from the toolchain ... this is grody -LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" -EXTRA_LIBS += $(LIBM) - -# use our linker script -LDSCRIPT = ld.script - -ifeq ($(WINTOOL),y) - # Windows-native toolchains - DIRLINK = $(TOPDIR)/tools/copydir.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" - ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}" -else - ifeq ($(PX4_WINTOOL),y) - # Windows-native toolchains (MSYS) - DIRLINK = $(TOPDIR)/tools/copydir.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - ARCHINCLUDES = -I. -isystem $(TOPDIR)/include - ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) - else - # Linux/Cygwin-native toolchain - MKDEP = $(TOPDIR)/tools/mkdeps.sh - ARCHINCLUDES = -I. -isystem $(TOPDIR)/include - ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) - endif -endif - -# tool versions -ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} -ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} - -# optimisation flags -ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -fno-strict-aliasing \ - -fno-strength-reduce \ - -fomit-frame-pointer \ - -funsafe-math-optimizations \ - -fno-builtin-printf \ - -ffunction-sections \ - -fdata-sections - -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") -ARCHOPTIMIZATION += -g -endif - -ARCHCFLAGS = -std=gnu99 -ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -ARCHWARNINGS = -Wall \ - -Wextra \ - -Wdouble-promotion \ - -Wshadow \ - -Wfloat-equal \ - -Wframe-larger-than=1024 \ - -Wpointer-arith \ - -Wlogical-op \ - -Wmissing-declarations \ - -Wpacked \ - -Wno-unused-parameter -# -Wcast-qual - generates spurious noreturn attribute warnings, try again later -# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code -# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives - -ARCHCWARNINGS = $(ARCHWARNINGS) \ - -Wbad-function-cast \ - -Wstrict-prototypes \ - -Wold-style-declaration \ - -Wmissing-parameter-type \ - -Wmissing-prototypes \ - -Wnested-externs \ - -Wunsuffixed-float-constants -ARCHWARNINGSXX = $(ARCHWARNINGS) \ - -Wno-psabi -ARCHDEFINES = -ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 - -# this seems to be the only way to add linker flags -EXTRA_LIBS += --warn-common \ - --gc-sections - -CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common -CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) -CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) -CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ - -NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections -LDNXFLATFLAGS = -e main -s 2048 - -OBJEXT = .o -LIBEXT = .a -EXEEXT = - - -# produce partially-linked $1 from files in $2 -define PRELINK - @echo "PRELINK: $1" - $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 -endef - -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe -HOSTLDFLAGS = - diff --git a/nuttx/configs/px4fmuv2/common/ld.script b/nuttx/configs/px4fmuv2/common/ld.script deleted file mode 100644 index 1be39fb87..000000000 --- a/nuttx/configs/px4fmuv2/common/ld.script +++ /dev/null @@ -1,150 +0,0 @@ -/**************************************************************************** - * configs/px4fmu/common/ld.script - * - * Copyright (C) 2011 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. - * - ****************************************************************************/ - -/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and - * 256Kb of SRAM. SRAM is split up into three blocks: - * - * 1) 112Kb of SRAM beginning at address 0x2000:0000 - * 2) 16Kb of SRAM beginning at address 0x2001:c000 - * 3) 64Kb of SRAM beginning at address 0x2002:0000 - * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 - * - * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 - * where the code expects to begin execution by jumping to the entry point in - * the 0x0800:0000 address range. - * - * The first 0x4000 of flash is reserved for the bootloader. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K - ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K -} - -OUTPUT_ARCH(arm) - -ENTRY(__start) /* treat __start as the anchor for dead code stripping */ -EXTERN(_vectors) /* force the vectors to be included in the output */ - -/* - * Ensure that abort() is present in the final object. The exception handling - * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). - */ -EXTERN(abort) - -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - - /* - * This is a hack to make the newlib libm __errno() call - * use the NuttX get_errno_ptr() function. - */ - __errno = get_errno_ptr; - } > flash - - /* - * Init functions (static constructors and the like) - */ - .init_section : { - _sinit = ABSOLUTE(.); - KEEP(*(.init_array .init_array.*)) - _einit = ABSOLUTE(.); - } > flash - - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > flash - - .ARM.extab : { - *(.ARM.extab*) - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/px4fmuv2/include/board.h b/nuttx/configs/px4fmuv2/include/board.h deleted file mode 100755 index 0055d65e1..000000000 --- a/nuttx/configs/px4fmuv2/include/board.h +++ /dev/null @@ -1,364 +0,0 @@ -/************************************************************************************ - * configs/px4fmu/include/board.h - * include/arch/board/board.h - * - * Copyright (C) 2009 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. - * - ************************************************************************************/ - -#ifndef __ARCH_BOARD_BOARD_H -#define __ARCH_BOARD_BOARD_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#ifndef __ASSEMBLY__ -# include -#endif - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Clocking *************************************************************************/ -/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE. - * - * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: - * System Clock source : PLL (HSE) - * SYSCLK(Hz) : 168000000 Determined by PLL configuration - * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) - * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) - * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) - * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) - * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) - * PLLM : 24 (STM32_PLLCFG_PLLM) - * PLLN : 336 (STM32_PLLCFG_PLLN) - * PLLP : 2 (STM32_PLLCFG_PLLP) - * PLLQ : 7 (STM32_PLLCFG_PPQ) - * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK - * Flash Latency(WS) : 5 - * Prefetch Buffer : OFF - * Instruction cache : ON - * Data cache : ON - * Require 48MHz for USB OTG FS, : Enabled - * SDIO and RNG clock - */ - -/* HSI - 16 MHz RC factory-trimmed - * LSI - 32 KHz RC - * HSE - On-board crystal frequency is 24MHz - * LSE - not installed - */ - -#define STM32_BOARD_XTAL 24000000ul - -#define STM32_HSI_FREQUENCY 16000000ul -#define STM32_LSI_FREQUENCY 32000 -#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL -//#define STM32_LSE_FREQUENCY 32768 - -/* Main PLL Configuration. - * - * PLL source is HSE - * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN - * = (25,000,000 / 25) * 336 - * = 336,000,000 - * SYSCLK = PLL_VCO / PLLP - * = 336,000,000 / 2 = 168,000,000 - * USB OTG FS, SDIO and RNG Clock - * = PLL_VCO / PLLQ - * = 48,000,000 - */ - -#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_PLLQ RCC_PLLCFG_PLLQ(7) - -#define STM32_SYSCLK_FREQUENCY 168000000ul - -/* AHB clock (HCLK) is SYSCLK (168MHz) */ - -#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ -#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY -#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ - -/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ - -#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ -#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) - -/* Timers driven from APB1 will be twice PCLK1 */ - -#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) - -/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ - -#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ -#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) - -/* Timers driven from APB2 will be twice PCLK2 */ - -#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY) - -/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx - * otherwise frequency is 2xAPBx. - * Note: TIM1,8 are on APB2, others on APB1 - */ - -#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY) -#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY) - -/* SDIO dividers. Note that slower clocking is required when DMA is disabled - * in order to avoid RX overrun/TX underrun errors due to delayed responses - * to service FIFOs in interrupt driven mode. These values have not been - * tuned!!! - * - * HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz - */ - -#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT) - -/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz - * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz - */ - -#ifdef CONFIG_SDIO_DMA -# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) -#else -# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) -#endif - -/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz - * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz - */ - -#ifdef CONFIG_SDIO_DMA -# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) -#else -# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) -#endif - -/* DMA Channl/Stream Selections *****************************************************/ -/* Stream selections are arbitrary for now but might become important in the future - * is we set aside more DMA channels/streams. - * - * SDIO DMA - *   DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA - *   DMAMAP_SDIO_2 = Channel 4, Stream 6 - */ - -#define DMAMAP_SDIO DMAMAP_SDIO_1 - -/* High-resolution timer - */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 8 /* use timer8 for the HRT */ -# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ -#endif - -/* Alternate function pin selections ************************************************/ - -/* - * UARTs. - */ -#define GPIO_USART1_RX GPIO_USART1_RX_1 /* console in from IO */ -#define GPIO_USART1_TX 0 /* USART1 is RX-only */ - -#define GPIO_USART2_RX GPIO_USART2_RX_2 -#define GPIO_USART2_TX GPIO_USART2_TX_2 -#define GPIO_USART2_RTS GPIO_USART2_RTS_2 -#define GPIO_USART2_CTS GPIO_USART2_CTS_2 - -#define GPIO_USART3_RX GPIO_USART3_RX_3 -#define GPIO_USART3_TX GPIO_USART3_TX_3 -#define GPIO_USART2_RTS GPIO_USART2_RTS_2 -#define GPIO_USART2_CTS GPIO_USART2_CTS_2 - -#define GPIO_UART4_RX GPIO_UART4_RX_1 -#define GPIO_UART4_TX GPIO_UART4_TX_1 - -#define GPIO_USART6_RX GPIO_USART6_RX_1 -#define GPIO_USART6_TX GPIO_USART6_TX_1 - -#define GPIO_UART7_RX GPIO_UART7_RX_1 -#define GPIO_UART7_TX GPIO_UART7_TX_1 - -/* UART8 has no alternate pin config */ - -/* UART RX DMA configurations */ -#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 -#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 - -/* - * PWM - * - * Six PWM outputs are configured. - * - * Pins: - * - * CH1 : PE14 : TIM1_CH4 - * CH2 : PE13 : TIM1_CH3 - * CH3 : PE11 : TIM1_CH2 - * CH4 : PE9 : TIM1_CH1 - * CH5 : PD13 : TIM4_CH2 - * CH6 : PD14 : TIM4_CH3 - * - */ -#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 -#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2 -#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2 -#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2 -#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 -#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2 - -/* - * CAN - * - * CAN1 is routed to the onboard transceiver. - * CAN2 is routed to the expansion connector. - */ - -#define GPIO_CAN1_RX GPIO_CAN1_RX_3 -#define GPIO_CAN1_TX GPIO_CAN1_TX_3 -#define GPIO_CAN2_RX GPIO_CAN2_RX_1 -#define GPIO_CAN2_TX GPIO_CAN2_TX_2 - -/* - * I2C - * - * The optional _GPIO configurations allow the I2C driver to manually - * reset the bus to clear stuck slaves. They match the pin configuration, - * but are normally-high GPIOs. - */ -#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 -#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 -#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) -#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) - -#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 -#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 -#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) -#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) - -/* - * I2C busses - */ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED 2 - -/* - * Devices on the onboard bus. - * - * Note that these are unshifted addresses. - */ -#define PX4_I2C_OBDEV_LED 0x55 -#define PX4_I2C_OBDEV_HMC5883 0x1e - -/* - * SPI - * - * There are sensors on SPI1, and SPI2 is connected to the FRAM. - */ -#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 -#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 -#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 - -#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 -#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 -#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 - -/* - * Use these in place of the spi_dev_e enumeration to - * select a specific SPI device on SPI1 - */ -#define PX4_SPIDEV_GYRO 1 -#define PX4_SPIDEV_ACCEL_MAG 2 -#define PX4_SPIDEV_BARO 3 - -/* - * Tone alarm output - */ -#define TONE_ALARM_TIMER 2 /* timer 2 */ -#define TONE_ALARM_CHANNEL 1 /* channel 1 */ -#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) -#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ -/************************************************************************************ - * 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. - * - ************************************************************************************/ - -EXTERN void stm32_boardinitialize(void); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx/configs/px4fmuv2/include/nsh_romfsimg.h b/nuttx/configs/px4fmuv2/include/nsh_romfsimg.h deleted file mode 100644 index 15e4e7a8d..000000000 --- a/nuttx/configs/px4fmuv2/include/nsh_romfsimg.h +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * - * 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 PX4 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. - * - ****************************************************************************/ - -/** - * nsh_romfsetc.h - * - * This file is a stub for 'make export' purposes; the actual ROMFS - * must be supplied by the library client. - */ - -extern unsigned char romfs_img[]; -extern unsigned int romfs_img_len; diff --git a/nuttx/configs/px4fmuv2/nsh/Make.defs b/nuttx/configs/px4fmuv2/nsh/Make.defs deleted file mode 100644 index 3306e4bf1..000000000 --- a/nuttx/configs/px4fmuv2/nsh/Make.defs +++ /dev/null @@ -1,3 +0,0 @@ -include ${TOPDIR}/.config - -include $(TOPDIR)/configs/px4fmuv2/common/Make.defs diff --git a/nuttx/configs/px4fmuv2/nsh/appconfig b/nuttx/configs/px4fmuv2/nsh/appconfig deleted file mode 100644 index 0e18aa8ef..000000000 --- a/nuttx/configs/px4fmuv2/nsh/appconfig +++ /dev/null @@ -1,52 +0,0 @@ -############################################################################ -# configs/px4fmu/nsh/appconfig -# -# Copyright (C) 2011 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nsh - -# The NSH application library -CONFIGURED_APPS += nshlib -CONFIGURED_APPS += system/readline - -ifeq ($(CONFIG_CAN),y) -#CONFIGURED_APPS += examples/can -endif - -#ifeq ($(CONFIG_USBDEV),y) -#ifeq ($(CONFIG_CDCACM),y) -CONFIGURED_APPS += examples/cdcacm -#endif -#endif diff --git a/nuttx/configs/px4fmuv2/nsh/defconfig b/nuttx/configs/px4fmuv2/nsh/defconfig deleted file mode 100755 index 17803c4d7..000000000 --- a/nuttx/configs/px4fmuv2/nsh/defconfig +++ /dev/null @@ -1,1083 +0,0 @@ -############################################################################ -# configs/px4fmu/nsh/defconfig -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# Copyright (C) 2011-2012 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. -# -############################################################################ -# -# architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_family - for use in C code. This identifies the -# 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 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, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# CONFIG_BOARD_LOOPSPERMSEC - for delay loops -# CONFIG_DRAM_SIZE - Describes the installed DRAM. -# CONFIG_DRAM_START - The start address of DRAM (physical) -# 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 -# stack. If defined, this symbol is the size of the interrupt -# stack in bytes. If not defined, the user task stacks will be -# used during interrupt handling. -# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions -# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. -# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. -# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. -# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that -# cause a 100 second delay during boot-up. This 100 second delay -# serves no purpose other than it allows you to calibrate -# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure -# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until -# the delay actually is 100 seconds. -# CONFIG_ARCH_DMA - Support DMA initialization -# -CONFIG_ARCH="arm" -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_CHIP="stm32" -CONFIG_ARCH_CHIP_STM32F427V=y -CONFIG_ARCH_BOARD="px4fmuv2" -CONFIG_ARCH_BOARD_PX4FMUV2=y -CONFIG_BOARD_LOOPSPERMSEC=16717 -CONFIG_DRAM_SIZE=0x00040000 -CONFIG_DRAM_START=0x20000000 -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_FPU=y -CONFIG_ARCH_INTERRUPTSTACK=n -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=n -CONFIG_ARCH_BUTTONS=n -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=y -CONFIG_ARCH_MATH_H=y - -CONFIG_ARMV7M_CMNVECTOR=y -CONFIG_STM32_STM32F427=y - -# -# JTAG Enable settings (by default JTAG-DP and SW-DP are enabled): -# -# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG (ignored) -# -# JTAG Enable options: -# -# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# but without JNTRST. -# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled -# -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=n -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=y - -# -# 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. -# -CONFIG_STM32_CCMEXCLUDE=y - -# -# On-board FSMC SRAM configuration -# -# CONFIG_STM32_FSMC - Required. See below -# CONFIG_MM_REGIONS - Required. Must be 2 or 3 (see above) -# -# CONFIG_STM32_FSMC_SRAM=y - Indicates that SRAM is available via the -# FSMC (as opposed to an LCD or FLASH). -# CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space -# CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space -# -#CONFIG_STM32_FSMC_SRAM=n -#CONFIG_HEAP2_BASE=0x64000000 -#CONFIG_HEAP2_END=(0x64000000+(2*1024*1024)) - -# -# Individual subsystems can be enabled: -# -# This set is exhaustive for PX4FMU and should be safe to cut and -# paste into any other config. -# -# AHB1: -CONFIG_STM32_CRC=n -CONFIG_STM32_BKPSRAM=y -CONFIG_STM32_CCMDATARAM=y -CONFIG_STM32_DMA1=y -CONFIG_STM32_DMA2=y -CONFIG_STM32_ETHMAC=n -CONFIG_STM32_OTGHS=n -# AHB2: -CONFIG_STM32_DCMI=n -CONFIG_STM32_CRYP=n -CONFIG_STM32_HASH=n -CONFIG_STM32_RNG=n -CONFIG_STM32_OTGFS=y -# AHB3: -CONFIG_STM32_FSMC=n -# APB1: -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=y -CONFIG_STM32_TIM4=y -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_TIM12=n -CONFIG_STM32_TIM13=n -CONFIG_STM32_TIM14=n -CONFIG_STM32_WWDG=y -CONFIG_STM32_IWDG=n -CONFIG_STM32_SPI2=y -CONFIG_STM32_SPI3=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=y -CONFIG_STM32_UART4=y -CONFIG_STM32_UART5=n -CONFIG_STM32_UART7=y -CONFIG_STM32_UART8=y -CONFIG_STM32_I2C1=y -CONFIG_STM32_I2C2=y -CONFIG_STM32_I2C3=n -CONFIG_STM32_CAN1=n -CONFIG_STM32_CAN2=n -CONFIG_STM32_DAC=n -CONFIG_STM32_PWR=y -# APB2: -CONFIG_STM32_TIM1=y -CONFIG_STM32_TIM8=n -CONFIG_STM32_USART1=y -# Mostly owned by the px4io driver, but uploader needs this -CONFIG_STM32_USART6=y -# We use our own driver, but leave this on. -CONFIG_STM32_ADC1=y -CONFIG_STM32_ADC2=n -CONFIG_STM32_ADC3=n -CONFIG_STM32_SDIO=y -CONFIG_STM32_SPI1=y -CONFIG_STM32_SYSCFG=y -CONFIG_STM32_TIM9=y -CONFIG_STM32_TIM10=y -CONFIG_STM32_TIM11=y - -# -# Enable single wire support. If this is not defined, then this mode cannot -# be enabled. -# -CONFIG_STM32_USART_SINGLEWIRE=y - -# -# We want the flash prefetch on for max performance. -# -STM32_FLASH_PREFETCH=y - -# -# STM32F40xxx specific serial device driver settings -# -# CONFIG_SERIAL_TERMIOS - Serial driver supports termios.h interfaces (tcsetattr, -# tcflush, etc.). If this is not defined, then the terminal settings (baud, -# parity, etc.) are not configurable at runtime; serial streams cannot be -# flushed, etc. -# CONFIG_SERIAL_CONSOLE_REINIT - re-initializes the console serial port -# immediately after creating the /dev/console device. This is required -# if the console serial port has RX DMA enabled. -# -# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the -# console and ttys0 (default is the USART1). -# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. -# This specific the size of the receive buffer -# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before -# being sent. This specific the size of the transmit buffer -# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be -# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. -# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity -# CONFIG_USARTn_2STOP - Two stop bits -# -CONFIG_SERIAL_TERMIOS=y -CONFIG_SERIAL_CONSOLE_REINIT=n -CONFIG_STANDARD_SERIAL=y - -CONFIG_UART8_SERIAL_CONSOLE=y - -#Mavlink messages can be bigger than 128 -CONFIG_USART1_TXBUFSIZE=512 -CONFIG_USART2_TXBUFSIZE=256 -CONFIG_USART3_TXBUFSIZE=256 -CONFIG_UART4_TXBUFSIZE=256 -CONFIG_USART6_TXBUFSIZE=128 -CONFIG_UART7_TXBUFSIZE=256 -CONFIG_UART8_TXBUFSIZE=256 - -CONFIG_USART1_RXBUFSIZE=512 -CONFIG_USART2_RXBUFSIZE=256 -CONFIG_USART3_RXBUFSIZE=256 -CONFIG_UART4_RXBUFSIZE=256 -CONFIG_USART6_RXBUFSIZE=256 -CONFIG_UART7_RXBUFSIZE=256 -CONFIG_UART8_RXBUFSIZE=256 - -CONFIG_USART1_BAUD=115200 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 -CONFIG_UART4_BAUD=115200 -CONFIG_USART6_BAUD=115200 -CONFIG_UART7_BAUD=115200 -CONFIG_UART8_BAUD=57600 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 -CONFIG_UART4_BITS=8 -CONFIG_USART6_BITS=8 -CONFIG_UART7_BITS=8 -CONFIG_UART8_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 -CONFIG_UART4_PARITY=0 -CONFIG_USART6_PARITY=0 -CONFIG_UART7_PARITY=0 -CONFIG_UART8_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 -CONFIG_UART4_2STOP=0 -CONFIG_USART6_2STOP=0 -CONFIG_UART7_2STOP=0 -CONFIG_UART8_2STOP=0 - -CONFIG_USART1_RXDMA=y -CONFIG_USART2_RXDMA=y -CONFIG_USART3_RXDMA=n -CONFIG_UART4_RXDMA=n -CONFIG_USART6_RXDMA=y -CONFIG_UART7_RXDMA=n -CONFIG_UART8_RXDMA=n - -# -# PX4FMU specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=n - -# -# STM32F40xxx specific SPI device driver settings -# -CONFIG_SPI_EXCHANGE=y -# DMA needs more work, not implemented on STM32F4x yet -#CONFIG_STM32_SPI_DMA=y - -# -# STM32F40xxx specific CAN device driver settings -# -# 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. -# Default: 4 -# CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback -# 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 -CONFIG_CAN1_BAUD=700000 -CONFIG_CAN2_BAUD=700000 - - -# XXX remove after integration testing -# 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 - -# -# I2C configuration -# -CONFIG_I2C=y -CONFIG_I2C_POLLED=n -CONFIG_I2C_TRANSFER=y -CONFIG_I2C_TRACE=n -CONFIG_I2C_RESET=y -# XXX fixed per-transaction timeout -CONFIG_STM32_I2CTIMEOMS=10 - -# -# MTD support -# -CONFIG_MTD=y - -# XXX re-enable after integration testing - -# -# I2C configuration -# -#CONFIG_I2C=y -#CONFIG_I2C_POLLED=y -#CONFIG_I2C_TRANSFER=y -#CONFIG_I2C_TRACE=n -#CONFIG_I2C_RESET=y - -# Dynamic timeout -#CONFIG_STM32_I2C_DYNTIMEO=y -#CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP=500 -#CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE=200 - -# Fixed per-transaction timeout -#CONFIG_STM32_I2CTIMEOSEC=0 -#CONFIG_STM32_I2CTIMEOMS=10 - - - - - - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=y - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# 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 -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. -# You would only need this if you are concerned about accurate -# time conversions in the past or in the distant future. -# CONFIG_JULIAN_TIME - Enables Julian time conversions. You -# would only need this if you are concerned about accurate -# time conversion in the distand past. You must also define -# CONFIG_GREGORIAN_TIME in order to use Julian time. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# 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_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, -# can be safely disabled. The worker thread also performs -# garbage collection -- completing any delayed memory deallocations -# from interrupt handlers. If the worker thread is disabled, -# then that clean will be performed by the IDLE thread instead -# (which runs at the lowest of priority and may not be appropriate -# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE -# is enabled, then the following options can also be used: -# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker -# thread. Default: 192 -# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for -# work in units of microseconds. Default: 50*1000 (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 -# the worker thread. Default: 4 -# -# CONFIG_SCHED_LPWORK. If CONFIG_SCHED_WORKQUEUE is defined, then a single -# work queue is created by default. If CONFIG_SCHED_LPWORK is also defined -# then an additional, lower-priority work queue will also be created. This -# lower priority work queue is better suited for more extended processing -# (such as file system clean-up operations) -# CONFIG_SCHED_LPWORKPRIORITY - The execution priority of the lower priority -# worker thread. Default: 50 -# CONFIG_SCHED_LPWORKPERIOD - How often the lower priority worker thread -# checks for work in units of microseconds. Default: 50*1000 (50 MS). -# CONFIG_SCHED_LPWORKSTACKSIZE - The stack size allocated for the lower -# priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE. -# CONFIG_SCHED_WAITPID - Enable the waitpid() API -# CONFIG_SCHED_ATEXIT - Enabled the atexit() API -# -CONFIG_USER_ENTRYPOINT="nsh_main" -#CONFIG_APPS_DIR= -CONFIG_DEBUG=y -CONFIG_DEBUG_VERBOSE=y -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=y -CONFIG_HAVE_CXXINITIALIZE=y -CONFIG_MM_REGIONS=2 -CONFIG_ARCH_LOWPUTC=y -CONFIG_MSEC_PER_TICK=1 -CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=y -CONFIG_TASK_NAME_SIZE=24 -CONFIG_START_YEAR=1970 -CONFIG_START_MONTH=1 -CONFIG_START_DAY=1 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=y -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=y -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=8 -CONFIG_FDCLONE_DISABLE=n -CONFIG_FDCLONE_STDIO=y -CONFIG_SDCLONE_DISABLE=y -CONFIG_SCHED_WORKQUEUE=y -CONFIG_SCHED_WORKPRIORITY=192 -CONFIG_SCHED_WORKPERIOD=5000 -CONFIG_SCHED_WORKSTACKSIZE=2048 -CONFIG_SCHED_LPWORK=y -CONFIG_SCHED_LPWORKPRIORITY=50 -CONFIG_SCHED_LPWORKPERIOD=50000 -CONFIG_SCHED_LPWORKSTACKSIZE=2048 -CONFIG_SIG_SIGWORK=4 -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 -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=n -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=n -CONFIG_DISABLE_MOUNTPOINT=n -CONFIG_DISABLE_ENVIRON=n -CONFIG_DISABLE_POLL=n - -# -# Misc libc settings -# -# 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 -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=y -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# 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 -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=32 -CONFIG_MAX_TASK_ARGS=8 -CONFIG_NPTHREAD_KEYS=4 -CONFIG_NFILE_DESCRIPTORS=32 -CONFIG_NFILE_STREAMS=25 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=256 -CONFIG_STDIO_LINEBUFFER=y -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=4 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_PREALLOC_WDOGS=50 -CONFIG_PREALLOC_TIMERS=50 - -# -# Filesystem configuration -# -# CONFIG_FS_FAT - Enable FAT filesystem support -# CONFIG_FAT_SECTORSIZE - Max supported sector size -# CONFIG_FAT_LCNAMES - Enable use of the NT-style upper/lower case 8.3 -# file name support. -# CONFIG_FAT_LFN - Enable FAT long file names. NOTE: Microsoft claims -# patents on FAT long file name technology. Please read the -# disclaimer in the top-level COPYING file and only enable this -# feature if you understand these issues. -# CONFIG_FAT_MAXFNAME - If CONFIG_FAT_LFN is defined, then the -# default, maximum long file name is 255 bytes. This can eat up -# a lot of memory (especially stack space). If you are willing -# to live with some non-standard, short long file names, then -# define this value. A good choice would be the same value as -# selected for CONFIG_NAME_MAX which will limit the visibility -# of longer file names anyway. -# CONFIG_FS_NXFFS: Enable NuttX FLASH file system (NXFF) support. -# CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH. -# This must have one of the values of 0xff or 0x00. -# Default: 0xff. -# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, -# don't both with file chunks smaller than this number of data bytes. -# CONFIG_NXFFS_MAXNAMLEN: The maximum size of an NXFFS file name. -# Default: 255. -# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data, -# don't both with file chunks smaller than this number of data bytes. -# Default: 32. -# CONFIG_NXFFS_TAILTHRESHOLD: clean-up can either mean -# packing files together toward the end of the file or, if file are -# deleted at the end of the file, clean up can simply mean erasing -# the end of FLASH memory so that it can be re-used again. However, -# doing this can also harm the life of the FLASH part because it can -# mean that the tail end of the FLASH is re-used too often. This -# threshold determines if/when it is worth erased the tail end of FLASH -# and making it available for re-use (and possible over-wear). -# Default: 8192. -# CONFIG_FS_ROMFS - Enable ROMFS filesystem support -# CONFIG_FS_RAMMAP - For file systems that do not support XIP, this -# option will enable a limited form of memory mapping that is -# implemented by copying whole files into memory. -# -CONFIG_FS_FAT=y -CONFIG_FAT_LCNAMES=y -CONFIG_FAT_LFN=y -CONFIG_FAT_MAXFNAME=32 -CONFIG_FS_NXFFS=y -CONFIG_NXFFS_MAXNAMLEN=32 -CONFIG_NXFFS_TAILTHRESHOLD=2048 -CONFIG_NXFFS_PREALLOCATED=y -CONFIG_FS_ROMFS=y -CONFIG_FS_BINFS=y - -# -# SPI-based MMC/SD driver -# -# CONFIG_MMCSD_NSLOTS -# Number of MMC/SD slots supported by the driver -# CONFIG_MMCSD_READONLY -# Provide read-only access (default is read/write) -# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card. -# Default is 20MHz, current setting 24 MHz -# -#CONFIG_MMCSD=n -# XXX need to rejig this for SDIO -#CONFIG_MMCSD_SPI=y -#CONFIG_MMCSD_NSLOTS=1 -#CONFIG_MMCSD_READONLY=n -#CONFIG_MMCSD_SPICLOCK=24000000 - -# -# Maintain legacy build behavior (revisit) -# - -CONFIG_MMCSD=y -#CONFIG_MMCSD_SPI=y -CONFIG_MMCSD_SDIO=y -CONFIG_MTD=y - -# -# SPI-based MMC/SD driver -# -#CONFIG_MMCSD_NSLOTS=1 -#CONFIG_MMCSD_READONLY=n -#CONFIG_MMCSD_SPICLOCK=12500000 - -# -# STM32 SDIO-based MMC/SD driver -# -CONFIG_SDIO_DMA=y -#CONFIG_SDIO_PRI=128 -#CONFIG_SDIO_DMAPRIO -#CONFIG_SDIO_WIDTH_D1_ONLY -CONFIG_MMCSD_MULTIBLOCK_DISABLE=y -CONFIG_MMCSD_MMCSUPPORT=n -CONFIG_MMCSD_HAVECARDDETECT=n - -# -# Block driver buffering -# -# CONFIG_FS_READAHEAD -# Enable read-ahead buffering -# CONFIG_FS_WRITEBUFFER -# Enable write buffering -# -CONFIG_FS_READAHEAD=n -CONFIG_FS_WRITEBUFFER=n - -# -# RTC Configuration -# -# CONFIG_RTC - Enables general support for a hardware RTC. Specific -# architectures may require other specific settings. -# CONFIG_RTC_DATETIME - There are two general types of RTC: (1) A simple -# battery backed counter that keeps the time when power is down, and (2) -# A full date / time RTC the provides the date and time information, often -# in BCD format. If CONFIG_RTC_DATETIME is selected, it specifies this -# second kind of RTC. In this case, the RTC is used to "seed" the normal -# NuttX timer and the NuttX system timer provides for higher resoution -# time. -# CONFIG_RTC_HIRES - If CONFIG_RTC_DATETIME not selected, then the simple, -# battery backed counter is used. There are two different implementations -# of such simple counters based on the time resolution of the counter: -# The typical RTC keeps time to resolution of 1 second, usually -# supporting a 32-bit time_t value. In this case, the RTC is used to -# "seed" the normal NuttX timer and the NuttX timer provides for higher -# resoution time. If CONFIG_RTC_HIRES is enabled in the NuttX configuration, -# then the RTC provides higher resolution time and completely replaces the -# system timer for purpose of date and time. -# CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the frequency -# of the high resolution RTC must be provided. If CONFIG_RTC_HIRES is -# not defined, CONFIG_RTC_FREQUENCY is assumed to be one. -# CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an -# alarm. A callback function will be executed when the alarm goes off -# -CONFIG_RTC=n -CONFIG_RTC_DATETIME=y -CONFIG_RTC_HIRES=n -CONFIG_RTC_FREQUENCY=n -CONFIG_RTC_ALARM=n - -# -# USB Device Configuration -# -# CONFIG_USBDEV -# Enables USB device support -# CONFIG_USBDEV_ISOCHRONOUS -# Build in extra support for isochronous endpoints -# CONFIG_USBDEV_DUALSPEED -# Hardware handles high and full speed operation (USB 2.0) -# CONFIG_USBDEV_SELFPOWERED -# Will cause USB features to indicate that the device is -# self-powered -# CONFIG_USBDEV_MAXPOWER -# Maximum power consumption in mA -# CONFIG_USBDEV_TRACE -# Enables USB tracing for debug -# CONFIG_USBDEV_TRACE_NRECORDS -# Number of trace entries to remember -# -CONFIG_USBDEV=y -CONFIG_USBDEV_ISOCHRONOUS=n -CONFIG_USBDEV_DUALSPEED=n -CONFIG_USBDEV_SELFPOWERED=y -CONFIG_USBDEV_REMOTEWAKEUP=n -CONFIG_USBDEV_MAXPOWER=500 -CONFIG_USBDEV_TRACE=n -CONFIG_USBDEV_TRACE_NRECORDS=512 - -# -# USB serial device class driver (Standard CDC ACM class) -# -# CONFIG_CDCACM -# Enable compilation of the USB serial driver -# CONFIG_CDCACM_CONSOLE -# Configures the CDC/ACM serial port as the console device. -# CONFIG_CDCACM_EP0MAXPACKET -# Endpoint 0 max packet size. Default 64 -# CONFIG_CDCACM_EPINTIN -# The logical 7-bit address of a hardware endpoint that supports -# interrupt IN operation. Default 2. -# CONFIG_CDCACM_EPINTIN_FSSIZE -# Max package size for the interrupt IN endpoint if full speed mode. -# Default 64. -# CONFIG_CDCACM_EPINTIN_HSSIZE -# Max package size for the interrupt IN endpoint if high speed mode. -# Default 64 -# CONFIG_CDCACM_EPBULKOUT -# The logical 7-bit address of a hardware endpoint that supports -# bulk OUT operation. Default 4. -# CONFIG_CDCACM_EPBULKOUT_FSSIZE -# Max package size for the bulk OUT endpoint if full speed mode. -# Default 64. -# CONFIG_CDCACM_EPBULKOUT_HSSIZE -# Max package size for the bulk OUT endpoint if high speed mode. -# Default 512. -# CONFIG_CDCACM_EPBULKIN -# The logical 7-bit address of a hardware endpoint that supports -# bulk IN operation. Default 3. -# CONFIG_CDCACM_EPBULKIN_FSSIZE -# Max package size for the bulk IN endpoint if full speed mode. -# Default 64. -# CONFIG_CDCACM_EPBULKIN_HSSIZE -# Max package size for the bulk IN endpoint if high speed mode. -# Default 512. -# CONFIG_CDCACM_NWRREQS and CONFIG_CDCACM_NRDREQS -# The number of write/read requests that can be in flight. -# Default 256. -# CONFIG_CDCACM_VENDORID and CONFIG_CDCACM_VENDORSTR -# The vendor ID code/string. Default 0x0525 and "NuttX" -# 0x0525 is the Netchip vendor and should not be used in any -# products. This default VID was selected for compatibility with -# the Linux CDC ACM default VID. -# CONFIG_CDCACM_PRODUCTID and CONFIG_CDCACM_PRODUCTSTR -# The product ID code/string. Default 0xa4a7 and "CDC/ACM Serial" -# 0xa4a7 was selected for compatibility with the Linux CDC ACM -# default PID. -# CONFIG_CDCACM_RXBUFSIZE and CONFIG_CDCACM_TXBUFSIZE -# Size of the serial receive/transmit buffers. Default 256. -# -CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=n -#CONFIG_CDCACM_EP0MAXPACKET -CONFIG_CDCACM_EPINTIN=1 -#CONFIG_CDCACM_EPINTIN_FSSIZE -#CONFIG_CDCACM_EPINTIN_HSSIZE -CONFIG_CDCACM_EPBULKOUT=3 -#CONFIG_CDCACM_EPBULKOUT_FSSIZE -#CONFIG_CDCACM_EPBULKOUT_HSSIZE -CONFIG_CDCACM_EPBULKIN=2 -#CONFIG_CDCACM_EPBULKIN_FSSIZE -#CONFIG_CDCACM_EPBULKIN_HSSIZE -#CONFIG_CDCACM_NWRREQS -#CONFIG_CDCACM_NRDREQS -CONFIG_CDCACM_VENDORID=0x26AC -CONFIG_CDCACM_VENDORSTR="3D Robotics" -CONFIG_CDCACM_PRODUCTID=0x0010 -CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6" -#CONFIG_CDCACM_RXBUFSIZE -#CONFIG_CDCACM_TXBUFSIZE - - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_BUILTIN_APPS - Support external registered, -# "named" applications that can be executed from the NSH -# command line (see apps/README.txt for more information). -# 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_MAX_ARGUMENTS - Maximum number of arguments for command line -# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# CONFIG_NSH_ARCHINIT - Platform provides architecture -# specific initialization (nsh_archinitialize()). -# -# If CONFIG_NSH_TELNET is selected: -# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size -# CONFIG_NSH_DHCPC - Obtain address using DHCP -# CONFIG_NSH_IPADDR - Provides static IP address -# CONFIG_NSH_DRIPADDR - Provides static router IP address -# CONFIG_NSH_NETMASK - Provides static network mask -# CONFIG_NSH_NOMAC - Use a bogus MAC address -# -# If CONFIG_NSH_ROMFSETC is selected: -# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint -# CONFIG_NSH_INITSCRIPT - Relative path to init script -# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor -# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size -# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor -# CONFIG_NSH_FATSECTSIZE - FAT FS sector size -# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors -# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint -# -CONFIG_BUILTIN=y -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=y -CONFIG_NSH_LINELEN=128 -CONFIG_NSH_MAX_ARGUMENTS=12 -CONFIG_NSH_NESTDEPTH=8 -CONFIG_NSH_DISABLESCRIPT=n -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=y -CONFIG_NSH_ARCHROMFS=y -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_USBCONSOLE=n -#CONFIG_NSH_USBCONDEV="/dev/ttyACM0" -CONFIG_NSH_TELNET=n -CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_IOBUFFER_SIZE=512 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=y -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 -CONFIG_NSH_ROMFSSECTSIZE=128 # Default 64, increased to allow for more than 64 folders on the sdcard -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT=/tmp - -# -# Architecture-specific NSH options -# -#CONFIG_NSH_MMCSDSPIPORTNO=3 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 - - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# (should also be =n for the STM3240G-EVAL which always runs from flash) -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2) there after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_STACK_POINTER= -# Idle thread needs 4096 bytes -# default 1 KB is not enough -# 4096 bytes -CONFIG_IDLETHREAD_STACKSIZE=6000 -# USERMAIN stack size probably needs to be around 4096 bytes -CONFIG_USERMAIN_STACKSIZE=4096 -CONFIG_PTHREAD_STACK_MIN=512 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= - -# enable bindir -CONFIG_APPS_BINDIR=y diff --git a/nuttx/configs/px4fmuv2/nsh/setenv.sh b/nuttx/configs/px4fmuv2/nsh/setenv.sh deleted file mode 100755 index 265520997..000000000 --- a/nuttx/configs/px4fmuv2/nsh/setenv.sh +++ /dev/null @@ -1,67 +0,0 @@ -#!/bin/bash -# configs/stm3240g-eval/nsh/setenv.sh -# -# Copyright (C) 2011 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. -# - -if [ "$_" = "$0" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -WD=`pwd` -if [ ! -x "setenv.sh" ]; then - echo "This script must be executed from the top-level NuttX build directory" - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then - export PATH_ORIG="${PATH}" -fi - -# This the Cygwin path to the location where I installed the RIDE -# toolchain under windows. You will also have to edit this if you install -# the RIDE toolchain in any other location -#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" - -# This the Cygwin path to the location where I installed the CodeSourcery -# toolchain under windows. You will also have to edit this if you install -# the CodeSourcery toolchain in any other location -export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" - -# This the Cygwin path to the location where I build the buildroot -# toolchain. -#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" - -# Add the path to the toolchain to the PATH varialble -export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/px4fmuv2/src/Makefile b/nuttx/configs/px4fmuv2/src/Makefile deleted file mode 100644 index d4276f7fc..000000000 --- a/nuttx/configs/px4fmuv2/src/Makefile +++ /dev/null @@ -1,84 +0,0 @@ -############################################################################ -# configs/px4fmu/src/Makefile -# -# Copyright (C) 2011 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)/Make.defs - -CFLAGS += -I$(TOPDIR)/sched - -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) - -CSRCS = empty.c -COBJS = $(CSRCS:.c=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) - -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -ifeq ($(WINTOOL),y) - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" -else - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m -endif - -all: libboard$(LIBEXT) - -$(AOBJS): %$(OBJEXT): %.S - $(call ASSEMBLE, $<, $@) - -$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c - $(call COMPILE, $<, $@) - -libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) - -.depend: Makefile $(SRCS) - $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - $(Q) touch $@ - -depend: .depend - -clean: - $(call DELFILE, libboard$(LIBEXT)) - $(call CLEAN) - -distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - --include Make.dep - diff --git a/nuttx/configs/px4fmuv2/src/empty.c b/nuttx/configs/px4fmuv2/src/empty.c deleted file mode 100644 index ace900866..000000000 --- a/nuttx/configs/px4fmuv2/src/empty.c +++ /dev/null @@ -1,4 +0,0 @@ -/* - * There are no source files here, but libboard.a can't be empty, so - * we have this empty source file to keep it company. - */ diff --git a/nuttx/configs/px4iov2/README.txt b/nuttx/configs/px4iov2/README.txt deleted file mode 100755 index 9b1615f42..000000000 --- a/nuttx/configs/px4iov2/README.txt +++ /dev/null @@ -1,806 +0,0 @@ -README -====== - -This README discusses issues unique to NuttX configurations for the -STMicro STM3210E-EVAL development board. - -Contents -======== - - - Development Environment - - GNU Toolchain Options - - IDEs - - NuttX buildroot Toolchain - - DFU and JTAG - - OpenOCD - - LEDs - - Temperature Sensor - - RTC - - STM3210E-EVAL-specific Configuration Options - - Configurations - -Development Environment -======================= - - Either Linux or Cygwin on Windows can be used for the development environment. - The source has been built only using the GNU toolchain (see below). Other - toolchains will likely cause problems. Testing was performed using the Cygwin - environment because the Raisonance R-Link emulatator and some RIDE7 development tools - were used and those tools works only under Windows. - -GNU Toolchain Options -===================== - - The NuttX make system has been modified to support the following different - toolchain options. - - 1. The CodeSourcery GNU toolchain, - 2. The devkitARM GNU toolchain, - 3. Raisonance GNU toolchain, or - 4. The NuttX buildroot Toolchain (see below). - - All testing has been conducted using the NuttX buildroot toolchain. However, - the make system is setup to default to use the devkitARM toolchain. To use - the CodeSourcery, devkitARM or Raisonance GNU toolchain, you simply need to - add one of the following configuration options to your .config (or defconfig) - file: - - CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux - CONFIG_STM32_DEVKITARM=y : devkitARM under Windows - CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows - CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) - - If you are not using CONFIG_STM32_BUILDROOT, then you may also have to modify - the PATH in the setenv.h file if your make cannot find the tools. - - NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are - Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot - toolchains are Cygwin and/or Linux native toolchains. There are several limitations - to using a Windows based toolchain in a Cygwin environment. The three biggest are: - - 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are - performed automatically in the Cygwin makefiles using the 'cygpath' utility - but you might easily find some new path problems. If so, check out 'cygpath -w' - - 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links - are used in Nuttx (e.g., include/arch). The make system works around these - problems for the Windows tools by copying directories instead of linking them. - But this can also cause some confusion for you: For example, you may edit - a file in a "linked" directory and find that your changes had no effect. - That is because you are building the copy of the file in the "fake" symbolic - directory. If you use a Windows toolchain, you should get in the habit of - making like this: - - make clean_context all - - An alias in your .bashrc file might make that less painful. - - 3. Dependencies are not made when using Windows versions of the GCC. This is - because the dependencies are generated using Windows pathes which do not - work with the Cygwin make. - - Support has been added for making dependencies with the windows-native toolchains. - That support can be enabled by modifying your Make.defs file as follows: - - - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)" - - If you have problems with the dependency build (for example, if you are not - building on C:), then you may need to modify tools/mkdeps.sh - - NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization - level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with - -Os. - - NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that - the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM - path or will get the wrong version of make. - -IDEs -==== - - NuttX is built using command-line make. It can be used with an IDE, but some - effort will be required to create the project (There is a simple RIDE project - in the RIDE subdirectory). - - Makefile Build - -------------- - Under Eclipse, it is pretty easy to set up an "empty makefile project" and - simply use the NuttX makefile to build the system. That is almost for free - under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty - makefile project in order to work with Windows (Google for "Eclipse Cygwin" - - there is a lot of help on the internet). - - Native Build - ------------ - Here are a few tips before you start that effort: - - 1) Select the toolchain that you will be using in your .config file - 2) Start the NuttX build at least one time from the Cygwin command line - before trying to create your project. This is necessary to create - certain auto-generated files and directories that will be needed. - 3) Set up include pathes: You will need include/, arch/arm/src/stm32, - arch/arm/src/common, arch/arm/src/armv7-m, and sched/. - 4) All assembly files need to have the definition option -D __ASSEMBLY__ - on the command line. - - Startup files will probably cause you some headaches. The NuttX startup file - is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX - one time from the Cygwin command line in order to obtain the pre-built - startup object needed by RIDE. - -NuttX buildroot Toolchain -========================= - - A GNU GCC-based toolchain is assumed. The files */setenv.sh should - be modified to point to the correct path to the Cortex-M3 GCC toolchain (if - different from the default in your PATH variable). - - If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX - SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573). - This GNU toolchain builds and executes in the Linux or Cygwin environment. - - 1. You must have already configured Nuttx in /nuttx. - - cd tools - ./configure.sh stm3210e-eval/ - - 2. Download the latest buildroot package into - - 3. unpack the buildroot tarball. The resulting directory may - have versioning information on it like buildroot-x.y.z. If so, - rename /buildroot-x.y.z to /buildroot. - - 4. cd /buildroot - - 5. cp configs/cortexm3-defconfig-4.3.3 .config - - 6. make oldconfig - - 7. make - - 8. Edit setenv.h, if necessary, so that the PATH variable includes - the path to the newly built binaries. - - See the file configs/README.txt in the buildroot source tree. That has more - detailed PLUS some special instructions that you will need to follow if you are - building a Cortex-M3 toolchain for Cygwin under Windows. - -DFU and JTAG -============ - - Enbling Support for the DFU Bootloader - -------------------------------------- - The linker files in these projects can be configured to indicate that you - will be loading code using STMicro built-in USB Device Firmware Upgrade (DFU) - loader or via some JTAG emulator. You can specify the DFU bootloader by - adding the following line: - - CONFIG_STM32_DFU=y - - to your .config file. Most of the configurations in this directory are set - up to use the DFU loader. - - If CONFIG_STM32_DFU is defined, the code will not be positioned at the beginning - of FLASH (0x08000000) but will be offset to 0x08003000. This offset is needed - to make space for the DFU loader and 0x08003000 is where the DFU loader expects - to find new applications at boot time. If you need to change that origin for some - other bootloader, you will need to edit the file(s) ld.script.dfu for each - configuration. - - The DFU SE PC-based software is available from the STMicro website, - http://www.st.com. General usage instructions: - - 1. Convert the NuttX Intel Hex file (nuttx.ihx) into a special DFU - file (nuttx.dfu)... see below for details. - 2. Connect the STM3210E-EVAL board to your computer using a USB - cable. - 3. Start the DFU loader on the STM3210E-EVAL board. You do this by - resetting the board while holding the "Key" button. Windows should - recognize that the DFU loader has been installed. - 3. Run the DFU SE program to load nuttx.dfu into FLASH. - - What if the DFU loader is not in FLASH? The loader code is available - inside of the Demo dirctory of the USBLib ZIP file that can be downloaded - from the STMicro Website. You can build it using RIDE (or other toolchains); - you will need a JTAG emulator to burn it into FLASH the first time. - - In order to use STMicro's built-in DFU loader, you will have to get - the NuttX binary into a special format with a .dfu extension. The - DFU SE PC_based software installation includes a file "DFU File Manager" - conversion program that a file in Intel Hex format to the special DFU - format. When you successfully build NuttX, you will find a file called - nutt.ihx in the top-level directory. That is the file that you should - provide to the DFU File Manager. You will need to rename it to nuttx.hex - in order to find it with the DFU File Manager. You will end up with - a file called nuttx.dfu that you can use with the STMicro DFU SE program. - - Enabling JTAG - ------------- - If you are not using the DFU, then you will probably also need to enable - JTAG support. By default, all JTAG support is disabled but there NuttX - configuration options to enable JTAG in various different ways. - - These configurations effect the setting of the SWJ_CFG[2:0] bits in the AFIO - MAPR register. These bits are used to configure the SWJ and trace alternate function I/Os. The SWJ (SerialWire JTAG) supports JTAG or SWD access to the - Cortex debug port. The default state in this port is for all JTAG support - to be disable. - - CONFIG_STM32_JTAG_FULL_ENABLE - sets SWJ_CFG[2:0] to 000 which enables full - SWJ (JTAG-DP + SW-DP) - - CONFIG_STM32_JTAG_NOJNTRST_ENABLE - sets SWJ_CFG[2:0] to 001 which enable - full SWJ (JTAG-DP + SW-DP) but without JNTRST. - - CONFIG_STM32_JTAG_SW_ENABLE - sets SWJ_CFG[2:0] to 010 which would set JTAG-DP - disabled and SW-DP enabled - - The default setting (none of the above defined) is SWJ_CFG[2:0] set to 100 - which disable JTAG-DP and SW-DP. - -OpenOCD -======= - -I have also used OpenOCD with the STM3210E-EVAL. In this case, I used -the Olimex USB ARM OCD. See the script in configs/stm3210e-eval/tools/oocd.sh -for more information. Using the script: - -1) Start the OpenOCD GDB server - - cd - configs/stm3210e-eval/tools/oocd.sh $PWD - -2) Load Nuttx - - cd - arm-none-eabi-gdb nuttx - gdb> target remote localhost:3333 - gdb> mon reset - gdb> mon halt - gdb> load nuttx - -3) Running NuttX - - gdb> mon reset - gdb> c - -LEDs -==== - -The STM3210E-EVAL board has four LEDs labeled LD1, LD2, LD3 and LD4 on the -board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is -defined. In that case, the usage by the board port is defined in -include/board.h and src/up_leds.c. The LEDs are used to encode OS-related -events as follows: - - SYMBOL Meaning LED1* LED2 LED3 LED4 - ---------------- ----------------------- ----- ----- ----- ----- - LED_STARTED NuttX has been started ON OFF OFF OFF - LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF - LED_IRQSENABLED Interrupts enabled ON ON OFF OFF - LED_STACKCREATED Idle stack created OFF OFF ON OFF - LED_INIRQ In an interrupt** ON N/C N/C OFF - LED_SIGNAL In a signal handler*** N/C ON N/C OFF - LED_ASSERTION An assertion failed ON ON N/C OFF - LED_PANIC The system has crashed N/C N/C N/C ON - LED_IDLE STM32 is is sleep mode (Optional, not used) - - * If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot - and these LEDs will give you some indication of where the failure was - ** The normal state is LED3 ON and LED1 faintly glowing. This faint glow - is because of timer interupts that result in the LED being illuminated - on a small proportion of the time. -*** LED2 may also flicker normally if signals are processed. - -Temperature Sensor -================== - -Support for the on-board LM-75 temperature sensor is available. This supported -has been verified, but has not been included in any of the available the -configurations. To set up the temperature sensor, add the following to the -NuttX configuration file - - CONFIG_I2C=y - CONFIG_I2C_LM75=y - -Then you can implement logic like the following to use the temperature sensor: - - #include - #include - - ret = stm32_lm75initialize("/dev/temp"); /* Register the temperature sensor */ - fd = open("/dev/temp", O_RDONLY); /* Open the temperature sensor device */ - ret = ioctl(fd, SNIOC_FAHRENHEIT, 0); /* Select Fahrenheit */ - bytesread = read(fd, buffer, 8*sizeof(b16_t)); /* Read temperature samples */ - -More complex temperature sensor operations are also available. See the IOCTAL -commands enumerated in include/nuttx/sensors/lm75.h. Also read the descriptions -of the stm32_lm75initialize() and stm32_lm75attach() interfaces in the -arch/board/board.h file (sames as configs/stm3210e-eval/include/board.h). - -RTC -=== - - The STM32 RTC may configured using the following settings. - - CONFIG_RTC - Enables general support for a hardware RTC. Specific - architectures may require other specific settings. - CONFIG_RTC_HIRES - The typical RTC keeps time to resolution of 1 - second, usually supporting a 32-bit time_t value. In this case, - the RTC is used to "seed" the normal NuttX timer and the - NuttX timer provides for higher resoution time. If CONFIG_RTC_HIRES - is enabled in the NuttX configuration, then the RTC provides higher - resolution time and completely replaces the system timer for purpose of - date and time. - CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the - frequency of the high resolution RTC must be provided. If CONFIG_RTC_HIRES - is not defined, CONFIG_RTC_FREQUENCY is assumed to be one. - CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an alarm. - A callback function will be executed when the alarm goes off - - In hi-res mode, the STM32 RTC operates only at 16384Hz. Overflow interrupts - are handled when the 32-bit RTC counter overflows every 3 days and 43 minutes. - A BKP register is incremented on each overflow interrupt creating, effectively, - a 48-bit RTC counter. - - In the lo-res mode, the RTC operates at 1Hz. Overflow interrupts are not handled - (because the next overflow is not expected until the year 2106. - - WARNING: Overflow interrupts are lost whenever the STM32 is powered down. The - overflow interrupt may be lost even if the STM32 is powered down only momentarily. - Therefore hi-res solution is only useful in systems where the power is always on. - -STM3210E-EVAL-specific Configuration Options -============================================ - - CONFIG_ARCH - Identifies the arch/ subdirectory. This should - be set to: - - CONFIG_ARCH=arm - - CONFIG_ARCH_family - For use in C code: - - CONFIG_ARCH_ARM=y - - CONFIG_ARCH_architecture - For use in C code: - - CONFIG_ARCH_CORTEXM3=y - - CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory - - CONFIG_ARCH_CHIP=stm32 - - CONFIG_ARCH_CHIP_name - For use in C code to identify the exact - chip: - - CONFIG_ARCH_CHIP_STM32F103ZET6 - - CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock - configuration features. - - CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n - - CONFIG_ARCH_BOARD - Identifies the configs subdirectory and - hence, the board that supports the particular chip or SoC. - - CONFIG_ARCH_BOARD=stm3210e_eval (for the STM3210E-EVAL development board) - - CONFIG_ARCH_BOARD_name - For use in C code - - CONFIG_ARCH_BOARD_STM3210E_EVAL=y - - CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation - of delay loops - - CONFIG_ENDIAN_BIG - define if big endian (default is little - endian) - - CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case): - - CONFIG_DRAM_SIZE=0x00010000 (64Kb) - - CONFIG_DRAM_START - The start address of installed DRAM - - CONFIG_DRAM_START=0x20000000 - - CONFIG_DRAM_END - Last address+1 of installed RAM - - CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) - - CONFIG_ARCH_IRQPRIO - The STM32F103Z supports interrupt prioritization - - CONFIG_ARCH_IRQPRIO=y - - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that - have LEDs - - CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt - stack. If defined, this symbol is the size of the interrupt - stack in bytes. If not defined, the user task stacks will be - used during interrupt handling. - - CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions - - CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. - - CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that - cause a 100 second delay during boot-up. This 100 second delay - serves no purpose other than it allows you to calibratre - CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure - the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until - the delay actually is 100 seconds. - - Individual subsystems can be enabled: - AHB - --- - CONFIG_STM32_DMA1 - CONFIG_STM32_DMA2 - CONFIG_STM32_CRC - CONFIG_STM32_FSMC - CONFIG_STM32_SDIO - - APB1 - ---- - CONFIG_STM32_TIM2 - CONFIG_STM32_TIM3 - CONFIG_STM32_TIM4 - CONFIG_STM32_TIM5 - CONFIG_STM32_TIM6 - CONFIG_STM32_TIM7 - CONFIG_STM32_WWDG - CONFIG_STM32_SPI2 - CONFIG_STM32_SPI4 - CONFIG_STM32_USART2 - CONFIG_STM32_USART3 - CONFIG_STM32_UART4 - CONFIG_STM32_UART5 - CONFIG_STM32_I2C1 - CONFIG_STM32_I2C2 - CONFIG_STM32_USB - CONFIG_STM32_CAN - CONFIG_STM32_BKP - CONFIG_STM32_PWR - CONFIG_STM32_DAC1 - CONFIG_STM32_DAC2 - CONFIG_STM32_USB - - APB2 - ---- - CONFIG_STM32_ADC1 - CONFIG_STM32_ADC2 - CONFIG_STM32_TIM1 - CONFIG_STM32_SPI1 - CONFIG_STM32_TIM8 - CONFIG_STM32_USART1 - CONFIG_STM32_ADC3 - - Timer and I2C devices may need to the following to force power to be applied - unconditionally at power up. (Otherwise, the device is powered when it is - initialized). - - CONFIG_STM32_FORCEPOWER - - Timer devices may be used for different purposes. One special purpose is - to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn - is defined (as above) then the following may also be defined to indicate that - the timer is intended to be used for pulsed output modulation, ADC conversion, - or DAC conversion. Note that ADC/DAC require two definition: Not only do you have - to assign the timer (n) for used by the ADC or DAC, but then you also have to - configure which ADC or DAC (m) it is assigned to. - - CONFIG_STM32_TIMn_PWM Reserve timer n for use by PWM, n=1,..,8 - CONFIG_STM32_TIMn_ADC Reserve timer n for use by ADC, n=1,..,8 - CONFIG_STM32_TIMn_ADCm Reserve timer n to trigger ADCm, n=1,..,8, m=1,..,3 - CONFIG_STM32_TIMn_DAC Reserve timer n for use by DAC, n=1,..,8 - CONFIG_STM32_TIMn_DACm Reserve timer n to trigger DACm, n=1,..,8, m=1,..,2 - - For each timer that is enabled for PWM usage, we need the following additional - configuration settings: - - CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4} - - NOTE: The STM32 timers are each capable of generating different signals on - each of the four channels with different duty cycles. That capability is - not supported by this driver: Only one output channel per timer. - - Alternate pin mappings (should not be used with the STM3210E-EVAL board): - - CONFIG_STM32_TIM1_FULL_REMAP - CONFIG_STM32_TIM1_PARTIAL_REMAP - CONFIG_STM32_TIM2_FULL_REMAP - CONFIG_STM32_TIM2_PARTIAL_REMAP_1 - CONFIG_STM32_TIM2_PARTIAL_REMAP_2 - CONFIG_STM32_TIM3_FULL_REMAP - CONFIG_STM32_TIM3_PARTIAL_REMAP - CONFIG_STM32_TIM4_REMAP - CONFIG_STM32_USART1_REMAP - CONFIG_STM32_USART2_REMAP - CONFIG_STM32_USART3_FULL_REMAP - CONFIG_STM32_USART3_PARTIAL_REMAP - CONFIG_STM32_SPI1_REMAP - CONFIG_STM32_SPI3_REMAP - CONFIG_STM32_I2C1_REMAP - CONFIG_STM32_CAN1_FULL_REMAP - CONFIG_STM32_CAN1_PARTIAL_REMAP - CONFIG_STM32_CAN2_REMAP - - JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): - CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) - CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) - but without JNTRST. - CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled - - STM32F103Z specific device driver settings - - CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART - m (m=4,5) for the console and ttys0 (default is the USART1). - CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received. - This specific the size of the receive buffer - CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before - being sent. This specific the size of the transmit buffer - CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be - CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8. - CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity - CONFIG_U[S]ARTn_2STOP - Two stop bits - - CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI - support. Non-interrupt-driven, poll-waiting is recommended if the - interrupt rate would be to high in the interrupt driven case. - CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance. - Cannot be used with CONFIG_STM32_SPI_INTERRUPT. - - CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO - and CONFIG_STM32_DMA2. - CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128 - CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority. - Default: Medium - CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default: - 4-bit transfer mode. - - STM3210E-EVAL CAN Configuration - - 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. - Default: 4 - CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback - 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_REGDEBUG - If CONFIG_DEBUG is set, this will generate an - dump of all CAN registers. - - STM3210E-EVAL LCD Hardware Configuration - - CONFIG_LCD_LANDSCAPE - Define for 320x240 display "landscape" - support. Default is this 320x240 "landscape" orientation - (this setting is informative only... not used). - CONFIG_LCD_PORTRAIT - Define for 240x320 display "portrait" - orientation support. In this orientation, the STM3210E-EVAL's - LCD ribbon cable is at the bottom of the display. Default is - 320x240 "landscape" orientation. - CONFIG_LCD_RPORTRAIT - Define for 240x320 display "reverse - portrait" orientation support. In this orientation, the - STM3210E-EVAL's LCD ribbon cable is at the top of the display. - Default is 320x240 "landscape" orientation. - CONFIG_LCD_BACKLIGHT - Define to support a backlight. - CONFIG_LCD_PWM - If CONFIG_STM32_TIM1 is also defined, then an - adjustable backlight will be provided using timer 1 to generate - various pulse widthes. The granularity of the settings is - determined by CONFIG_LCD_MAXPOWER. If CONFIG_LCD_PWM (or - CONFIG_STM32_TIM1) is not defined, then a simple on/off backlight - is provided. - CONFIG_LCD_RDSHIFT - When reading 16-bit gram data, there appears - to be a shift in the returned data. This value fixes the offset. - Default 5. - - The LCD driver dynamically selects the LCD based on the reported LCD - ID value. However, code size can be reduced by suppressing support for - individual LCDs using: - - CONFIG_STM32_AM240320_DISABLE - CONFIG_STM32_SPFD5408B_DISABLE - CONFIG_STM32_R61580_DISABLE - -Configurations -============== - -Each STM3210E-EVAL configuration is maintained in a sudirectory and -can be selected as follow: - - cd tools - ./configure.sh stm3210e-eval/ - cd - - . ./setenv.sh - -Where is one of the following: - - buttons: - -------- - - Uses apps/examples/buttons to exercise STM3210E-EVAL buttons and - button interrupts. - - CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows - - composite - --------- - - This configuration exercises a composite USB interface consisting - of a CDC/ACM device and a USB mass storage device. This configuration - uses apps/examples/composite. - - nsh and nsh2: - ------------ - Configure the NuttShell (nsh) located at examples/nsh. - - Differences between the two NSH configurations: - - =========== ======================= ================================ - nsh nsh2 - =========== ======================= ================================ - Toolchain: NuttX buildroot for Codesourcery for Windows (1) - Linux or Cygwin (1,2) - ----------- ----------------------- -------------------------------- - Loader: DfuSe DfuSe - ----------- ----------------------- -------------------------------- - Serial Debug output: USART1 Debug output: USART1 - Console: NSH output: USART1 NSH output: USART1 (3) - ----------- ----------------------- -------------------------------- - microSD Yes Yes - Support - ----------- ----------------------- -------------------------------- - FAT FS CONFIG_FAT_LCNAME=y CONFIG_FAT_LCNAME=y - Config CONFIG_FAT_LFN=n CONFIG_FAT_LFN=y (4) - ----------- ----------------------- -------------------------------- - Support for No Yes - Built-in - Apps - ----------- ----------------------- -------------------------------- - Built-in None apps/examples/nx - Apps apps/examples/nxhello - apps/examples/usbstorage (5) - =========== ======================= ================================ - - (1) You will probably need to modify nsh/setenv.sh or nsh2/setenv.sh - to set up the correct PATH variable for whichever toolchain you - may use. - (2) Since DfuSe is assumed, this configuration may only work under - Cygwin without modification. - (3) When any other device other than /dev/console is used for a user - interface, (1) linefeeds (\n) will not be expanded to carriage return - / linefeeds \r\n). You will need to configure your terminal program - to account for this. And (2) input is not automatically echoed so - you will have to turn local echo on. - (4) Microsoft holds several patents related to the design of - long file names in the FAT file system. Please refer to the - details in the top-level COPYING file. Please do not use FAT - long file name unless you are familiar with these patent issues. - (5) When built as an NSH add-on command (CONFIG_EXAMPLES_USBMSC_BUILTIN=y), - Caution should be used to assure that the SD drive is not in use when - the USB storage device is configured. Specifically, the SD driver - should be unmounted like: - - nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Card is mounted in NSH - ... - nsh> umount /mnd/sdcard # Unmount before connecting USB!!! - nsh> msconn # Connect the USB storage device - ... - nsh> msdis # Disconnect USB storate device - nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Restore the mount - - Failure to do this could result in corruption of the SD card format. - - nx: - --- - An example using the NuttX graphics system (NX). This example - focuses on general window controls, movement, mouse and keyboard - input. - - CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait - - nxlines: - ------ - Another example using the NuttX graphics system (NX). This - example focuses on placing lines on the background in various - orientations. - - CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait - - nxtext: - ------ - Another example using the NuttX graphics system (NX). This - example focuses on placing text on the background while pop-up - windows occur. Text should continue to update normally with - or without the popup windows present. - - CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin - CONFIG_LCD_RPORTRAIT=y : 240x320 reverse portrait - - NOTE: When I tried building this example with the CodeSourcery - tools, I got a hardfault inside of its libgcc. I haven't - retested since then, but beware if you choose to change the - toolchain. - - ostest: - ------ - This configuration directory, performs a simple OS test using - examples/ostest. By default, this project assumes that you are - using the DFU bootloader. - - CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin - - RIDE - ---- - This configuration builds a trivial bring-up binary. It is - useful only because it words with the RIDE7 IDE and R-Link debugger. - - CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows - - usbserial: - --------- - This configuration directory exercises the USB serial class - driver at examples/usbserial. See examples/README.txt for - more information. - - CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin - - USB debug output can be enabled as by changing the following - settings in the configuration file: - - -CONFIG_DEBUG=n - -CONFIG_DEBUG_VERBOSE=n - -CONFIG_DEBUG_USB=n - +CONFIG_DEBUG=y - +CONFIG_DEBUG_VERBOSE=y - +CONFIG_DEBUG_USB=y - - -CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n - -CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n - -CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n - -CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n - -CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n - +CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=y - +CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=y - +CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=y - +CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=y - +CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=y - - By default, the usbserial example uses the Prolific PL2303 - serial/USB converter emulation. The example can be modified - to use the CDC/ACM serial class by making the following changes - to the configuration file: - - -CONFIG_PL2303=y - +CONFIG_PL2303=n - - -CONFIG_CDCACM=n - +CONFIG_CDCACM=y - - The example can also be converted to use the alternative - USB serial example at apps/examples/usbterm by changing the - following: - - -CONFIGURED_APPS += examples/usbserial - +CONFIGURED_APPS += examples/usbterm - - In either the original appconfig file (before configuring) - or in the final apps/.config file (after configuring). - - usbstorage: - ---------- - This configuration directory exercises the USB mass storage - class driver at examples/usbstorage. See examples/README.txt for - more information. - - CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin - diff --git a/nuttx/configs/px4iov2/common/Make.defs b/nuttx/configs/px4iov2/common/Make.defs deleted file mode 100644 index 7f782b5b2..000000000 --- a/nuttx/configs/px4iov2/common/Make.defs +++ /dev/null @@ -1,175 +0,0 @@ -############################################################################ -# configs/px4fmu/common/Make.defs -# -# Copyright (C) 2011 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. -# -############################################################################ - -# -# Generic Make.defs for the PX4FMU -# Do not specify/use this file directly - it is included by config-specific -# Make.defs in the per-config directories. -# - -include ${TOPDIR}/tools/Config.mk - -# -# We only support building with the ARM bare-metal toolchain from -# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. -# -CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI - -include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs - -CC = $(CROSSDEV)gcc -CXX = $(CROSSDEV)g++ -CPP = $(CROSSDEV)gcc -E -LD = $(CROSSDEV)ld -AR = $(CROSSDEV)ar rcs -NM = $(CROSSDEV)nm -OBJCOPY = $(CROSSDEV)objcopy -OBJDUMP = $(CROSSDEV)objdump - -MAXOPTIMIZATION = -O3 -ARCHCPUFLAGS = -mcpu=cortex-m3 \ - -mthumb \ - -march=armv7-m - -# enable precise stack overflow tracking -#INSTRUMENTATIONDEFINES = -finstrument-functions \ -# -ffixed-r10 - -# use our linker script -LDSCRIPT = ld.script - -ifeq ($(WINTOOL),y) - # Windows-native toolchains - DIRLINK = $(TOPDIR)/tools/copydir.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" - ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" - ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}" -else - ifeq ($(PX4_WINTOOL),y) - # Windows-native toolchains (MSYS) - DIRLINK = $(TOPDIR)/tools/copydir.sh - DIRUNLINK = $(TOPDIR)/tools/unlink.sh - MKDEP = $(TOPDIR)/tools/mknulldeps.sh - ARCHINCLUDES = -I. -isystem $(TOPDIR)/include - ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) - else - # Linux/Cygwin-native toolchain - MKDEP = $(TOPDIR)/tools/mkdeps.sh - ARCHINCLUDES = -I. -isystem $(TOPDIR)/include - ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx - ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) - endif -endif - -# tool versions -ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} -ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} - -# optimisation flags -ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -fno-strict-aliasing \ - -fno-strength-reduce \ - -fomit-frame-pointer \ - -funsafe-math-optimizations \ - -fno-builtin-printf \ - -ffunction-sections \ - -fdata-sections - -ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") -ARCHOPTIMIZATION += -g -endif - -ARCHCFLAGS = -std=gnu99 -ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -ARCHWARNINGS = -Wall \ - -Wextra \ - -Wdouble-promotion \ - -Wshadow \ - -Wfloat-equal \ - -Wframe-larger-than=1024 \ - -Wpointer-arith \ - -Wlogical-op \ - -Wmissing-declarations \ - -Wpacked \ - -Wno-unused-parameter -# -Wcast-qual - generates spurious noreturn attribute warnings, try again later -# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code -# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives - -ARCHCWARNINGS = $(ARCHWARNINGS) \ - -Wbad-function-cast \ - -Wstrict-prototypes \ - -Wold-style-declaration \ - -Wmissing-parameter-type \ - -Wmissing-prototypes \ - -Wnested-externs \ - -Wunsuffixed-float-constants -ARCHWARNINGSXX = $(ARCHWARNINGS) -ARCHDEFINES = -ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 - -# this seems to be the only way to add linker flags -EXTRA_LIBS += --warn-common \ - --gc-sections - -CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common -CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) -CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) -CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ - -NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections -LDNXFLATFLAGS = -e main -s 2048 - -OBJEXT = .o -LIBEXT = .a -EXEEXT = - -# produce partially-linked $1 from files in $2 -define PRELINK - @echo "PRELINK: $1" - $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 -endef - -HOSTCC = gcc -HOSTINCLUDES = -I. -HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe -HOSTLDFLAGS = - diff --git a/nuttx/configs/px4iov2/common/ld.script b/nuttx/configs/px4iov2/common/ld.script deleted file mode 100755 index 69c2f9cb2..000000000 --- a/nuttx/configs/px4iov2/common/ld.script +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * configs/stm3210e-eval/nsh/ld.script - * - * Copyright (C) 2009, 2011 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. - * - ****************************************************************************/ - -/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and - * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, - * FLASH memory is aliased to address 0x0000:0000 where the code expects to - * begin execution by jumping to the entry point in the 0x0800:0000 address - * range. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K -} - -OUTPUT_ARCH(arm) -ENTRY(__start) /* treat __start as the anchor for dead code stripping */ -EXTERN(_vectors) /* force the vectors to be included in the output */ - -/* - * Ensure that abort() is present in the final object. The exception handling - * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). - */ -EXTERN(abort) - -SECTIONS -{ - .text : { - _stext = ABSOLUTE(.); - *(.vectors) - *(.text .text.*) - *(.fixup) - *(.gnu.warning) - *(.rodata .rodata.*) - *(.gnu.linkonce.t.*) - *(.glue_7) - *(.glue_7t) - *(.got) - *(.gcc_except_table) - *(.gnu.linkonce.r.*) - _etext = ABSOLUTE(.); - } > flash - - /* - * Init functions (static constructors and the like) - */ - .init_section : { - _sinit = ABSOLUTE(.); - KEEP(*(.init_array .init_array.*)) - _einit = ABSOLUTE(.); - } > flash - - .ARM.extab : { - *(.ARM.extab*) - } > flash - - __exidx_start = ABSOLUTE(.); - .ARM.exidx : { - *(.ARM.exidx*) - } > flash - __exidx_end = ABSOLUTE(.); - - _eronly = ABSOLUTE(.); - - /* The STM32F100CB has 8Kb of SRAM beginning at the following address */ - - .data : { - _sdata = ABSOLUTE(.); - *(.data .data.*) - *(.gnu.linkonce.d.*) - CONSTRUCTORS - _edata = ABSOLUTE(.); - } > sram AT > flash - - .bss : { - _sbss = ABSOLUTE(.); - *(.bss .bss.*) - *(.gnu.linkonce.b.*) - *(COMMON) - _ebss = ABSOLUTE(.); - } > sram - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_info 0 : { *(.debug_info) } - .debug_line 0 : { *(.debug_line) } - .debug_pubnames 0 : { *(.debug_pubnames) } - .debug_aranges 0 : { *(.debug_aranges) } -} diff --git a/nuttx/configs/px4iov2/common/setenv.sh b/nuttx/configs/px4iov2/common/setenv.sh deleted file mode 100755 index ff9a4bf8a..000000000 --- a/nuttx/configs/px4iov2/common/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# configs/stm3210e-eval/dfu/setenv.sh -# -# Copyright (C) 2009 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - -WD=`pwd` -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/px4iov2/include/README.txt b/nuttx/configs/px4iov2/include/README.txt deleted file mode 100755 index 2264a80aa..000000000 --- a/nuttx/configs/px4iov2/include/README.txt +++ /dev/null @@ -1 +0,0 @@ -This directory contains header files unique to the PX4IO board. diff --git a/nuttx/configs/px4iov2/include/board.h b/nuttx/configs/px4iov2/include/board.h deleted file mode 100755 index 21aacda87..000000000 --- a/nuttx/configs/px4iov2/include/board.h +++ /dev/null @@ -1,184 +0,0 @@ -/************************************************************************************ - * configs/px4io/include/board.h - * include/arch/board/board.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * - * 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_BOARD_H -#define __ARCH_BOARD_BOARD_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#ifndef __ASSEMBLY__ -# include -# include -#endif -#include -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Clocking *************************************************************************/ - -/* On-board crystal frequency is 24MHz (HSE) */ - -#define STM32_BOARD_XTAL 24000000ul - -/* Use the HSE output as the system clock */ - -#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE -#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE -#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL - -/* AHB clock (HCLK) is SYSCLK (24MHz) */ - -#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK -#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY -#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ - -/* APB2 clock (PCLK2) is HCLK (24MHz) */ - -#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK -#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY -#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */ - -/* APB2 timer 1 will receive PCLK2. */ - -#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) - -/* APB1 clock (PCLK1) is HCLK (24MHz) */ - -#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK -#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY) - -/* All timers run off PCLK */ - -#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY) - -/* - * Some of the USART pins are not available; override the GPIO - * definitions with an invalid pin configuration. - */ -#undef GPIO_USART2_CTS -#define GPIO_USART2_CTS 0xffffffff -#undef GPIO_USART2_RTS -#define GPIO_USART2_RTS 0xffffffff -#undef GPIO_USART2_CK -#define GPIO_USART2_CK 0xffffffff -#undef GPIO_USART3_TX -#define GPIO_USART3_TX 0xffffffff -#undef GPIO_USART3_CK -#define GPIO_USART3_CK 0xffffffff -#undef GPIO_USART3_CTS -#define GPIO_USART3_CTS 0xffffffff -#undef GPIO_USART3_RTS -#define GPIO_USART3_RTS 0xffffffff - -/* - * High-resolution timer - */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ -#endif - -/* - * PPM - * - * PPM input is handled by the HRT timer. - * - * Pin is PA8, timer 1, channel 1 - */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ -# define GPIO_PPM_IN GPIO_TIM1_CH1IN -#endif - -/* LED definitions ******************************************************************/ -/* PX4 has two LEDs that we will encode as: */ - -#define LED_STARTED 0 /* LED? */ -#define LED_HEAPALLOCATE 1 /* LED? */ -#define LED_IRQSENABLED 2 /* LED? + LED? */ -#define LED_STACKCREATED 3 /* LED? */ -#define LED_INIRQ 4 /* LED? + LED? */ -#define LED_SIGNAL 5 /* LED? + LED? */ -#define LED_ASSERTION 6 /* LED? + LED? + LED? */ -#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ -/************************************************************************************ - * 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. - * - ************************************************************************************/ - -EXTERN void stm32_boardinitialize(void); - -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx/configs/px4iov2/io/Make.defs b/nuttx/configs/px4iov2/io/Make.defs deleted file mode 100644 index 369772d03..000000000 --- a/nuttx/configs/px4iov2/io/Make.defs +++ /dev/null @@ -1,3 +0,0 @@ -include ${TOPDIR}/.config - -include $(TOPDIR)/configs/px4io/common/Make.defs diff --git a/nuttx/configs/px4iov2/io/appconfig b/nuttx/configs/px4iov2/io/appconfig deleted file mode 100644 index 48a41bcdb..000000000 --- a/nuttx/configs/px4iov2/io/appconfig +++ /dev/null @@ -1,32 +0,0 @@ -############################################################################ -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# -# 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 PX4 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. -# -############################################################################ diff --git a/nuttx/configs/px4iov2/io/defconfig b/nuttx/configs/px4iov2/io/defconfig deleted file mode 100755 index 1eaf4f2d1..000000000 --- a/nuttx/configs/px4iov2/io/defconfig +++ /dev/null @@ -1,548 +0,0 @@ -############################################################################ -# configs/px4io/nsh/defconfig -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# Copyright (C) 2011-2012 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. -# -############################################################################ -# -# architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_family - for use in C code. This identifies the -# 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 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, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# CONFIG_BOARD_LOOPSPERMSEC - for delay loops -# CONFIG_DRAM_SIZE - Describes the installed DRAM. -# CONFIG_DRAM_START - The start address of DRAM (physical) -# 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 -# stack in bytes. If not defined, the user task stacks will be -# used during interrupt handling. -# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions -# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. -# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. -# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. -# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that -# cause a 100 second delay during boot-up. This 100 second delay -# serves no purpose other than it allows you to calibrate -# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure -# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until -# the delay actually is 100 seconds. -# CONFIG_ARCH_DMA - Support DMA initialization -# -CONFIG_ARCH="arm" -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM3=y -CONFIG_ARCH_CHIP="stm32" -CONFIG_ARCH_CHIP_STM32F100C8=y -CONFIG_ARCH_BOARD="px4iov2" -CONFIG_ARCH_BOARD_PX4IOV2=y -CONFIG_BOARD_LOOPSPERMSEC=2000 -CONFIG_DRAM_SIZE=0x00002000 -CONFIG_DRAM_START=0x20000000 -CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_INTERRUPTSTACK=n -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=n -CONFIG_ARCH_BUTTONS=n -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=y -CONFIG_ARCH_MATH_H=y - -CONFIG_ARMV7M_CMNVECTOR=y - -# -# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): -# -# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG -# -# JTAG Enable options: -# -# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# but without JNTRST. -# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled -# -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=y -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=n - -# -# Individual subsystems can be enabled: -# -# AHB: -CONFIG_STM32_DMA1=y -CONFIG_STM32_DMA2=n -CONFIG_STM32_CRC=n -# APB1: -# Timers 2,3 and 4 are owned by the PWM driver -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=n -CONFIG_STM32_TIM4=n -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_WWDG=n -CONFIG_STM32_SPI2=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=y -CONFIG_STM32_I2C1=n -CONFIG_STM32_I2C2=n -CONFIG_STM32_BKP=n -CONFIG_STM32_PWR=n -CONFIG_STM32_DAC=n -# APB2: -# We use our own ADC driver, but leave this on for clocking purposes. -CONFIG_STM32_ADC1=y -CONFIG_STM32_ADC2=n -# TIM1 is owned by the HRT -CONFIG_STM32_TIM1=n -CONFIG_STM32_SPI1=n -CONFIG_STM32_TIM8=n -CONFIG_STM32_USART1=y -CONFIG_STM32_ADC3=n - - -# -# STM32F100 specific serial device driver settings -# -# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the -# console and ttys0 (default is the USART1). -# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. -# This specific the size of the receive buffer -# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before -# being sent. This specific the size of the transmit buffer -# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be -# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. -# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity -# CONFIG_USARTn_2STOP - Two stop bits -# -CONFIG_SERIAL_TERMIOS=y -CONFIG_STANDARD_SERIAL=y - -CONFIG_USART1_SERIAL_CONSOLE=y -CONFIG_USART2_SERIAL_CONSOLE=n -CONFIG_USART3_SERIAL_CONSOLE=n - -CONFIG_USART1_TXBUFSIZE=64 -CONFIG_USART2_TXBUFSIZE=64 -CONFIG_USART3_TXBUFSIZE=64 - -CONFIG_USART1_RXBUFSIZE=64 -CONFIG_USART2_RXBUFSIZE=64 -CONFIG_USART3_RXBUFSIZE=64 - -CONFIG_USART1_BAUD=115200 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 - -CONFIG_USART1_RXDMA=y -SERIAL_HAVE_CONSOLE_DMA=y -# Conflicts with I2C1 DMA -CONFIG_USART2_RXDMA=n -CONFIG_USART3_RXDMA=y - -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# 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 -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. -# You would only need this if you are concerned about accurate -# time conversions in the past or in the distant future. -# CONFIG_JULIAN_TIME - Enables Julian time conversions. You -# would only need this if you are concerned about accurate -# time conversion in the distand past. You must also define -# CONFIG_GREGORIAN_TIME in order to use Julian time. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# 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_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, -# can be safely disabled. The worker thread also performs -# garbage collection -- completing any delayed memory deallocations -# from interrupt handlers. If the worker thread is disabled, -# then that clean will be performed by the IDLE thread instead -# (which runs at the lowest of priority and may not be appropriate -# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE -# is enabled, then the following options can also be used: -# 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). -# 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 -# the worker thread. Default: 4 -# CONFIG_SCHED_WAITPID - Enable the waitpid() API -# CONFIG_SCHED_ATEXIT - Enabled the atexit() API -# -CONFIG_USER_ENTRYPOINT="user_start" -#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_MSEC_PER_TICK=1 -CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=y -CONFIG_MM_REGIONS=1 -CONFIG_MM_SMALL=y -CONFIG_ARCH_LOWPUTC=y -CONFIG_RR_INTERVAL=0 -CONFIG_SCHED_INSTRUMENTATION=n -CONFIG_TASK_NAME_SIZE=8 -CONFIG_START_YEAR=1970 -CONFIG_START_MONTH=1 -CONFIG_START_DAY=1 -CONFIG_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n -# this eats ~1KiB of RAM ... work out why -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SEM_NNESTPRIO=0 -CONFIG_FDCLONE_DISABLE=y -CONFIG_FDCLONE_STDIO=y -CONFIG_SDCLONE_DISABLE=y -CONFIG_SCHED_WORKQUEUE=n -CONFIG_SCHED_WORKPRIORITY=50 -CONFIG_SCHED_WORKPERIOD=50000 -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 -# APIs supported by the OS. If the compiler supports -# weak functions, then it should not be necessary to -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=y -CONFIG_DISABLE_PTHREAD=y -CONFIG_DISABLE_SIGNALS=y -CONFIG_DISABLE_MQUEUE=y -CONFIG_DISABLE_MOUNTPOINT=y -CONFIG_DISABLE_ENVIRON=y -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# 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 -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=4 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=2 -CONFIG_NFILE_DESCRIPTORS=8 -CONFIG_NFILE_STREAMS=0 -CONFIG_NAME_MAX=12 -CONFIG_STDIO_BUFFER_SIZE=32 -CONFIG_STDIO_LINEBUFFER=n -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=4 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_PREALLOC_WDOGS=4 -CONFIG_PREALLOC_TIMERS=0 - - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_BUILTIN_APPS - Support external registered, -# "named" applications that can be executed from the NSH -# command line (see apps/README.txt for more information). -# 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_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# CONFIG_NSH_ARCHINIT - Platform provides architecture -# specific initialization (nsh_archinitialize()). -# - -# Disable NSH completely -CONFIG_NSH_CONSOLE=n - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# (should also be =n for the STM3210E-EVAL which always runs from flash) -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2) there after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_STACK_POINTER= -CONFIG_IDLETHREAD_STACKSIZE=1024 -CONFIG_USERMAIN_STACKSIZE=1200 -CONFIG_PTHREAD_STACK_MIN=512 -CONFIG_PTHREAD_STACK_DEFAULT=1024 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/px4iov2/io/setenv.sh b/nuttx/configs/px4iov2/io/setenv.sh deleted file mode 100755 index ff9a4bf8a..000000000 --- a/nuttx/configs/px4iov2/io/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# configs/stm3210e-eval/dfu/setenv.sh -# -# Copyright (C) 2009 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - -WD=`pwd` -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/px4iov2/nsh/Make.defs b/nuttx/configs/px4iov2/nsh/Make.defs deleted file mode 100644 index 87508e22e..000000000 --- a/nuttx/configs/px4iov2/nsh/Make.defs +++ /dev/null @@ -1,3 +0,0 @@ -include ${TOPDIR}/.config - -include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs diff --git a/nuttx/configs/px4iov2/nsh/appconfig b/nuttx/configs/px4iov2/nsh/appconfig deleted file mode 100644 index 3cfc41b43..000000000 --- a/nuttx/configs/px4iov2/nsh/appconfig +++ /dev/null @@ -1,44 +0,0 @@ -############################################################################ -# configs/stm3210e-eval/nsh/appconfig -# -# Copyright (C) 2011-2012 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. -# -############################################################################ - -# Path to example in apps/examples containing the user_start entry point - -CONFIGURED_APPS += examples/nsh - -CONFIGURED_APPS += system/readline -CONFIGURED_APPS += nshlib -CONFIGURED_APPS += reboot - -CONFIGURED_APPS += drivers/boards/px4iov2 diff --git a/nuttx/configs/px4iov2/nsh/defconfig b/nuttx/configs/px4iov2/nsh/defconfig deleted file mode 100755 index 14d7a6401..000000000 --- a/nuttx/configs/px4iov2/nsh/defconfig +++ /dev/null @@ -1,567 +0,0 @@ -############################################################################ -# configs/px4io/nsh/defconfig -# -# Copyright (C) 2009-2012 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. -# -############################################################################ -# -# architecture selection -# -# CONFIG_ARCH - identifies the arch subdirectory and, hence, the -# processor architecture. -# CONFIG_ARCH_family - for use in C code. This identifies the -# 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. -# 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, -# the board that supports the particular chip or SoC. -# CONFIG_ARCH_BOARD_name - for use in C code -# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) -# 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 -# stack in bytes. If not defined, the user task stacks will be -# used during interrupt handling. -# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions -# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. -# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. -# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. -# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that -# cause a 100 second delay during boot-up. This 100 second delay -# serves no purpose other than it allows you to calibrate -# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure -# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until -# the delay actually is 100 seconds. -# CONFIG_ARCH_DMA - Support DMA initialization -# -CONFIG_ARCH=arm -CONFIG_ARCH_ARM=y -CONFIG_ARCH_CORTEXM3=y -CONFIG_ARCH_CHIP=stm32 -CONFIG_ARCH_CHIP_STM32F100C8=y -CONFIG_ARCH_BOARD=px4iov2 -CONFIG_ARCH_BOARD_PX4IOV2=y -CONFIG_BOARD_LOOPSPERMSEC=24000 -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 -CONFIG_ARCH_BOOTLOADER=n -CONFIG_ARCH_LEDS=n -CONFIG_ARCH_BUTTONS=y -CONFIG_ARCH_CALIBRATION=n -CONFIG_ARCH_DMA=n -CONFIG_ARMV7M_CMNVECTOR=y - -# -# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): -# -# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG -# -# JTAG Enable options: -# -# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) -# but without JNTRST. -# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled -# -CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=y -CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=n - -# -# Individual subsystems can be enabled: -# AHB: -CONFIG_STM32_DMA1=n -CONFIG_STM32_DMA2=n -CONFIG_STM32_CRC=n -# APB1: -# Timers 2,3 and 4 are owned by the PWM driver -CONFIG_STM32_TIM2=n -CONFIG_STM32_TIM3=n -CONFIG_STM32_TIM4=n -CONFIG_STM32_TIM5=n -CONFIG_STM32_TIM6=n -CONFIG_STM32_TIM7=n -CONFIG_STM32_WWDG=n -CONFIG_STM32_SPI2=n -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=y -CONFIG_STM32_I2C1=y -CONFIG_STM32_I2C2=n -CONFIG_STM32_BKP=n -CONFIG_STM32_PWR=n -CONFIG_STM32_DAC=n -# APB2: -CONFIG_STM32_ADC1=y -CONFIG_STM32_ADC2=n -# TIM1 is owned by the HRT -CONFIG_STM32_TIM1=n -CONFIG_STM32_SPI1=n -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 -# -# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the -# console and ttys0 (default is the USART1). -# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. -# This specific the size of the receive buffer -# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before -# being sent. This specific the size of the transmit buffer -# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be -# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. -# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity -# CONFIG_USARTn_2STOP - Two stop bits -# -CONFIG_USART1_SERIAL_CONSOLE=y -CONFIG_USART2_SERIAL_CONSOLE=n -CONFIG_USART3_SERIAL_CONSOLE=n - -CONFIG_USART1_TXBUFSIZE=64 -CONFIG_USART2_TXBUFSIZE=64 -CONFIG_USART3_TXBUFSIZE=64 - -CONFIG_USART1_RXBUFSIZE=64 -CONFIG_USART2_RXBUFSIZE=64 -CONFIG_USART3_RXBUFSIZE=64 - -CONFIG_USART1_BAUD=57600 -CONFIG_USART2_BAUD=115200 -CONFIG_USART3_BAUD=115200 - -CONFIG_USART1_BITS=8 -CONFIG_USART2_BITS=8 -CONFIG_USART3_BITS=8 - -CONFIG_USART1_PARITY=0 -CONFIG_USART2_PARITY=0 -CONFIG_USART3_PARITY=0 - -CONFIG_USART1_2STOP=0 -CONFIG_USART2_2STOP=0 -CONFIG_USART3_2STOP=0 - -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y -CONFIG_PWM_SERVO=y - -# -# General build options -# -# CONFIG_RRLOAD_BINARY - make the rrload binary format used with -# BSPs from www.ridgerun.com using the tools/mkimage.sh script -# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format -# used with many different loaders using the GNU objcopy program -# Should not be selected if you are not using the GNU toolchain. -# CONFIG_RAW_BINARY - make a raw binary format file used with many -# different loaders using the GNU objcopy program. This option -# should not be selected if you are not using the GNU toolchain. -# CONFIG_HAVE_LIBM - toolchain supports libm.a -# -CONFIG_RRLOAD_BINARY=n -CONFIG_INTELHEX_BINARY=n -CONFIG_MOTOROLA_SREC=n -CONFIG_RAW_BINARY=y -CONFIG_HAVE_LIBM=n - -# -# General OS setup -# -# CONFIG_APPS_DIR - Identifies the relative path to the directory -# that builds the application to link with NuttX. Default: ../apps -# CONFIG_DEBUG - enables built-in debug options -# CONFIG_DEBUG_VERBOSE - enables verbose debug output -# 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 -# handle and enables the API mm_addregion(start, end); -# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot -# time console output -# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz -# or MSEC_PER_TICK=10. This setting may be defined to -# inform NuttX that the processor hardware is providing -# system timer interrupts at some interrupt interval other -# than 10 msec. -# CONFIG_RR_INTERVAL - The round robin timeslice will be set -# this number of milliseconds; Round robin scheduling can -# be disabled by setting this value to zero. -# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in -# scheduler to monitor system performance -# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a -# task name to save in the TCB. Useful if scheduler -# instrumentation is selected. Set to zero to disable. -# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - -# Used to initialize the internal time logic. -# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. -# You would only need this if you are concerned about accurate -# time conversions in the past or in the distant future. -# CONFIG_JULIAN_TIME - Enables Julian time conversions. You -# would only need this if you are concerned about accurate -# time conversion in the distand past. You must also define -# CONFIG_GREGORIAN_TIME in order to use Julian time. -# CONFIG_DEV_CONSOLE - Set if architecture-specific logic -# provides /dev/console. Enables stdout, stderr, stdin. -# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console -# driver (minimul support) -# CONFIG_MUTEX_TYPES: Set to enable support for recursive and -# errorcheck mutexes. Enables pthread_mutexattr_settype(). -# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority -# inheritance on mutexes and semaphores. -# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority -# inheritance is enabled. It defines the maximum number of -# different threads (minus one) that can take counts on a -# semaphore with priority inheritance support. This may be -# set to zero if priority inheritance is disabled OR if you -# are only using semaphores as mutexes (only one holder) OR -# if no more than two threads participate using a counting -# semaphore. -# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, -# then this setting is the maximum number of higher priority -# threads (minus 1) than can be waiting for another thread -# to release a count on a semaphore. This value may be set -# to zero if no more than one thread is expected to wait for -# a semaphore. -# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors -# by task_create() when a new task is started. If set, all -# files/drivers will appear to be closed in the new task. -# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first -# three file descriptors (stdin, stdout, stderr) by task_create() -# when a new task is started. If set, all files/drivers will -# appear to be closed in the new task except for stdin, stdout, -# and stderr. -# 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, -# can be safely disabled. The worker thread also performs -# garbage collection -- completing any delayed memory deallocations -# from interrupt handlers. If the worker thread is disabled, -# then that clean will be performed by the IDLE thread instead -# (which runs at the lowest of priority and may not be appropriate -# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE -# is enabled, then the following options can also be used: -# 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). -# 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 -# the worker thread. Default: 4 -# -#CONFIG_APPS_DIR= -CONFIG_DEBUG=n -CONFIG_DEBUG_VERBOSE=n -CONFIG_DEBUG_SYMBOLS=y -CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=n -CONFIG_MM_REGIONS=1 -CONFIG_MM_SMALL=y -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_GREGORIAN_TIME=n -CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y -CONFIG_DEV_LOWCONSOLE=n -CONFIG_MUTEX_TYPES=n -CONFIG_PRIORITY_INHERITANCE=n -CONFIG_SEM_PREALLOCHOLDERS=0 -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=512 -CONFIG_SIG_SIGWORK=4 - -CONFIG_USER_ENTRYPOINT="nsh_main" -# -# 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 -# disable functions unless you want to restrict usage -# of those APIs. -# -# There are certain dependency relationships in these -# features. -# -# o mq_notify logic depends on signals to awaken tasks -# waiting for queues to become full or empty. -# o pthread_condtimedwait() depends on signals to wake -# up waiting tasks. -# -CONFIG_DISABLE_CLOCK=n -CONFIG_DISABLE_POSIX_TIMERS=y -CONFIG_DISABLE_PTHREAD=n -CONFIG_DISABLE_SIGNALS=n -CONFIG_DISABLE_MQUEUE=y -CONFIG_DISABLE_MOUNTPOINT=y -CONFIG_DISABLE_ENVIRON=y -CONFIG_DISABLE_POLL=y - -# -# Misc libc settings -# -# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a -# little smaller if we do not support fieldwidthes -# -CONFIG_NOPRINTF_FIELDWIDTH=n - -# -# Allow for architecture optimized implementations -# -# The architecture can provide optimized versions of the -# following to improve system performance -# -CONFIG_ARCH_MEMCPY=n -CONFIG_ARCH_MEMCMP=n -CONFIG_ARCH_MEMMOVE=n -CONFIG_ARCH_MEMSET=n -CONFIG_ARCH_STRCMP=n -CONFIG_ARCH_STRCPY=n -CONFIG_ARCH_STRNCPY=n -CONFIG_ARCH_STRLEN=n -CONFIG_ARCH_STRNLEN=n -CONFIG_ARCH_BZERO=n - -# -# Sizes of configurable things (0 disables) -# -# CONFIG_MAX_TASKS - The maximum number of simultaneously -# active tasks. This value must be a power of two. -# CONFIG_MAX_TASK_ARGS - This controls the maximum number of -# of parameters that a task may receive (i.e., maxmum value -# of 'argc') -# CONFIG_NPTHREAD_KEYS - The number of items of thread- -# specific data that can be retained -# CONFIG_NFILE_DESCRIPTORS - The maximum number of file -# descriptors (one for each open) -# CONFIG_NFILE_STREAMS - The maximum number of streams that -# can be fopen'ed -# 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_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 -# structures. The system manages a pool of preallocated -# message structures to minimize dynamic allocations -# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with -# a fixed payload size given by this settin (does not include -# other message structure overhead. -# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that -# can be passed to a watchdog handler -# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog -# structures. The system manages a pool of preallocated -# watchdog structures to minimize dynamic allocations -# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX -# timer structures. The system manages a pool of preallocated -# timer structures to minimize dynamic allocations. Set to -# zero for all dynamic allocations. -# -CONFIG_MAX_TASKS=4 -CONFIG_MAX_TASK_ARGS=4 -CONFIG_NPTHREAD_KEYS=2 -CONFIG_NFILE_DESCRIPTORS=6 -CONFIG_NFILE_STREAMS=4 -CONFIG_NAME_MAX=32 -CONFIG_STDIO_BUFFER_SIZE=64 -CONFIG_NUNGET_CHARS=2 -CONFIG_PREALLOC_MQ_MSGS=1 -CONFIG_MQ_MAXMSGSIZE=32 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_PREALLOC_WDOGS=3 -CONFIG_PREALLOC_TIMERS=1 - - -# -# Settings for apps/nshlib -# -# CONFIG_NSH_BUILTIN_APPS - Support external registered, -# "named" applications that can be executed from the NSH -# command line (see apps/README.txt for more information). -# 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_NESTDEPTH - Max number of nested if-then[-else]-fi -# CONFIG_NSH_DISABLESCRIPT - Disable scripting support -# CONFIG_NSH_DISABLEBG - Disable background commands -# CONFIG_NSH_ROMFSETC - Use startup script in /etc -# CONFIG_NSH_CONSOLE - Use serial console front end -# CONFIG_NSH_TELNET - Use telnetd console front end -# CONFIG_NSH_ARCHINIT - Platform provides architecture -# specific initialization (nsh_archinitialize()). -# -# If CONFIG_NSH_TELNET is selected: -# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size -# CONFIG_NSH_DHCPC - Obtain address using DHCP -# CONFIG_NSH_IPADDR - Provides static IP address -# CONFIG_NSH_DRIPADDR - Provides static router IP address -# CONFIG_NSH_NETMASK - Provides static network mask -# CONFIG_NSH_NOMAC - Use a bogus MAC address -# -# If CONFIG_NSH_ROMFSETC is selected: -# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint -# CONFIG_NSH_INITSCRIPT - Relative path to init script -# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor -# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size -# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor -# CONFIG_NSH_FATSECTSIZE - FAT FS sector size -# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors -# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint -# -CONFIG_BUILTIN=y -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_FILEIOSIZE=64 -CONFIG_NSH_STRERROR=n -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_NESTDEPTH=1 -CONFIG_NSH_DISABLESCRIPT=y -CONFIG_NSH_DISABLEBG=n -CONFIG_NSH_ROMFSETC=n -CONFIG_NSH_CONSOLE=y -CONFIG_NSH_TELNET=n -CONFIG_NSH_ARCHINIT=n -CONFIG_NSH_IOBUFFER_SIZE=256 -CONFIG_NSH_STACKSIZE=1024 -CONFIG_NSH_DHCPC=n -CONFIG_NSH_NOMAC=n -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_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=64 -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT=/tmp - -# -# Architecture-specific NSH options -# -CONFIG_NSH_MMCSDSPIPORTNO=0 -CONFIG_NSH_MMCSDSLOTNO=0 -CONFIG_NSH_MMCSDMINOR=0 - -# -# Stack and heap information -# -# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP -# operation from FLASH but must copy initialized .data sections to RAM. -# (should also be =n for the STM3210E-EVAL which always runs from flash) -# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH -# but copy themselves entirely into RAM for better performance. -# CONFIG_CUSTOM_STACK - The up_ implementation will handle -# all stack operations outside of the nuttx model. -# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) -# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. -# This is the thread that (1) performs the inital boot of the system up -# to the point where user_start() is spawned, and (2) there after is the -# IDLE thread that executes only when there is no other thread ready to -# run. -# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate -# for the main user thread that begins at the user_start() entry point. -# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size -# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size -# CONFIG_HEAP_BASE - The beginning of the heap -# CONFIG_HEAP_SIZE - The size of the heap -# -CONFIG_BOOT_RUNFROMFLASH=n -CONFIG_BOOT_COPYTORAM=n -CONFIG_CUSTOM_STACK=n -CONFIG_STACK_POINTER= -CONFIG_IDLETHREAD_STACKSIZE=800 -CONFIG_USERMAIN_STACKSIZE=1024 -CONFIG_PTHREAD_STACK_MIN=256 -CONFIG_PTHREAD_STACK_DEFAULT=512 -CONFIG_HEAP_BASE= -CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/px4iov2/nsh/setenv.sh b/nuttx/configs/px4iov2/nsh/setenv.sh deleted file mode 100755 index d83685192..000000000 --- a/nuttx/configs/px4iov2/nsh/setenv.sh +++ /dev/null @@ -1,47 +0,0 @@ -#!/bin/bash -# configs/stm3210e-eval/dfu/setenv.sh -# -# Copyright (C) 2009 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. -# - -if [ "$(basename $0)" = "setenv.sh" ] ; then - echo "You must source this script, not run it!" 1>&2 - exit 1 -fi - -if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi - -WD=`pwd` -export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" -export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin" -export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" - -echo "PATH : ${PATH}" diff --git a/nuttx/configs/px4iov2/src/Makefile b/nuttx/configs/px4iov2/src/Makefile deleted file mode 100644 index bb9539d16..000000000 --- a/nuttx/configs/px4iov2/src/Makefile +++ /dev/null @@ -1,84 +0,0 @@ -############################################################################ -# configs/stm3210e-eval/src/Makefile -# -# Copyright (C) 2009-2010 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)/Make.defs - -CFLAGS += -I$(TOPDIR)/sched - -ASRCS = -AOBJS = $(ASRCS:.S=$(OBJEXT)) - -CSRCS = empty.c - -COBJS = $(CSRCS:.c=$(OBJEXT)) - -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) - -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -ifeq ($(WINTOOL),y) - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" -else - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m -endif - -all: libboard$(LIBEXT) - -$(AOBJS): %$(OBJEXT): %.S - $(call ASSEMBLE, $<, $@) - -$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c - $(call COMPILE, $<, $@) - -libboard$(LIBEXT): $(OBJS) - $(call ARCHIVE, $@, $(OBJS)) - -.depend: Makefile $(SRCS) - @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ - -depend: .depend - -clean: - $(call DELFILE, libboard$(LIBEXT)) - $(call CLEAN) - -distclean: clean - $(call DELFILE, Make.dep) - $(call DELFILE, .depend) - --include Make.dep diff --git a/nuttx/configs/px4iov2/src/README.txt b/nuttx/configs/px4iov2/src/README.txt deleted file mode 100644 index d4eda82fd..000000000 --- a/nuttx/configs/px4iov2/src/README.txt +++ /dev/null @@ -1 +0,0 @@ -This directory contains drivers unique to the STMicro STM3210E-EVAL development board. diff --git a/nuttx/configs/px4iov2/src/empty.c b/nuttx/configs/px4iov2/src/empty.c deleted file mode 100644 index ace900866..000000000 --- a/nuttx/configs/px4iov2/src/empty.c +++ /dev/null @@ -1,4 +0,0 @@ -/* - * There are no source files here, but libboard.a can't be empty, so - * we have this empty source file to keep it company. - */ diff --git a/src/drivers/boards/px4fmuv2/px4fmu_init.c b/src/drivers/boards/px4fmuv2/px4fmu_init.c index 03ec5a255..f9d1b8022 100644 --- a/src/drivers/boards/px4fmuv2/px4fmu_init.c +++ b/src/drivers/boards/px4fmuv2/px4fmu_init.c @@ -59,9 +59,9 @@ #include #include -#include "stm32_internal.h" +#include #include "px4fmu_internal.h" -#include "stm32_uart.h" +#include #include diff --git a/src/drivers/boards/px4fmuv2/px4fmu_internal.h b/src/drivers/boards/px4fmuv2/px4fmu_internal.h index dd291b9b7..dce51bcda 100644 --- a/src/drivers/boards/px4fmuv2/px4fmu_internal.h +++ b/src/drivers/boards/px4fmuv2/px4fmu_internal.h @@ -50,7 +50,7 @@ __BEGIN_DECLS /* these headers are not C++ safe */ -#include +#include /**************************************************************************************************** diff --git a/src/drivers/boards/px4fmuv2/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmuv2/px4fmu_pwm_servo.c index 14e4052be..d1656005b 100644 --- a/src/drivers/boards/px4fmuv2/px4fmu_pwm_servo.c +++ b/src/drivers/boards/px4fmuv2/px4fmu_pwm_servo.c @@ -46,7 +46,7 @@ #include #include -#include +#include #include #include diff --git a/src/drivers/boards/px4fmuv2/px4fmu_spi.c b/src/drivers/boards/px4fmuv2/px4fmu_spi.c index f90f25071..5e90c227d 100644 --- a/src/drivers/boards/px4fmuv2/px4fmu_spi.c +++ b/src/drivers/boards/px4fmuv2/px4fmu_spi.c @@ -50,9 +50,9 @@ #include #include -#include "up_arch.h" -#include "chip.h" -#include "stm32_internal.h" +#include +#include +#include #include "px4fmu_internal.h" /************************************************************************************ diff --git a/src/drivers/boards/px4fmuv2/px4fmu_usb.c b/src/drivers/boards/px4fmuv2/px4fmu_usb.c index b0b669fbe..3492e2c68 100644 --- a/src/drivers/boards/px4fmuv2/px4fmu_usb.c +++ b/src/drivers/boards/px4fmuv2/px4fmu_usb.c @@ -51,8 +51,8 @@ #include #include -#include "up_arch.h" -#include "stm32_internal.h" +#include +#include #include "px4fmu_internal.h" /************************************************************************************ diff --git a/src/drivers/boards/px4iov2/px4iov2_init.c b/src/drivers/boards/px4iov2/px4iov2_init.c index 5d7b22560..e95298bf5 100644 --- a/src/drivers/boards/px4iov2/px4iov2_init.c +++ b/src/drivers/boards/px4iov2/px4iov2_init.c @@ -54,7 +54,7 @@ #include -#include "stm32_internal.h" +#include #include "px4iov2_internal.h" #include diff --git a/src/drivers/boards/px4iov2/px4iov2_internal.h b/src/drivers/boards/px4iov2/px4iov2_internal.h index 81a75431c..2bf65e047 100755 --- a/src/drivers/boards/px4iov2/px4iov2_internal.h +++ b/src/drivers/boards/px4iov2/px4iov2_internal.h @@ -48,7 +48,7 @@ #include /* these headers are not C++ safe */ -#include +#include /****************************************************************************** diff --git a/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c b/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c index 5e1aafa49..4f1b9487c 100644 --- a/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c +++ b/src/drivers/boards/px4iov2/px4iov2_pwm_servo.c @@ -46,7 +46,7 @@ #include #include -#include +#include #include #include diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h index a4c59d218..faeb9cf60 100644 --- a/src/drivers/drv_gpio.h +++ b/src/drivers/drv_gpio.h @@ -42,7 +42,7 @@ #include -#ifdef CONFIG_ARCH_BOARD_PX4FMU +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 /* * PX4FMU GPIO numbers. * @@ -67,7 +67,7 @@ #endif -#ifdef CONFIG_ARCH_BOARD_PX4FMUV2 +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 /* * PX4FMUv2 GPIO numbers. * @@ -93,36 +93,14 @@ #endif -#ifdef CONFIG_ARCH_BOARD_PX4IO -/* - * PX4IO GPIO numbers. - * - * XXX note that these are here for reference/future use; currently - * there is no good way to wire these up without a common STM32 GPIO - * driver, which isn't implemented yet. - */ -/* outputs */ -# define GPIO_ACC1_POWER (1<<0) /**< accessory power 1 */ -# define GPIO_ACC2_POWER (1<<1) /**< accessory power 2 */ -# define GPIO_SERVO_POWER (1<<2) /**< servo power */ -# define GPIO_RELAY1 (1<<3) /**< relay 1 */ -# define GPIO_RELAY2 (1<<4) /**< relay 2 */ -# define GPIO_LED_BLUE (1<<5) /**< blue LED */ -# define GPIO_LED_AMBER (1<<6) /**< amber/red LED */ -# define GPIO_LED_SAFETY (1<<7) /**< safety LED */ - -/* inputs */ -# define GPIO_ACC_OVERCURRENT (1<<8) /**< accessory 1/2 overcurrent detect */ -# define GPIO_SERVO_OVERCURRENT (1<<9) /**< servo overcurrent detect */ -# define GPIO_SAFETY_BUTTON (1<<10) /**< safety button pressed */ - -/** - * Default GPIO device - other devices may also support this protocol if - * they also export GPIO-like things. This is always the GPIOs on the - * main board. - */ -# define GPIO_DEVICE_PATH "/dev/px4io" +#ifdef CONFIG_ARCH_BOARD_PX4IO_V1 +/* no GPIO driver on the PX4IOv1 board */ +# define GPIO_DEVICE_PATH "/nonexistent" +#endif +#ifdef CONFIG_ARCH_BOARD_PX4IO_V2 +/* no GPIO driver on the PX4IOv2 board */ +# define GPIO_DEVICE_PATH "/nonexistent" #endif #ifndef GPIO_DEVICE_PATH diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index ff99de02f..7d3af4b0d 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -59,10 +59,10 @@ #include #include -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) # include # define FMU_HAVE_PPM -#elif defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) # include # undef FMU_HAVE_PPM #else @@ -158,7 +158,7 @@ private: }; const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = { -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, @@ -168,7 +168,7 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = { {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, #endif -#if defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, @@ -873,7 +873,7 @@ PX4FMU::gpio_reset(void) } } -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) /* if we have a GPIO direction control, set it to zero (input) */ stm32_gpiowrite(GPIO_GPIO_DIR, 0); stm32_configgpio(GPIO_GPIO_DIR); @@ -883,7 +883,7 @@ PX4FMU::gpio_reset(void) void PX4FMU::gpio_set_function(uint32_t gpios, int function) { -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) /* * GPIOs 0 and 1 must have the same direction as they are buffered * by a shared 2-port driver. Any attempt to set either sets both. @@ -918,7 +918,7 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function) } } -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) /* flip buffer to input mode if required */ if ((GPIO_SET_INPUT == function) && (gpios & 3)) stm32_gpiowrite(GPIO_GPIO_DIR, 0); @@ -1024,17 +1024,17 @@ fmu_new_mode(PortMode new_mode) break; case PORT_FULL_PWM: -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) /* select 4-pin PWM mode */ servo_mode = PX4FMU::MODE_4PWM; #endif -#if defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) servo_mode = PX4FMU::MODE_6PWM; #endif break; /* mixed modes supported on v1 board only */ -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) case PORT_FULL_SERIAL: /* set all multi-GPIOs to serial mode */ gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4; @@ -1116,7 +1116,7 @@ test(void) if (ioctl(fd, PWM_SERVO_SET(3), 1600) < 0) err(1, "servo 4 set failed"); -#if defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) if (ioctl(fd, PWM_SERVO_SET(4), 1800) < 0) err(1, "servo 5 set failed"); if (ioctl(fd, PWM_SERVO_SET(5), 2000) < 0) err(1, "servo 6 set failed"); @@ -1183,7 +1183,7 @@ fmu_main(int argc, char *argv[]) } else if (!strcmp(verb, "mode_pwm")) { new_mode = PORT_FULL_PWM; -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) } else if (!strcmp(verb, "mode_serial")) { new_mode = PORT_FULL_SERIAL; @@ -1217,9 +1217,9 @@ fmu_main(int argc, char *argv[]) fake(argc - 1, argv + 1); fprintf(stderr, "FMU: unrecognised command, try:\n"); -#if defined(CONFIG_ARCH_BOARD_PX4FMU) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio\n"); -#elif defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) fprintf(stderr, " mode_gpio, mode_pwm\n"); #endif exit(1); diff --git a/src/drivers/px4io/interface_serial.cpp b/src/drivers/px4io/interface_serial.cpp index 9727daa71..06b955971 100644 --- a/src/drivers/px4io/interface_serial.cpp +++ b/src/drivers/px4io/interface_serial.cpp @@ -56,7 +56,6 @@ #include #include #include -#include #include diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 15e213afb..29624018f 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1604,9 +1604,9 @@ start(int argc, char *argv[]) PX4IO_interface *interface; -#if defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) interface = io_serial_interface(); -#elif defined(CONFIG_ARCH_BOARD_PX4FMU) +#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V1) interface = io_i2c_interface(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO); #else # error Unknown board - cannot select interface. @@ -1741,9 +1741,9 @@ if_test(unsigned mode) { PX4IO_interface *interface; -#if defined(CONFIG_ARCH_BOARD_PX4FMUV2) +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) interface = io_serial_interface(); -#elif defined(CONFIG_ARCH_BOARD_PX4FMU) +#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V1) interface = io_i2c_interface(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO); #else # error Unknown board - cannot select interface. diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/uploader.cpp index 28c584438..ec22a5e17 100644 --- a/src/drivers/px4io/uploader.cpp +++ b/src/drivers/px4io/uploader.cpp @@ -56,10 +56,10 @@ #include "uploader.h" -#ifdef CONFIG_ARCH_BOARD_PX4FMUV2 +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 #include #endif -#ifdef CONFIG_ARCH_BOARD_PX4FMU +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 #include #endif diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index 7ef3db970..1cc18afda 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -70,7 +70,7 @@ #include "stm32_gpio.h" #include "stm32_tim.h" -#ifdef CONFIG_HRT_TIMER +#ifdef HRT_TIMER /* HRT configuration */ #if HRT_TIMER == 1 @@ -275,7 +275,7 @@ static void hrt_call_invoke(void); /* * Specific registers and bits used by PPM sub-functions */ -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it. * @@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status); # define CCMR1_PPM 0 # define CCMR2_PPM 0 # define CCER_PPM 0 -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Initialise the timer we are going to use. @@ -907,4 +907,4 @@ hrt_latency_update(void) } -#endif /* CONFIG_HRT_TIMER */ +#endif /* HRT_TIMER */ diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 167ef30a8..2284be84d 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -117,10 +117,6 @@ #include -#ifndef CONFIG_HRT_TIMER -# error This driver requires CONFIG_HRT_TIMER -#endif - /* Tone alarm configuration */ #if TONE_ALARM_TIMER == 2 # define TONE_ALARM_BASE STM32_TIM2_BASE diff --git a/src/modules/px4iofirmware/module.mk b/src/modules/px4iofirmware/module.mk index 4dd1aa8d7..59f470a94 100644 --- a/src/modules/px4iofirmware/module.mk +++ b/src/modules/px4iofirmware/module.mk @@ -15,10 +15,10 @@ SRCS = adc.c \ ../systemlib/mixer/mixer_multirotor.cpp \ ../systemlib/mixer/mixer_simple.cpp \ -ifeq ($(BOARD),px4io) +ifeq ($(BOARD),px4io-v1) SRCS += i2c.c endif -ifeq ($(BOARD),px4iov2) +ifeq ($(BOARD),px4io-v2) SRCS += serial.c \ ../systemlib/hx_stream.c endif diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index b32782285..ccf175e45 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -42,10 +42,10 @@ #include #include -#ifdef CONFIG_ARCH_BOARD_PX4IO +#ifdef CONFIG_ARCH_BOARD_PX4IO_V1 # include #endif -#ifdef CONFIG_ARCH_BOARD_PX4IOV2 +#ifdef CONFIG_ARCH_BOARD_PX4IO_V2 # include #endif @@ -129,18 +129,7 @@ extern struct sys_state_s system_state; #define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s)) #define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s)) -#ifdef CONFIG_ARCH_BOARD_PX4IOV2 - -# define PX4IO_RELAY_CHANNELS 0 -# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s)) - -# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT)) - -# define PX4IO_ADC_CHANNEL_COUNT 2 -# define ADC_VSERVO 4 -# define ADC_RSSI 5 - -#else /* CONFIG_ARCH_BOARD_PX4IOV1 */ +#ifdef CONFIG_ARCH_BOARD_PX4IO_V1 # define PX4IO_RELAY_CHANNELS 4 # define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s)) @@ -158,6 +147,19 @@ extern struct sys_state_s system_state; #endif +#ifdef CONFIG_ARCH_BOARD_PX4IO_V2 + +# define PX4IO_RELAY_CHANNELS 0 +# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s)) + +# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT)) + +# define PX4IO_ADC_CHANNEL_COUNT 2 +# define ADC_VSERVO 4 +# define ADC_RSSI 5 + +#endif + #define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY) /* diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index f4541936b..873ee73f1 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -59,7 +59,7 @@ static void pwm_configure_rates(uint16_t map, uint16_t defaultrate, uint16_t alt */ static const uint16_t r_page_config[] = { [PX4IO_P_CONFIG_PROTOCOL_VERSION] = PX4IO_PROTOCOL_VERSION, -#ifdef CONFIG_ARCH_BOARD_PX4IOV2 +#ifdef CONFIG_ARCH_BOARD_PX4IO_V2 [PX4IO_P_CONFIG_HARDWARE_VERSION] = 2, #else [PX4IO_P_CONFIG_HARDWARE_VERSION] = 1, diff --git a/src/modules/px4iofirmware/serial.c b/src/modules/px4iofirmware/serial.c index e4bc68f58..2f3184623 100644 --- a/src/modules/px4iofirmware/serial.c +++ b/src/modules/px4iofirmware/serial.c @@ -50,7 +50,7 @@ #include #include #include -#include +#include #include //#define DEBUG -- cgit v1.2.3