diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 411016f238..a5d412fe21 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -44,7 +44,7 @@ pipeline { ] def nuttx_builds_other = [ - target: ["px4_esc-v1_default", "thiemar_s2740vc-v1_default"], + target: ["px4_esc-v1_default"], image: docker_images.nuttx, archive: false ] diff --git a/Makefile b/Makefile index 60b65c4e56..2f6951fb16 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_thiemar_s2740vc-v1_default \ sizes # builds with RTPS diff --git a/boards/thiemar/s2740vc-v1/default.cmake b/boards/thiemar/s2740vc-v1/default.cmake deleted file mode 100644 index 7b134ba548..0000000000 --- a/boards/thiemar/s2740vc-v1/default.cmake +++ /dev/null @@ -1,50 +0,0 @@ - -add_definitions( - -DPARAM_NO_ORB - -DPARAM_NO_AUTOSAVE - ) - -# 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/s2740vc-v1) - -# N.B. this would be uncommented when there is an APP -#include(px4_make_uavcan_bootloader) -#px4_make_uavcan_bootloadable(BOARD ${PX4_BOARD} -# BIN ${PX4_BINARY_DIR}/platforms/nuttx/s2740vc-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 thiemar - MODEL s2740vc-v1 - TOOLCHAIN arm-none-eabi - ARCHITECTURE cortex-m4 - - DRIVERS - bootloaders - #uavcannode - - MODULES - - SYSTEMCMDS - config - reboot - top - ver - work_queue - - ) diff --git a/boards/thiemar/s2740vc-v1/firmware.prototype b/boards/thiemar/s2740vc-v1/firmware.prototype deleted file mode 100644 index 7fbc67dd14..0000000000 --- a/boards/thiemar/s2740vc-v1/firmware.prototype +++ /dev/null @@ -1,13 +0,0 @@ -{ - "board_id": 23, - "magic": "S2740VCblv1", - "description": "Firmware for the S2740VC board", - "image": "", - "build_time": 0, - "summary": "S2740VCv1", - "version": "0.1", - "image_size": 0, - "image_maxsize": 65536, - "git_identity": "", - "board_revision": 0 -} diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/include/README.txt b/boards/thiemar/s2740vc-v1/nuttx-config/include/README.txt deleted file mode 100644 index 15a113781d..0000000000 --- a/boards/thiemar/s2740vc-v1/nuttx-config/include/README.txt +++ /dev/null @@ -1,2 +0,0 @@ -This directory contains header files unique to the -S2740VC board using STM32F302K8 diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/include/board.h b/boards/thiemar/s2740vc-v1/nuttx-config/include/board.h deleted file mode 100644 index ab5612cba6..0000000000 --- a/boards/thiemar/s2740vc-v1/nuttx-config/include/board.h +++ /dev/null @@ -1,186 +0,0 @@ -/************************************************************************************ - * configs/s2740vc/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_S2740VC_INCLUDE_BOARD_H -#define __CONFIGS_S2740VC_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 - -#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PA10 */ -#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PA9 */ - -/* Probes unused */ -#define PROBE_INIT(mask) -#define PROBE(n,s) -#define PROBE_MARK(n) - -/************************************************************************************ - * 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); - -#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_S2740VC_INCLUDE_BOARD_H */ diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/nsh/IMPORTANT_README.txt b/boards/thiemar/s2740vc-v1/nuttx-config/nsh/IMPORTANT_README.txt deleted file mode 100644 index d6ecdb23e2..0000000000 --- a/boards/thiemar/s2740vc-v1/nuttx-config/nsh/IMPORTANT_README.txt +++ /dev/null @@ -1 +0,0 @@ -N.B. The nsh build is not complete - it will build but is not pinied out to the HW DO NOT ATTEMPT TO RUN IT! diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/nsh/defconfig b/boards/thiemar/s2740vc-v1/nuttx-config/nsh/defconfig deleted file mode 100644 index 22aa699038..0000000000 --- a/boards/thiemar/s2740vc-v1/nuttx-config/nsh/defconfig +++ /dev/null @@ -1,106 +0,0 @@ -# -# This file is autogenerated: PLEASE DO NOT EDIT IT. -# -# You can use "make menuconfig" to make any modifications to the installed .config file. -# You can then do "make savedefconfig" to generate a new defconfig file that includes your -# modifications. -# -# CONFIG_ARCH_FPU is not set -# CONFIG_DEV_NULL is not set -# CONFIG_DISABLE_OS_API is not set -# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set -CONFIG_ARCH="arm" -CONFIG_ARCH_BOARD_CUSTOM=y -CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" -CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y -CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" -CONFIG_ARCH_CHIP="stm32" -CONFIG_ARCH_CHIP_STM32=y -CONFIG_ARCH_CHIP_STM32F302K8=y -CONFIG_ARCH_INTERRUPTSTACK=1024 -CONFIG_ARCH_STACKDUMP=y -CONFIG_ARMV7M_MEMCPY=y -CONFIG_ARMV7M_USEBASEPRI=y -CONFIG_BOARDCTL_RESET=y -CONFIG_BOARD_LOOPSPERMSEC=5483 -CONFIG_BUILTIN=y -CONFIG_BUILTIN_PROXY_STACKSIZE=392 -CONFIG_C99_BOOL8=y -CONFIG_CLOCK_MONOTONIC=y -CONFIG_DEBUG_CUSTOMOPT=y -CONFIG_DEBUG_HARDFAULT_ALERT=y -CONFIG_DEBUG_OPTLEVEL="-Os" -CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEFAULT_SMALL=y -CONFIG_EXAMPLES_NULL=y -CONFIG_FDCLONE_STDIO=y -CONFIG_GRAN=y -CONFIG_GRAN_INTR=y -CONFIG_HAVE_CXX=y -CONFIG_HAVE_CXXINITIALIZE=y -CONFIG_LIBC_LONG_LONG=y -CONFIG_LIBC_STRERROR=y -CONFIG_LIB_BOARDCTL=y -CONFIG_LIB_SENDFILE_BUFSIZE=0 -CONFIG_MAX_TASKS=4 -CONFIG_MAX_WDOGPARMS=2 -CONFIG_MEMSET_64BIT=y -CONFIG_MEMSET_OPTSPEED=y -CONFIG_MM_REGIONS=2 -CONFIG_MQ_MAXMSGSIZE=8 -CONFIG_NAME_MAX=8 -CONFIG_NFILE_DESCRIPTORS=5 -CONFIG_NFILE_STREAMS=1 -CONFIG_NPTHREAD_KEYS=0 -CONFIG_NXFONTS_DISABLE_16BPP=y -CONFIG_NXFONTS_DISABLE_1BPP=y -CONFIG_NXFONTS_DISABLE_24BPP=y -CONFIG_NXFONTS_DISABLE_2BPP=y -CONFIG_NXFONTS_DISABLE_32BPP=y -CONFIG_NXFONTS_DISABLE_4BPP=y -CONFIG_NXFONTS_DISABLE_8BPP=y -CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=768 -CONFIG_PREALLOC_MQ_MSGS=4 -CONFIG_PREALLOC_TIMERS=2 -CONFIG_PREALLOC_WDOGS=4 -CONFIG_PRIORITY_INHERITANCE=y -CONFIG_PTHREAD_MUTEX_ROBUST=y -CONFIG_PTHREAD_STACK_DEFAULT=768 -CONFIG_RAM_SIZE=16384 -CONFIG_RAM_START=0x20000000 -CONFIG_RAW_BINARY=y -CONFIG_SCHED_ATEXIT=y -CONFIG_SCHED_INSTRUMENTATION=y -CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y -CONFIG_SEM_NNESTPRIO=4 -CONFIG_SEM_PREALLOCHOLDERS=4 -CONFIG_SIG_DEFAULT=y -CONFIG_SIG_SIGALRM_ACTION=y -CONFIG_SIG_SIGUSR1_ACTION=y -CONFIG_SIG_SIGUSR2_ACTION=y -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_FLOWCONTROL_BROKEN=y -CONFIG_STM32_FORCEPOWER=y -CONFIG_STM32_JTAG_FULL_ENABLE=y -CONFIG_STM32_PWR=y -CONFIG_STM32_SERIALBRK_BSDCOMPAT=y -CONFIG_STM32_SERIAL_DISABLE_REORDERING=y -CONFIG_STM32_TIM3=y -CONFIG_STM32_USART1=y -CONFIG_STM32_USART_BREAKS=y -CONFIG_STM32_USART_SINGLEWIRE=y -CONFIG_SYSTEM_READLINE=y -CONFIG_TASK_NAME_SIZE=12 -CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=768 -CONFIG_USART1_RXBUFSIZE=32 -CONFIG_USART1_RXDMA=y -CONFIG_USART1_SERIAL_CONSOLE=y -CONFIG_USART1_TXBUFSIZE=32 -CONFIG_USER_ENTRYPOINT="null_main" -CONFIG_WDOG_INTRESERVE=2 diff --git a/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld b/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld deleted file mode 100644 index 5d92a06ccb..0000000000 --- a/boards/thiemar/s2740vc-v1/nuttx-config/scripts/script.ld +++ /dev/null @@ -1,142 +0,0 @@ -/**************************************************************************** - * configs/s2740vc-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 STM32F302K8 has 64KiB of FLASH beginning at address 0x0800:0000 and - * 16KiB 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 = 0x08000000, LENGTH = 64K - sram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K -} - -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(.); - - /* The STM32F302K8 has 16Kb 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/thiemar/s2740vc-v1/src/CMakeLists.txt b/boards/thiemar/s2740vc-v1/src/CMakeLists.txt deleted file mode 100644 index 20a1df3f1c..0000000000 --- a/boards/thiemar/s2740vc-v1/src/CMakeLists.txt +++ /dev/null @@ -1,46 +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. -# -############################################################################ - -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 - can.c - init.c -) - -target_link_libraries(drivers_board - PRIVATE - px4_layer -) diff --git a/boards/thiemar/s2740vc-v1/src/board_config.h b/boards/thiemar/s2740vc-v1/src/board_config.h deleted file mode 100644 index 64af68fd9e..0000000000 --- a/boards/thiemar/s2740vc-v1/src/board_config.h +++ /dev/null @@ -1,130 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-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 board_config.h - * - * S2740VCv1 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 1 /* use timer1 for the HRT */ -#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ -#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ -#define GPIO_PPM_IN (GPIO_ALT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN12) - -/* CAN *************************************************************************** - * - * GPIO Function MPU Board - * Pin # Name - * -- ----- -------------------------------- ---------------------------- - * - * PA[11] PA11/CAN_RX 21 CAN_RX - * PA[12] PA12/CAN_TX 22 CAN_TX - * PB[6] PB06 29 nCAN_SILENT - */ - -#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR) - - -__BEGIN_DECLS - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * 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: 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/thiemar/s2740vc-v1/src/can.c b/boards/thiemar/s2740vc-v1/src/can.c deleted file mode 100644 index 862c1cceed..0000000000 --- a/boards/thiemar/s2740vc-v1/src/can.c +++ /dev/null @@ -1,131 +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 pxesc_can.c - * - * Board-specific CAN functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include - -#include -#include - -#include "chip.h" -#include "up_arch.h" - -#include "stm32.h" -#include "stm32_can.h" -#include "board_config.h" - -#if defined(CONFIG_CAN) - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ -/* Configuration ********************************************************************/ -/* The STM32F107VC supports CAN1 and CAN2 */ - -#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) -# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." -# undef CONFIG_STM32_CAN2 -#endif - -#ifdef CONFIG_STM32_CAN1 -# define CAN_PORT 1 -#else -# define CAN_PORT 2 -#endif - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ -int can_devinit(void); - -/************************************************************************************ - * Name: can_devinit - * - * Description: - * All STM32 architectures must provide the following interface to work with - * examples/can. - * - ************************************************************************************/ - -__EXPORT int can_devinit(void) -{ - static bool initialized = false; - struct can_dev_s *can; - int ret; - - /* Check if we have already initialized */ - - if (!initialized) { - /* Call stm32_caninitialize() to get an instance of the CAN interface */ - - can = stm32_caninitialize(CAN_PORT); - - if (can == NULL) { - canerr("ERROR: Failed to get CAN interface\n"); - return -ENODEV; - } - - /* Register the CAN driver at "/dev/can0" */ - - ret = can_register("/dev/can0", can); - - if (ret < 0) { - canerr("ERROR: can_register failed: %d\n", ret); - return ret; - } - - /* Now we are initialized */ - - initialized = true; - } - - return OK; -} - -#endif /* CONFIG_CAN && CONFIG_STM32_CAN1 */ diff --git a/boards/thiemar/s2740vc-v1/src/init.c b/boards/thiemar/s2740vc-v1/src/init.c deleted file mode 100644 index 3f8a729251..0000000000 --- a/boards/thiemar/s2740vc-v1/src/init.c +++ /dev/null @@ -1,169 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-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 s2740vc_init.c - * - * S2740VCv1-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 - -#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) -{ - stm32_configgpio(GPIO_CAN_SILENT); -} - - -__EXPORT void board_initialize(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)stm32_serial_dma_poll, - NULL); - - return result; -}