From e39e73cea195d7237dbe8409f7bf9ea0182b93d1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 31 Oct 2019 22:34:05 -0400 Subject: [PATCH] delete auav esc35-v1 board --- Makefile | 1 - boards/auav/esc35-v1/default.cmake | 60 ---- boards/auav/esc35-v1/firmware.prototype | 13 - boards/auav/esc35-v1/nuttx-config/Kconfig | 22 -- .../esc35-v1/nuttx-config/include/README.txt | 2 - .../esc35-v1/nuttx-config/include/board.h | 261 ----------------- .../auav/esc35-v1/nuttx-config/nsh/defconfig | 116 -------- .../esc35-v1/nuttx-config/scripts/script.ld | 154 ---------- boards/auav/esc35-v1/src/CMakeLists.txt | 46 --- boards/auav/esc35-v1/src/board_config.h | 273 ------------------ boards/auav/esc35-v1/src/init.c | 210 -------------- boards/auav/esc35-v1/src/led.c | 192 ------------ boards/auav/esc35-v1/src/usb.c | 102 ------- 13 files changed, 1452 deletions(-) delete mode 100644 boards/auav/esc35-v1/default.cmake delete mode 100644 boards/auav/esc35-v1/firmware.prototype delete mode 100644 boards/auav/esc35-v1/nuttx-config/Kconfig delete mode 100644 boards/auav/esc35-v1/nuttx-config/include/README.txt delete mode 100644 boards/auav/esc35-v1/nuttx-config/include/board.h delete mode 100644 boards/auav/esc35-v1/nuttx-config/nsh/defconfig delete mode 100644 boards/auav/esc35-v1/nuttx-config/scripts/script.ld delete mode 100644 boards/auav/esc35-v1/src/CMakeLists.txt delete mode 100644 boards/auav/esc35-v1/src/board_config.h delete mode 100644 boards/auav/esc35-v1/src/init.c delete mode 100644 boards/auav/esc35-v1/src/led.c delete mode 100644 boards/auav/esc35-v1/src/usb.c diff --git a/Makefile b/Makefile index e9479d31ee..60b65c4e56 100644 --- a/Makefile +++ b/Makefile @@ -264,7 +264,6 @@ misc_qgc_extra_firmware: \ alt_firmware: \ check_px4_cannode-v1_default \ check_px4_esc-v1_default \ - check_auav_esc35-v1_default \ check_thiemar_s2740vc-v1_default \ sizes diff --git a/boards/auav/esc35-v1/default.cmake b/boards/auav/esc35-v1/default.cmake deleted file mode 100644 index 606c066e48..0000000000 --- a/boards/auav/esc35-v1/default.cmake +++ /dev/null @@ -1,60 +0,0 @@ - -add_definitions( - -DFLASH_BASED_PARAMS - -DPARAM_NO_ORB - -DPARAM_NO_AUTOSAVE - -DPARAMETER_BUFFER_SIZE=1024 -) - -# UAVCAN boot loadable Module ID -set(uavcanblid_sw_version_major 0) -set(uavcanblid_sw_version_minor 1) -add_definitions( - -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} - -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} - ) - -# Bring in common uavcan hardware identity definitions -include(px4_git) -px4_add_git_submodule(TARGET git_uavcan_board_ident PATH "cmake/configs/uavcan_board_ident") -include(configs/uavcan_board_ident/esc35-v1) - -add_definitions( - -DHW_UAVCAN_NAME=${uavcanblid_name} - -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} - -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} -) - -include(px4_make_uavcan_bootloader) -px4_make_uavcan_bootloadable( - BOARD auav_esc35-v1 - BIN ${PX4_BINARY_DIR}/auav_esc35-v1.bin - HWNAME ${uavcanblid_name} - HW_MAJOR ${uavcanblid_hw_version_major} - HW_MINOR ${uavcanblid_hw_version_minor} - SW_MAJOR ${uavcanblid_sw_version_major} - SW_MINOR ${uavcanblid_sw_version_minor} -) - -px4_add_board( - PLATFORM nuttx - VENDOR auav - MODEL esc35-v1 - TOOLCHAIN arm-none-eabi - ARCHITECTURE cortex-m4 - - DRIVERS - bootloaders - uavcanesc - - MODULES - - SYSTEMCMDS - config - reboot - param - top - ver - work_queue - - ) diff --git a/boards/auav/esc35-v1/firmware.prototype b/boards/auav/esc35-v1/firmware.prototype deleted file mode 100644 index a613cefbdc..0000000000 --- a/boards/auav/esc35-v1/firmware.prototype +++ /dev/null @@ -1,13 +0,0 @@ -{ - "board_id": 27, - "magic": "ESC35v1", - "description": "Firmware for the ESC35V1 board", - "image": "", - "build_time": 0, - "summary": "ESC35v1", - "version": "0.1", - "image_size": 0, - "image_maxsize": 229376, - "git_identity": "", - "board_revision": 0 -} diff --git a/boards/auav/esc35-v1/nuttx-config/Kconfig b/boards/auav/esc35-v1/nuttx-config/Kconfig deleted file mode 100644 index 50c16460fd..0000000000 --- a/boards/auav/esc35-v1/nuttx-config/Kconfig +++ /dev/null @@ -1,22 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -if ARCH_BOARD_ESC35_V1 - -config BOARD_HAS_PROBES - bool "Board provides GPIO or other Hardware for signaling to timing analyze." - default y - ---help--- - This board provides GPIO PC13-PC15 as PROBE_1-3 to provide timing signals from selected drivers. - -config BOARD_USE_PROBES - bool "Enable the use the board provided GPIO PC13-PC15 as PROBE_1-3 to provide timing signals from selected drivers" - default n - depends on BOARD_HAS_PROBES - - ---help--- - Select to use GPIO PC13-PC15 as PROBE_1-3 to provide timing signals from selected drivers. - -endif diff --git a/boards/auav/esc35-v1/nuttx-config/include/README.txt b/boards/auav/esc35-v1/nuttx-config/include/README.txt deleted file mode 100644 index 5089f9023a..0000000000 --- a/boards/auav/esc35-v1/nuttx-config/include/README.txt +++ /dev/null @@ -1,2 +0,0 @@ -This directory contains header files unique to the -AUAV ESC35 V1.0 board using STM32F303CC diff --git a/boards/auav/esc35-v1/nuttx-config/include/board.h b/boards/auav/esc35-v1/nuttx-config/include/board.h deleted file mode 100644 index 17a210d461..0000000000 --- a/boards/auav/esc35-v1/nuttx-config/include/board.h +++ /dev/null @@ -1,261 +0,0 @@ -/************************************************************************************ - * configs/esc35-v1/include/board.h - * - * Copyright (C) 2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -#ifndef __CONFIGS_ESC35_V1_INCLUDE_BOARD_H -#define __CONFIGS_ESC35_V1_INCLUDE_BOARD_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#ifndef __ASSEMBLY__ -# include -#endif -#include "stm32_rcc.h" -#include "stm32_sdio.h" -#include "stm32.h" - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* Clocking *************************************************************************/ - -/* HSI - 8 MHz RC factory-trimmed - * LSI - 40 KHz RC (30-60KHz, uncalibrated) - * HSE - On-board crystal frequency is 8MHz - * LSE - 32.768 kHz - */ - -#define STM32_BOARD_XTAL 8000000ul - -#define STM32_HSI_FREQUENCY 8000000ul -#define STM32_LSI_FREQUENCY 40000 -#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL -#define STM32_LSE_FREQUENCY 32768 - -/* PLL source is HSE/1, PLL multipler is 9: PLL frequency is 8MHz (XTAL) x 9 = 72MHz */ - -#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC -#define STM32_CFGR_PLLXTPRE 0 -#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx9 -#define STM32_PLL_FREQUENCY (9*STM32_BOARD_XTAL) - -/* Use the PLL and set the SYSCLK source to be the PLL */ - -#define STM32_SYSCLK_SW RCC_CFGR_SW_PLL -#define STM32_SYSCLK_SWS RCC_CFGR_SWS_PLL -#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY - -/* AHB clock (HCLK) is SYSCLK (72MHz) */ - -#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK -#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY -#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ - -/* APB2 clock (PCLK2) is HCLK (72MHz) */ - -#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK -#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY - -/* APB2 timer 1 will receive PCLK2. */ - -#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM15_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM16_CLKIN (STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM17_CLKIN (STM32_PCLK2_FREQUENCY) - -/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */ - -#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 -#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) - -/* APB1 timers 2-7 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_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB1_TIM7_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,15-7 are on APB2, others on APB1 - */ - -#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN -#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN -#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN -#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN -#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN -#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN -#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN -#define BOARD_TIM15_FREQUENCY STM32_APB2_TIM15_CLKIN -#define BOARD_TIM16_FREQUENCY STM32_APB2_TIM16_CLKIN -#define BOARD_TIM17_FREQUENCY STM32_APB2_TIM17_CLKIN - -/* USB divider -- Divide PLL clock by 1.5 */ - -#define STM32_CFGR_USBPRE 0 - - -#if defined(CONFIG_BOARD_USE_PROBES) -# define PROBE_N(n) (1<<((n)-1)) -# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL | GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) -# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL | GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN14) -# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL | GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15) - -# define PROBE_INIT(mask) \ - do { \ - if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ - if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ - if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ - } while(0) - -# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) -# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) -#else -# define PROBE_INIT(mask) -# define PROBE(n,s) -# define PROBE_MARK(n) -#endif - -/* Leds *************************************************************************/ - -/* LED index values for use with board_setled() */ - -#define BOARD_LED1 0 -#define BOARD_LED_RED BOARD_LED1 -#define BOARD_LED2 1 -#define BOARD_LED_GREEN BOARD_LED2 -#define BOARD_LED3 2 -#define BOARD_LED_BLUE BOARD_LED3 -#define BOARD_NLEDS 3 - -/* LED bits for use with board_setleds() */ - -#define BOARD_LED_RED_BIT (1 << BOARD_LED_RED) -#define BOARD_LED_GREEN_BIT (1 << BOARD_LED_GREEN) -#define BOARD_LED_BLUE_BIT (1 << BOARD_LED_BLUE) - -/* TODO:define these - * 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 as follows: - * - * SYMBOL Meaning LED state - * Red Green Blue - * ------------------------ -------------------------- ------ ------ ----*/ - -#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ -#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ -#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ -#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ -#define LED_INIRQ 4 /* In an interrupt N/C GLOW N/C */ -#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ -#define LED_ASSERTION 6 /* An assertion failed GLOW GLOW N/C */ -#define LED_PANIC 7 /* The system has crashed Blk OFF N/C */ -#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ - - -/* Led PWM */ - -#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 /* PA1 - Blue */ -#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_2 /* PA2 - Red */ -#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_2 /* PA3 - Green */ - -/************************************************************************************ - * 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 initialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -void stm32_boardinitialize(void); - -/************************************************************************************ - * Name: stm32_ledinit, stm32_setled, and stm32_setleds - * - * Description: - * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If - * CONFIG_ARCH_LEDS is not defined, then the following interfaces are available to - * control the LEDs from user applications. - * - ************************************************************************************/ - -#ifndef CONFIG_ARCH_LEDS -void stm32_led_initialize(void); -void stm32_setled(int led, bool ledon); -void stm32_setleds(uint8_t ledset); -#endif - -#if !defined(CONFIG_NSH_LIBRARY) -int app_archinitialize(void); -#else -#define app_archinitialize() (-ENOSYS) -#endif - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_ESC35_V1_INCLUDE_BOARD_H */ diff --git a/boards/auav/esc35-v1/nuttx-config/nsh/defconfig b/boards/auav/esc35-v1/nuttx-config/nsh/defconfig deleted file mode 100644 index ea8f46f06b..0000000000 --- a/boards/auav/esc35-v1/nuttx-config/nsh/defconfig +++ /dev/null @@ -1,116 +0,0 @@ -# CONFIG_DISABLE_OS_API is not set -# CONFIG_NSH_CMDOPT_HEXDUMP is not set -# CONFIG_NSH_DISABLE_DATE is not set -# CONFIG_NSH_DISABLE_PS is not set -# CONFIG_SERIAL is not set -CONFIG_ARCH="arm" -CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" -CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" -CONFIG_ARCH_CHIP_STM32=y -CONFIG_ARCH_CHIP_STM32F303CC=y -CONFIG_ARCH_INTERRUPTSTACK=4096 -CONFIG_ARCH_MATH_H=y -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARMV7M_MEMCPY=y -CONFIG_ARMV7M_USEBASEPRI=y -CONFIG_BOARDCTL_RESET=y -CONFIG_BOARD_CUSTOM_LEDS=y -CONFIG_BOARD_INITIALIZE=y -CONFIG_BOARD_LOOPSPERMSEC=5483 -CONFIG_BUILTIN=y -CONFIG_BUILTIN_PROXY_STACKSIZE=4096 -CONFIG_C99_BOOL8=y -CONFIG_CDCACM=y -CONFIG_CDCACM_BULKIN_REQLEN=96 -CONFIG_CDCACM_CONSOLE=y -CONFIG_CDCACM_PRODUCTSTR="AUAV ESC35" -CONFIG_CDCACM_RXBUFSIZE=256 -CONFIG_CDCACM_TXBUFSIZE=256 -CONFIG_CDCACM_VENDORSTR="Auav" -CONFIG_DEBUG_CUSTOMOPT=y -CONFIG_DEBUG_HARDFAULT_ALERT=y -CONFIG_DEBUG_OPTLEVEL="-Os" -CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEV_FIFO_SIZE=0 -CONFIG_DEV_PIPE_SIZE=70 -CONFIG_FDCLONE_STDIO=y -CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=y -CONFIG_IDLETHREAD_STACKSIZE=4096 -CONFIG_LIBC_FLOATINGPOINT=y -CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=16 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_MEMSET_64BIT=y -CONFIG_MEMSET_OPTSPEED=y -CONFIG_NAME_MAX=93 -CONFIG_NFILE_DESCRIPTORS=20 -CONFIG_NFILE_STREAMS=12 -CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_DISABLE_BASENAME=y -CONFIG_NSH_DISABLE_DIRNAME=y -CONFIG_NSH_DISABLE_PSSTACKUSAGE=y -CONFIG_NSH_DISABLE_REBOOT=y -CONFIG_NSH_DISABLE_TELNETD=y -CONFIG_NSH_DISABLE_TIME=y -CONFIG_NSH_DISABLE_WGET=y -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_LINELEN=128 -CONFIG_NSH_MAXARGUMENTS=12 -CONFIG_NSH_NESTDEPTH=8 -CONFIG_NSH_READLINE=y -CONFIG_NSH_STRERROR=y -CONFIG_PIPES=y -CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=4096 -CONFIG_PREALLOC_MQ_MSGS=4 -CONFIG_PREALLOC_TIMERS=20 -CONFIG_PREALLOC_WDOGS=20 -CONFIG_PRIORITY_INHERITANCE=y -CONFIG_PTHREAD_STACK_DEFAULT=4096 -CONFIG_PTHREAD_STACK_MIN=4096 -CONFIG_RAM_SIZE=131072 -CONFIG_RAM_START=0x20000000 -CONFIG_RAW_BINARY=y -CONFIG_READLINE_CMD_HISTORY=y -CONFIG_READLINE_CMD_HISTORY_LEN=4 -CONFIG_READLINE_CMD_HISTORY_LINELEN=64 -CONFIG_READLINE_TABCOMPLETION=y -CONFIG_SCHED_ATEXIT=y -CONFIG_SCHED_HPWORK=y -CONFIG_SCHED_HPWORKPRIORITY=192 -CONFIG_SCHED_HPWORKSTACKSIZE=4096 -CONFIG_SCHED_INSTRUMENTATION=y -CONFIG_SCHED_LPWORK=y -CONFIG_SCHED_LPWORKPRIORITY=50 -CONFIG_SCHED_LPWORKSTACKSIZE=4096 -CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y -CONFIG_SEM_NNESTPRIO=8 -CONFIG_SEM_PREALLOCHOLDERS=0 -CONFIG_SIG_SIGWORK=4 -CONFIG_STACK_COLORATION=y -CONFIG_START_DAY=30 -CONFIG_START_MONTH=11 -CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y -CONFIG_STM32_DMA1=y -CONFIG_STM32_DMA2=y -CONFIG_STM32_FORCEPOWER=y -CONFIG_STM32_JTAG_SW_ENABLE=y -CONFIG_STM32_PWR=y -CONFIG_STM32_TIM1=y -CONFIG_STM32_TIM2=y -CONFIG_STM32_USB=y -CONFIG_SYMTAB_ORDEREDBYNAME=y -CONFIG_SYSTEM_CDCACM=y -CONFIG_SYSTEM_NSH=y -CONFIG_TASK_NAME_SIZE=24 -CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=4096 -CONFIG_TIME_EXTENDED=y -CONFIG_USBDEV_BUSPOWERED=y -CONFIG_USBDEV_DUALSPEED=y -CONFIG_USBDEV_MAXPOWER=500 -CONFIG_USEC_PER_TICK=1000 -CONFIG_USERMAIN_STACKSIZE=4096 -CONFIG_USER_ENTRYPOINT="nsh_main" -CONFIG_WATCHDOG=y diff --git a/boards/auav/esc35-v1/nuttx-config/scripts/script.ld b/boards/auav/esc35-v1/nuttx-config/scripts/script.ld deleted file mode 100644 index 7a97b71f70..0000000000 --- a/boards/auav/esc35-v1/nuttx-config/scripts/script.ld +++ /dev/null @@ -1,154 +0,0 @@ -/**************************************************************************** - * configs/esc35-v1/scripts/ld.script - * - * Copyright (C) 2015 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 STM32F303CC has 256KiB of FLASH beginning at address 0x0800:0000 and - * 40KiB of SRAM beginning at address 0x2000:0000. With an addtional 8 KiB - * located at 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 bootloader uses only the first 16KiB of flash. - * Paramater storage will use the next 8 2KiB Sectors. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x08008000, LENGTH = 224K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 40K - ccsram (rwx): ORIGIN = 0x10000000, 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) - . = ALIGN(8); - /* - * This section positions the app_descriptor_t used - * by the make_can_boot_descriptor.py tool to set - * the application image's descriptor so that the - * uavcan bootloader has the ability to validate the - * image crc, size etc - */ - KEEP(*(.app_descriptor)) - *(.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(.); - - /* The STM32F303CC has 48KiB 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) - . = ALIGN(4); - _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/boards/auav/esc35-v1/src/CMakeLists.txt b/boards/auav/esc35-v1/src/CMakeLists.txt deleted file mode 100644 index 48721c0896..0000000000 --- a/boards/auav/esc35-v1/src/CMakeLists.txt +++ /dev/null @@ -1,46 +0,0 @@ -############################################################################ -# -# Copyright (c) 2016 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. -# -############################################################################ - -message(WARNING "Configuraton is incomplete") -message(WARNING "DO NOT RUN THIS ON HW") -message(WARNING "IT IS NOT PINED OUT TO HW") - -add_library(drivers_board - init.c - led.c - usb.c -) -target_link_libraries(drivers_board - PRIVATE - px4_layer -) diff --git a/boards/auav/esc35-v1/src/board_config.h b/boards/auav/esc35-v1/src/board_config.h deleted file mode 100644 index 39462805ef..0000000000 --- a/boards/auav/esc35-v1/src/board_config.h +++ /dev/null @@ -1,273 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 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 board_config.h - * - * ESC35v1 internal definitions - */ - -#pragma once - -/**************************************************************************************************** - * Included Files - ****************************************************************************************************/ - -#include -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -#if STM32_NSPI < 1 -# undef CONFIG_STM32_SPI1 -# undef CONFIG_STM32_SPI2 -#elif STM32_NSPI < 2 -# undef CONFIG_STM32_SPI2 -#endif - -/* High-resolution timer - */ -#define HRT_TIMER 3 /* use timer1 for the HRT */ -#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ - -/* GPIO *********************************************************************** - * - * GPIO Function MPU Board - * Pin # Name - * -- ----- -------------------------------- ---------------------- - * - * PB[6] PB06 42 nCAN_SILENT - */ - -#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR) - -#define GPIO_RC_PWM (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTA | GPIO_PIN0) - -#define GPIO_OC_ADJ (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN4 | GPIO_OUTPUT_CLEAR) -#define GPIO_EN_GATE (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR) -#define GPIO_DC_CAL (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN6 | GPIO_OUTPUT_CLEAR) - - -/* CAN ************************************************************************ * - * - * GPIO Function MPU Board - * Pin # Name - * -- ----- -------------------------------- ------------------------ - * - * PB[8] PB8/CAN_RX 45 CAN_RX - * PB[9] PB9/CAN_TX 46 CAN_TX - * - */ -#define GPIO_CAN1_RX GPIO_CAN_RX_3 -#define GPIO_CAN1_TX GPIO_CAN_TX_3 - -/* Analog *********************************************************************** - * - * GPIO Function MPU Board - * Pin # Name - * -- ----- -------------------------------- ---------------------- - * - * PC[00] PC0/ADC123_IN10 8 TEMP_SENS - * PC[01] PC1/ADC123_IN11/SPI3_MOSI/SPI2_MOSI 9 VBAT_SENS - * PC[02] PC2/ADC123_IN12/SPI2_MISO, 10 CURR_SENS2 - * PC[03] PC3/ADC123_IN13/SPI2_MOSI 11 CURR_SENS1 - * - */ - -/* LEDs *********************************************************************** - * - * GPIO Function MPU Board - * Pin # Name - * -- ----- -------------------------------- ---------------------- - * - * PC[07] PC7/TIM3_CH2/TIM8_CH2 38 LED_RED - * PC[08] PC8/TIM3_CH3/TIM8_CH3 39 LED_GREEN - * PC[09] PC9/TIM3_CH4/TIM8_CH4 40 LED_BLUE - */ - -#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN2 | GPIO_OUTPUT_CLEAR) -#define GPIO_LED_RED GPIO_LED1 - -#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN3 | GPIO_OUTPUT_CLEAR) -#define GPIO_LED_GREEN GPIO_LED2 - -#define GPIO_LED3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR) -#define GPIO_LED_BLUE GPIO_LED3 - -__BEGIN_DECLS - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_spiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins. - * - ************************************************************************************/ - -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || \ - defined(CONFIG_STM32_SPI3) -void weak_function board_spiinitialize(void); -#endif - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins. - * - ************************************************************************************/ - -void stm32_usbinitialize(void); - -/************************************************************************************ - * Name: stm32_usb_set_pwr_callback() - * - * Description: - * Called to setup set a call back for USB power state changes. - * - * Inputs: - * pwr_changed_handler: An interrupt handler that will be called on VBUS power - * state changes. - * - ************************************************************************************/ - -void stm32_usb_set_pwr_callback(xcpt_t pwr_changed_handler); - - -/**************************************************************************** - * Name: stm32_led_initialize - * - * Description: - * This functions is called very early in initialization to perform board- - * specific initialization of LED-related resources. This includes such - * things as, for example, configure GPIO pins to drive the LEDs and also - * putting the LEDs in their correct initial state. - * - * NOTE: In most architectures, LED initialization() is called from - * board-specific initialization and should, therefore, have the name - * _led_intialize(). But there are a few architectures where the - * LED initialization function is still called from common chip - * architecture logic. This interface is not, however, a common board - * interface in any event and the name board_autoled_initialization is - * deprecated. - * - * Input Parameters: - * None - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_ARCH_LEDS -void board_autoled_initialize(void); -#endif - -/************************************************************************************ - * Name: stm32_can_initialize - * - * Description: - * Called at application startup time to initialize the CAN functionality. - * - ************************************************************************************/ - -#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2)) -int board_can_initialize(void); -#endif - -/************************************************************************************ - * Name: board_button_initialize - * - * Description: - * Called at application startup time to initialize the Buttons functionality. - * - ************************************************************************************/ - -#if defined(CONFIG_ARCH_BUTTONS) -void board_button_initialize(void); -#endif - -/**************************************************************************** - * Name: usbmsc_archinitialize - * - * Description: - * Called from the application system/usbmc or the boards_nsh if the - * application is not included. - * Perform architecture specific initialization. This function must - * configure the block device to export via USB. This function must be - * provided by architecture-specific logic in order to use this add-on. - * - ****************************************************************************/ - -#if !defined(CONFIG_NSH_BUILTIN_APPS) && !defined(CONFIG_SYSTEM_USBMSC) -int usbmsc_archinitialize(void); -#endif - -/**************************************************************************** - * Name: composite_archinitialize - * - * Description: - * Called from the application system/composite or the boards_nsh if the - * application is not included. - * Perform architecture specific initialization. This function must - * configure the block device to export via USB. This function must be - * provided by architecture-specific logic in order to use this add-on. - * - ****************************************************************************/ - -#if !defined(CONFIG_NSH_BUILTIN_APPS) && !defined(CONFIG_SYSTEM_COMPOSITE) -extern int composite_archinitialize(void); -#endif - -#include - -#endif /* __ASSEMBLY__ */ - -__END_DECLS diff --git a/boards/auav/esc35-v1/src/init.c b/boards/auav/esc35-v1/src/init.c deleted file mode 100644 index e8501f11bd..0000000000 --- a/boards/auav/esc35-v1/src/init.c +++ /dev/null @@ -1,210 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 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 px4flow_init.c - * - * PX4ESC-specific early startup code. This file implements the - * board_app_initialize() 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 initialization. - */ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include "board_config.h" -#include "stm32_uart.h" - -#include - -#include -#include - -#include - -#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) -#endif - -# if defined(FLASH_BASED_PARAMS) -# include -#endif - -#include "board_config.h" - -/* todo: This is constant but not proper */ -__BEGIN_DECLS -extern void led_off(int led); -__END_DECLS - - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ -/* Configuration ************************************************************/ - -/* Debug ********************************************************************/ - -/**************************************************************************** - * 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 initialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -__EXPORT void stm32_boardinitialize(void) -{ - /* configure LEDs */ - - board_autoled_initialize(); - -#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || \ - defined(CONFIG_STM32_SPI3) - board_spiinitialize(); -#endif -} - - -__EXPORT void board_initialize(void) -{ -} - -static void hrt_calls_this(void) -{ - -} - -/**************************************************************************** - * Name: board_app_initialize - * - * Description: - * Perform application specific initialization. This function is never - * called directly from application code, but only indirectly via the - * (non-standard) boardctl() interface using the command BOARDIOC_INIT. - * - * Input Parameters: - * arg - The boardctl() argument is passed to the board_app_initialize() - * implementation without modification. The argument has no - * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initalization logic and the the - * matching application logic. The value cold be such things as a - * mode enumeration value, a set of DIP switch switch settings, a - * pointer to configuration data read from a file or serial FLASH, - * or whatever you would like to do with it. Every implementation - * should accept zero/NULL as a default configuration. - * - * Returned Value: - * Zero (OK) is returned on success; a negated errno value is returned on - * any failure to indicate the nature of the failure. - * - ****************************************************************************/ - -__EXPORT int board_app_initialize(uintptr_t arg) -{ - int result = OK; - - - px4_platform_init(); - - /* set up the serial DMA polling */ - static struct hrt_call serial_dma_call; - struct timespec ts; - - /* - * Poll at 1ms intervals for received bytes that have not triggered - * a DMA event. - */ - ts.tv_sec = 0; - ts.tv_nsec = 1000000; - - hrt_call_every(&serial_dma_call, - ts_to_abstime(&ts), - ts_to_abstime(&ts), - (hrt_callout)hrt_calls_this, - NULL); - -#if defined(FLASH_BASED_PARAMS) - static sector_descriptor_t sector_map[] = { - {1, 2 * 1024, 0x08004000}, - {2, 2 * 1024, 0x08004800}, - {3, 2 * 1024, 0x08005000}, - {4, 2 * 1024, 0x08005800}, - {5, 2 * 1024, 0x08006000}, - {6, 2 * 1024, 0x08006800}, - {7, 2 * 1024, 0x08007000}, - {8, 2 * 1024, 0x08007800}, - {0, 0, 0}, - }; - static uint8_t param_buffer[PARAMETER_BUFFER_SIZE]; - - parameter_flashfs_init(sector_map, param_buffer, sizeof(param_buffer)); -#endif - return result; -} - - -__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const uint8_t *filename, int lineno) -{ -} - -__EXPORT int fsync(int fd) -{ - return 0; -} diff --git a/boards/auav/esc35-v1/src/led.c b/boards/auav/esc35-v1/src/led.c deleted file mode 100644 index 53f0412e4e..0000000000 --- a/boards/auav/esc35-v1/src/led.c +++ /dev/null @@ -1,192 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 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 px4esc_led.c - * - * PX4ESC LED backend. - */ - -#include - -#include -#include - -#include "stm32.h" -#include "board_config.h" - -#include - -#include - -/* - * Ideally we'd be able to get these from up_internal.h, - * but since we want to be able to disable the NuttX use - * of leds for system indication at will and there is no - * separate switch, we need to build independent of the - * CONFIG_ARCH_LEDS configuration switch. - */ -__BEGIN_DECLS -extern void led_init(void); -extern void led_on(int led); -extern void led_off(int led); -extern void led_toggle(int led); -__END_DECLS - -static uint32_t g_ledmap[] = { - GPIO_LED_RED, // Indexed by BOARD_LED_RED - GPIO_LED_GREEN, // Indexed by BOARD_LED_GREEN - GPIO_LED_BLUE, // Indexed by BOARD_LED_BLUE -}; - -__EXPORT void led_init(void) -{ - /* Configure LED GPIOs for output */ - for (size_t l = 0; l < arraySize(g_ledmap); l++) { - stm32_configgpio(g_ledmap[l]); - } -} - -__EXPORT void board_autoled_initialize(void) -{ - led_init(); -} - -static void phy_set_led(int led, bool state) -{ - /* Pull Down to switch on */ - stm32_gpiowrite(g_ledmap[led], !state); -} - -static bool phy_get_led(int led) -{ - - return !stm32_gpioread(g_ledmap[led]); -} - -__EXPORT void led_on(int led) -{ - phy_set_led(led, true); -} - -__EXPORT void led_off(int led) -{ - phy_set_led(led, false); -} - -__EXPORT void led_toggle(int led) -{ - - phy_set_led(led, !phy_get_led(led)); -} - -static bool g_initialized; - -// Nuttx Usages - -__EXPORT -void board_autoled_on(int led) -{ - switch (led) { - default: - case LED_STARTED: - case LED_HEAPALLOCATE: - phy_set_led(BOARD_LED_BLUE, true); - break; - - case LED_IRQSENABLED: - phy_set_led(BOARD_LED_GREEN, true); - break; - - case LED_STACKCREATED: - phy_set_led(BOARD_LED_GREEN, true); - phy_set_led(BOARD_LED_BLUE, true); - g_initialized = true; - break; - - case LED_INIRQ: - case LED_SIGNAL: - phy_set_led(BOARD_LED_GREEN, true); - break; - - case LED_ASSERTION: - phy_set_led(BOARD_LED_RED, true); - phy_set_led(BOARD_LED_GREEN, true); - break; - - case LED_PANIC: - phy_set_led(BOARD_LED_RED, true); - break; - - case LED_IDLE : /* IDLE */ - phy_set_led(BOARD_LED_RED, true); - phy_set_led(BOARD_LED_BLUE, true); - break; - } -} - -/**************************************************************************** - * Name: board_autoled_off - ****************************************************************************/ - - -__EXPORT void board_autoled_off(int led) -{ - switch (led) { - default: - case LED_STARTED: - case LED_HEAPALLOCATE: - case LED_IRQSENABLED: - phy_set_led(BOARD_LED_BLUE, false); - - case LED_STACKCREATED: - break; - - case LED_INIRQ: - case LED_SIGNAL: - case LED_ASSERTION: - phy_set_led(BOARD_LED_RED, false); - phy_set_led(BOARD_LED_GREEN, false); - - break; - - case LED_PANIC: - phy_set_led(BOARD_LED_RED, false); - phy_set_led(BOARD_LED_GREEN, false); - break; - - case LED_IDLE: /* IDLE */ - phy_set_led(BOARD_LED_GREEN, g_initialized); - break; - } -} diff --git a/boards/auav/esc35-v1/src/usb.c b/boards/auav/esc35-v1/src/usb.c deleted file mode 100644 index 3495658b66..0000000000 --- a/boards/auav/esc35-v1/src/usb.c +++ /dev/null @@ -1,102 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2015 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 px4esc_usb.c - * - * Board-specific USB functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include -#include "board_config.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the PX4FMU board. - * - ************************************************************************************/ - -__EXPORT void stm32_usbinitialize(void) -{ -} - -int stm32_usbpullup(FAR struct usbdev_s *dev, bool enable) -{ - usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); - return OK; -} - -/************************************************************************************ - * Name: stm32_usbsuspend - * - * Description: - * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is - * used. This function is called whenever the USB enters or leaves suspend mode. - * This is an opportunity for the board logic to shutdown clocks, power, etc. - * while the USB is suspended. - * - ************************************************************************************/ - -__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) -{ - uinfo("resume: %d\n", resume); -}