Adding s2740vc-v1 board and bootloader

This commit is contained in:
David Sidrane 2016-12-12 12:29:49 -10:00 committed by Lorenz Meier
parent 6ce7ade2c6
commit 276bf47865
26 changed files with 4395 additions and 0 deletions

View File

@ -0,0 +1,12 @@
{
"board_id": 23,
"magic": "S2740VCblv1",
"description": "Firmware for the S2740VC board",
"image": "",
"build_time": 0,
"summary": "S2740VCv1",
"version": "0.1",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,30 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader)
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/)
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/)
set(px4_module_base ${px4_src_base}modules/)
#
# UAVCAN boot loadable Module ID
#
# Bring in common uavcan hardware identity definitions
#
include(configs/uavcan_board_ident/s2740vc-v1)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
set(config_module_list
drivers/boards/s2740vc-v1/bootloader
)
#
# Bootloaders use a compact vector table not
# from the lib, but exported in startup
#
set(nuttx_startup_files stm32_vectors.o)

View File

@ -0,0 +1,67 @@
include(nuttx/px4_impl_nuttx)
add_definitions(-DPARAM_NO_ORB)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh)
#
# UAVCAN boot loadable Module ID
set(uavcanblid_sw_version_major 0)
set(uavcanblid_sw_version_minor 1)
#
# Bring in common uavcan hardware identity definitions
#
include(configs/uavcan_board_ident/s2740vc-v1)
# N.B. this would be uncommented when there is an APP
#px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
# BIN ${CMAKE_CURRENT_BINARY_DIR}/src/firmware/nuttx/firmware_nuttx.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})
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
set(config_module_list
#
# Board support modules
#
drivers/stm32
drivers/led
drivers/boards/s2740vc-v1
#
# System commands
#
systemcmds/reboot
systemcmds/top
systemcmds/config
systemcmds/ver
#
# General system control
#
#
# Library modules
#
modules/param
modules/systemlib
#
# Libraries
#
# had to add for cmake, not sure why wasn't in original config
platforms/nuttx
platforms/common
platforms/nuttx/px4_layer
)

View File

@ -0,0 +1,8 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
if CONFIG_ARCH_BOARD_S2740VC_V1
endif

View File

@ -0,0 +1,164 @@
############################################################################
# configs/s2740vc/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# 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}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_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${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
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 = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.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)/scripts/$(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)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(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}
# Optimization 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 = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
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 =
LDFLAGS += --wrap up_svcall

View File

@ -0,0 +1,184 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* 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.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
S2740VC - v1.2 STM32F302K8U6
esc35 - v1.0 STM32F303CC
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

View File

@ -0,0 +1,911 @@
#
# Automatically generated file; DO NOT EDIT.
# Nuttx/ Configuration
#
#
# Build Setup
#
# CONFIG_EXPERIMENTAL is not set
CONFIG_DEFAULT_SMALL=y
CONFIG_HOST_LINUX=y
# CONFIG_HOST_OSX is not set
# CONFIG_HOST_WINDOWS is not set
# CONFIG_HOST_OTHER is not set
#
# Build Configuration
#
CONFIG_APPS_DIR="../apps"
CONFIG_BUILD_FLAT=y
# 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
# CONFIG_UBOOT_UIMAGE is not set
#
# Customize Header Files
#
# CONFIG_ARCH_STDINT_H is not set
# CONFIG_ARCH_STDBOOL_H is not set
# CONFIG_ARCH_MATH_H is not set
# CONFIG_ARCH_FLOAT_H is not set
# CONFIG_ARCH_STDARG_H is not set
# CONFIG_ARCH_DEBUG_H is not set
#
# Debug Options
#
# CONFIG_DEBUG_ALERT is not set
# CONFIG_DEBUG_FEATURES is not set
CONFIG_ARCH_HAVE_STACKCHECK=y
# CONFIG_STACK_COLORATION is not set
CONFIG_ARCH_HAVE_HEAPCHECK=y
# CONFIG_HEAP_COLORATION is not set
CONFIG_DEBUG_SYMBOLS=y
CONFIG_ARCH_HAVE_CUSTOMOPT=y
# CONFIG_DEBUG_NOOPT is not set
CONFIG_DEBUG_CUSTOMOPT=y
# CONFIG_DEBUG_FULLOPT is not set
CONFIG_DEBUG_OPTLEVEL="-Os"
#
# System Type
#
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_A1X is not set
# CONFIG_ARCH_CHIP_C5471 is not set
# CONFIG_ARCH_CHIP_CALYPSO is not set
# CONFIG_ARCH_CHIP_DM320 is not set
# CONFIG_ARCH_CHIP_EFM32 is not set
# CONFIG_ARCH_CHIP_IMX1 is not set
# CONFIG_ARCH_CHIP_IMX6 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_TIVA is not set
# CONFIG_ARCH_CHIP_LPC11XX 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_SAMA5 is not set
# CONFIG_ARCH_CHIP_SAMD is not set
# CONFIG_ARCH_CHIP_SAML is not set
# CONFIG_ARCH_CHIP_SAM34 is not set
# CONFIG_ARCH_CHIP_SAMV7 is not set
CONFIG_ARCH_CHIP_STM32=y
# CONFIG_ARCH_CHIP_STM32F7 is not set
# CONFIG_ARCH_CHIP_STM32L4 is not set
# CONFIG_ARCH_CHIP_STR71X is not set
# CONFIG_ARCH_CHIP_TMS570 is not set
# CONFIG_ARCH_CHIP_MOXART is not set
# CONFIG_ARCH_ARM7TDMI is not set
# CONFIG_ARCH_ARM926EJS is not set
# CONFIG_ARCH_ARM920T is not set
# CONFIG_ARCH_CORTEXM0 is not set
# CONFIG_ARCH_CORTEXM3 is not set
CONFIG_ARCH_CORTEXM4=y
# CONFIG_ARCH_CORTEXM7 is not set
# CONFIG_ARCH_CORTEXA5 is not set
# CONFIG_ARCH_CORTEXA8 is not set
# CONFIG_ARCH_CORTEXA9 is not set
# CONFIG_ARCH_CORTEXR4 is not set
# CONFIG_ARCH_CORTEXR4F is not set
# CONFIG_ARCH_CORTEXR5 is not set
# CONFIG_ARCH_CORTEX5F is not set
# CONFIG_ARCH_CORTEXR7 is not set
# CONFIG_ARCH_CORTEXR7F is not set
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="stm32"
# CONFIG_ARM_TOOLCHAIN_IAR is not set
CONFIG_ARM_TOOLCHAIN_GNU=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARCH_HAVE_CMNVECTOR=y
# CONFIG_ARMV7M_CMNVECTOR is not set
# CONFIG_ARMV7M_LAZYFPU is not set
CONFIG_ARCH_HAVE_FPU=y
# CONFIG_ARCH_HAVE_DPFPU is not set
# CONFIG_ARCH_FPU is not set
# CONFIG_ARCH_HAVE_TRUSTZONE is not set
CONFIG_ARM_HAVE_MPU_UNIFIED=y
# CONFIG_ARM_MPU is not set
#
# ARMV7M Configuration Options
#
# CONFIG_ARMV7M_HAVE_ICACHE is not set
# CONFIG_ARMV7M_HAVE_DCACHE is not set
# CONFIG_ARMV7M_HAVE_ITCM is not set
# CONFIG_ARMV7M_HAVE_DTCM is not set
# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y
CONFIG_ARMV7M_HAVE_STACKCHECK=y
# CONFIG_ARMV7M_STACKCHECK is not set
# CONFIG_ARMV7M_ITMSYSLOG 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_STM32L162ZD is not set
# CONFIG_ARCH_CHIP_STM32L162VE 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_STM32F102CB is not set
# CONFIG_ARCH_CHIP_STM32F103T8 is not set
# CONFIG_ARCH_CHIP_STM32F103TB is not set
# CONFIG_ARCH_CHIP_STM32F103C4 is not set
# CONFIG_ARCH_CHIP_STM32F103C8 is not set
# CONFIG_ARCH_CHIP_STM32F103CB is not set
# CONFIG_ARCH_CHIP_STM32F103R8 is not set
# CONFIG_ARCH_CHIP_STM32F103RB is not set
# CONFIG_ARCH_CHIP_STM32F103RC is not set
# CONFIG_ARCH_CHIP_STM32F103RD is not set
# CONFIG_ARCH_CHIP_STM32F103RE is not set
# CONFIG_ARCH_CHIP_STM32F103RG is not set
# CONFIG_ARCH_CHIP_STM32F103V8 is not set
# CONFIG_ARCH_CHIP_STM32F103VB is not set
# CONFIG_ARCH_CHIP_STM32F103VC is not set
# CONFIG_ARCH_CHIP_STM32F103VE is not set
# CONFIG_ARCH_CHIP_STM32F103ZE is not set
# CONFIG_ARCH_CHIP_STM32F105VB is not set
# CONFIG_ARCH_CHIP_STM32F105RB is not set
# CONFIG_ARCH_CHIP_STM32F107VC is not set
# CONFIG_ARCH_CHIP_STM32F205RG is not set
# CONFIG_ARCH_CHIP_STM32F207IG is not set
# CONFIG_ARCH_CHIP_STM32F207ZE is not set
# CONFIG_ARCH_CHIP_STM32F302K6 is not set
CONFIG_ARCH_CHIP_STM32F302K8=y
# 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_STM32F303K6 is not set
# CONFIG_ARCH_CHIP_STM32F303K8 is not set
# CONFIG_ARCH_CHIP_STM32F303C6 is not set
# CONFIG_ARCH_CHIP_STM32F303C8 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_STM32F303RD is not set
# CONFIG_ARCH_CHIP_STM32F303RE is not set
# CONFIG_ARCH_CHIP_STM32F303VB is not set
# CONFIG_ARCH_CHIP_STM32F303VC is not set
# CONFIG_ARCH_CHIP_STM32F372C8 is not set
# CONFIG_ARCH_CHIP_STM32F372R8 is not set
# CONFIG_ARCH_CHIP_STM32F372V8 is not set
# CONFIG_ARCH_CHIP_STM32F372CB is not set
# CONFIG_ARCH_CHIP_STM32F372RB is not set
# CONFIG_ARCH_CHIP_STM32F372VB is not set
# CONFIG_ARCH_CHIP_STM32F372CC is not set
# CONFIG_ARCH_CHIP_STM32F372RC is not set
# CONFIG_ARCH_CHIP_STM32F372VC is not set
# CONFIG_ARCH_CHIP_STM32F373C8 is not set
# CONFIG_ARCH_CHIP_STM32F373R8 is not set
# CONFIG_ARCH_CHIP_STM32F373V8 is not set
# CONFIG_ARCH_CHIP_STM32F373CB is not set
# CONFIG_ARCH_CHIP_STM32F373RB is not set
# CONFIG_ARCH_CHIP_STM32F373VB is not set
# CONFIG_ARCH_CHIP_STM32F373CC is not set
# CONFIG_ARCH_CHIP_STM32F373RC is not set
# CONFIG_ARCH_CHIP_STM32F373VC is not set
# CONFIG_ARCH_CHIP_STM32F401RE is not set
# CONFIG_ARCH_CHIP_STM32F411RE is not set
# CONFIG_ARCH_CHIP_STM32F411VE 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 is not set
# CONFIG_ARCH_CHIP_STM32F427Z is not set
# CONFIG_ARCH_CHIP_STM32F427I is not set
# CONFIG_ARCH_CHIP_STM32F429V is not set
# CONFIG_ARCH_CHIP_STM32F429Z is not set
# CONFIG_ARCH_CHIP_STM32F429I is not set
# CONFIG_ARCH_CHIP_STM32F429B is not set
# CONFIG_ARCH_CHIP_STM32F429N is not set
# CONFIG_ARCH_CHIP_STM32F446M is not set
# CONFIG_ARCH_CHIP_STM32F446R is not set
# CONFIG_ARCH_CHIP_STM32F446V is not set
# CONFIG_ARCH_CHIP_STM32F446Z is not set
# CONFIG_ARCH_CHIP_STM32F469A is not set
# CONFIG_ARCH_CHIP_STM32F469I is not set
# CONFIG_ARCH_CHIP_STM32F469B is not set
# CONFIG_ARCH_CHIP_STM32F469N is not set
CONFIG_STM32_FLASH_CONFIG_DEFAULT=y
# CONFIG_STM32_FLASH_CONFIG_4 is not set
# CONFIG_STM32_FLASH_CONFIG_6 is not set
# CONFIG_STM32_FLASH_CONFIG_8 is not set
# CONFIG_STM32_FLASH_CONFIG_B is not set
# CONFIG_STM32_FLASH_CONFIG_C is not set
# CONFIG_STM32_FLASH_CONFIG_D is not set
# CONFIG_STM32_FLASH_CONFIG_E is not set
# CONFIG_STM32_FLASH_CONFIG_F is not set
# CONFIG_STM32_FLASH_CONFIG_G is not set
# CONFIG_STM32_FLASH_CONFIG_I 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_USBACCESSLINE 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_STM32F205 is not set
# CONFIG_STM32_STM32F207 is not set
CONFIG_STM32_STM32F30XX=y
CONFIG_STM32_STM32F302=y
# CONFIG_STM32_STM32F303 is not set
# CONFIG_STM32_STM32F37XX is not set
# CONFIG_STM32_STM32F40XX is not set
# CONFIG_STM32_STM32F401 is not set
# CONFIG_STM32_STM32F411 is not set
# CONFIG_STM32_STM32F405 is not set
# CONFIG_STM32_STM32F407 is not set
# CONFIG_STM32_STM32F427 is not set
# CONFIG_STM32_STM32F429 is not set
# CONFIG_STM32_STM32F446 is not set
# CONFIG_STM32_STM32F469 is not set
# CONFIG_STM32_DFU is not set
#
# STM32 Peripheral Support
#
# CONFIG_STM32_HAVE_CCM is not set
CONFIG_STM32_HAVE_USBDEV=y
# CONFIG_STM32_HAVE_OTGFS is not set
# CONFIG_STM32_HAVE_FSMC is not set
# CONFIG_STM32_HAVE_LTDC is not set
# CONFIG_STM32_HAVE_USART3 is not set
# CONFIG_STM32_HAVE_UART4 is not set
# CONFIG_STM32_HAVE_UART5 is not set
# CONFIG_STM32_HAVE_USART6 is not set
# CONFIG_STM32_HAVE_UART7 is not set
# CONFIG_STM32_HAVE_UART8 is not set
CONFIG_STM32_HAVE_TIM1=y
# CONFIG_STM32_HAVE_TIM2 is not set
CONFIG_STM32_HAVE_TIM3=y
CONFIG_STM32_HAVE_TIM4=y
# CONFIG_STM32_HAVE_TIM5 is not set
CONFIG_STM32_HAVE_TIM6=y
# CONFIG_STM32_HAVE_TIM7 is not set
# CONFIG_STM32_HAVE_TIM8 is not set
# CONFIG_STM32_HAVE_TIM9 is not set
# CONFIG_STM32_HAVE_TIM10 is not set
# CONFIG_STM32_HAVE_TIM11 is not set
# CONFIG_STM32_HAVE_TIM12 is not set
# CONFIG_STM32_HAVE_TIM13 is not set
# CONFIG_STM32_HAVE_TIM14 is not set
CONFIG_STM32_HAVE_TIM15=y
CONFIG_STM32_HAVE_TIM16=y
CONFIG_STM32_HAVE_TIM17=y
# CONFIG_STM32_HAVE_ADC2 is not set
# CONFIG_STM32_HAVE_ADC3 is not set
# CONFIG_STM32_HAVE_ADC4 is not set
# CONFIG_STM32_HAVE_ADC1_DMA is not set
# CONFIG_STM32_HAVE_ADC2_DMA is not set
# CONFIG_STM32_HAVE_ADC3_DMA is not set
# CONFIG_STM32_HAVE_ADC4_DMA is not set
CONFIG_STM32_HAVE_CAN1=y
# CONFIG_STM32_HAVE_CAN2 is not set
CONFIG_STM32_HAVE_DAC1=y
# CONFIG_STM32_HAVE_DAC2 is not set
# CONFIG_STM32_HAVE_RNG is not set
# CONFIG_STM32_HAVE_ETHMAC is not set
CONFIG_STM32_HAVE_I2C2=y
CONFIG_STM32_HAVE_I2C3=y
CONFIG_STM32_HAVE_SPI2=y
CONFIG_STM32_HAVE_SPI3=y
# CONFIG_STM32_HAVE_SPI4 is not set
# CONFIG_STM32_HAVE_SPI5 is not set
# CONFIG_STM32_HAVE_SPI6 is not set
# CONFIG_STM32_HAVE_SAIPLL is not set
# CONFIG_STM32_HAVE_I2SPLL is not set
# CONFIG_STM32_ADC1 is not set
# CONFIG_STM32_CAN1 is not set
# CONFIG_STM32_CRC is not set
# CONFIG_STM32_DMA1 is not set
# CONFIG_STM32_DMA2 is not set
# CONFIG_STM32_DAC1 is not set
# CONFIG_STM32_I2C1 is not set
# CONFIG_STM32_I2C2 is not set
# CONFIG_STM32_I2C3 is not set
# CONFIG_STM32_PWR is not set
# CONFIG_STM32_SDIO is not set
# CONFIG_STM32_SPI1 is not set
# CONFIG_STM32_SPI2 is not set
# CONFIG_STM32_SPI3 is not set
CONFIG_STM32_SYSCFG=y
CONFIG_STM32_TIM1=y
# CONFIG_STM32_TIM2 is not set
# CONFIG_STM32_TIM3 is not set
# CONFIG_STM32_TIM4 is not set
# CONFIG_STM32_TIM6 is not set
# CONFIG_STM32_TIM15 is not set
# CONFIG_STM32_TIM16 is not set
# CONFIG_STM32_TIM17 is not set
# CONFIG_STM32_TSC is not set
# CONFIG_STM32_USART1 is not set
# CONFIG_STM32_USART2 is not set
# CONFIG_STM32_USB is not set
# CONFIG_STM32_IWDG is not set
# CONFIG_STM32_WWDG is not set
CONFIG_STM32_NOEXT_VECTORS=y
#
# Alternate Pin Mapping
#
# CONFIG_STM32_JTAG_DISABLE is not set
CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
# CONFIG_STM32_JTAG_SW_ENABLE is not set
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER is not set
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
#
# Timer Configuration
#
# CONFIG_STM32_ONESHOT is not set
# CONFIG_STM32_FREERUN is not set
# CONFIG_STM32_TIM1_PWM is not set
# CONFIG_STM32_TIM1_CAP is not set
# CONFIG_STM32_TIM3_CAP is not set
# CONFIG_STM32_TIM4_CAP is not set
# CONFIG_STM32_HAVE_RTC_COUNTER is not set
# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
#
# USB FS Host Configuration
#
#
# USB HS Host Configuration
#
#
# USB Host Debug Configuration
#
#
# USB Device Configuration
#
#
# Architecture Options
#
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_VECNOTIRQ is not set
# CONFIG_ARCH_DMA is not set
CONFIG_ARCH_HAVE_IRQPRIO=y
# CONFIG_ARCH_L2CACHE is not set
# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
# CONFIG_ARCH_HAVE_ADDRENV is not set
# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
# CONFIG_ARCH_HAVE_MULTICPU is not set
CONFIG_ARCH_HAVE_VFORK=y
# CONFIG_ARCH_HAVE_MMU is not set
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARCH_NAND_HWECC is not set
# CONFIG_ARCH_HAVE_EXTCLK is not set
# CONFIG_ARCH_HAVE_POWEROFF is not set
CONFIG_ARCH_HAVE_RESET=y
# CONFIG_ARCH_USE_MPU is not set
# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_ARCH_STACKDUMP is not set
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_IDLE_CUSTOM 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=5483
# CONFIG_ARCH_CALIBRATION is not set
#
# Interrupt options
#
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
CONFIG_ARCH_INTERRUPTSTACK=3072
CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
# CONFIG_ARCH_HIPRI_INTERRUPT is not set
#
# 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
#
# Boot Memory Configuration
#
CONFIG_RAM_START=0x20000000
CONFIG_RAM_SIZE=16384
# CONFIG_ARCH_HAVE_SDRAM is not set
#
# Board Selection
#
CONFIG_ARCH_BOARD_S2740VC_V1=y
CONFIG_ARCH_BOARD="s2740vc-v1"
#
# Custom Board Configuration
#
# CONFIG_BOARD_CRASHDUMP is not set
# CONFIG_BOARD_CUSTOM_LEDS is not set
# CONFIG_BOARD_CUSTOM_BUTTONS is not set
#
# Common Board Options
#
#
# Board-Specific Options
#
# CONFIG_LIB_BOARDCTL is not set
#
# RTOS Features
#
CONFIG_DISABLE_OS_API=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_DISABLE_PTHREAD=y
CONFIG_DISABLE_SIGNALS=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_ENVIRON=y
#
# Clocks and Timers
#
CONFIG_ARCH_HAVE_TICKLESS=y
# CONFIG_SCHED_TICKLESS is not set
CONFIG_USEC_PER_TICK=10000
# CONFIG_SYSTEM_TIME64 is not set
# CONFIG_CLOCK_MONOTONIC is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=2014
CONFIG_START_MONTH=11
CONFIG_START_DAY=30
CONFIG_MAX_WDOGPARMS=1
CONFIG_PREALLOC_WDOGS=1
CONFIG_WDOG_INTRESERVE=0
CONFIG_PREALLOC_TIMERS=0
#
# Tasks and Scheduling
#
# CONFIG_INIT_NONE is not set
CONFIG_INIT_ENTRYPOINT=y
CONFIG_USER_ENTRYPOINT="main"
CONFIG_RR_INTERVAL=0
# CONFIG_SCHED_SPORADIC is not set
CONFIG_TASK_NAME_SIZE=0
CONFIG_MAX_TASKS=0
# CONFIG_SCHED_HAVE_PARENT is not set
# CONFIG_SCHED_WAITPID is not set
#
# Performance Monitoring
#
# CONFIG_SCHED_CPULOAD is not set
# CONFIG_SCHED_INSTRUMENTATION is not set
#
# Files and I/O
#
# CONFIG_DEV_CONSOLE is not set
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_NFILE_DESCRIPTORS=0
CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=0
# CONFIG_PRIORITY_INHERITANCE is not set
#
# RTOS hooks
#
# CONFIG_BOARD_INITIALIZE is not set
# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
# CONFIG_SCHED_ONEXIT is not set
# CONFIG_MODULE is not set
#
# Work queue support
#
#
# Stack and heap information
#
CONFIG_IDLETHREAD_STACKSIZE=4096
CONFIG_USERMAIN_STACKSIZE=4096
CONFIG_PTHREAD_STACK_MIN=256
CONFIG_PTHREAD_STACK_DEFAULT=464
# CONFIG_LIB_SYSCALL is not set
#
# Device Drivers
#
CONFIG_DISABLE_POLL=y
# CONFIG_DEV_NULL is not set
# CONFIG_DEV_ZERO is not set
# CONFIG_DEV_URANDOM is not set
# CONFIG_DEV_LOOP is not set
#
# Buffering
#
# CONFIG_DRVR_WRITEBUFFER is not set
# CONFIG_DRVR_READAHEAD is not set
# CONFIG_RAMDISK is not set
# CONFIG_CAN is not set
# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set
# CONFIG_PWM is not set
CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_I2C is not set
# CONFIG_SPI is not set
# CONFIG_I2S is not set
#
# Timer Driver Support
#
# CONFIG_TIMER is not set
# CONFIG_RTC is not set
# CONFIG_WATCHDOG is not set
# CONFIG_ANALOG is not set
# CONFIG_AUDIO_DEVICES is not set
# CONFIG_VIDEO_DEVICES is not set
# CONFIG_BCH is not set
# CONFIG_INPUT is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
# CONFIG_LCD is not set
# CONFIG_SLCD is not set
#
# LED Support
#
# CONFIG_RGBLED is not set
# CONFIG_PCA9635PW is not set
# CONFIG_NCP5623C is not set
# CONFIG_MMCSD is not set
# CONFIG_MODEM is not set
# CONFIG_MTD is not set
# CONFIG_EEPROM is not set
# CONFIG_PIPES is not set
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
# CONFIG_SERCOMM_CONSOLE is not set
# CONFIG_SERIAL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
# CONFIG_DRIVERS_WIRELESS is not set
#
# System Logging
#
# CONFIG_ARCH_SYSLOG is not set
# CONFIG_RAMLOG is not set
# CONFIG_SYSLOG_INTBUFFER is not set
# CONFIG_SYSLOG_TIMESTAMP is not set
# CONFIG_SYSLOG_SERIAL_CONSOLE is not set
# CONFIG_SYSLOG_CHAR is not set
CONFIG_SYSLOG_NONE=y
# CONFIG_SYSLOG_FILE is not set
#
# Networking Support
#
# CONFIG_ARCH_HAVE_NET is not set
# CONFIG_ARCH_HAVE_PHY is not set
# CONFIG_NET is not set
#
# Crypto API
#
# CONFIG_CRYPTO is not set
#
# File Systems
#
#
# File system configuration
#
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y
# CONFIG_FS_READABLE is not set
# CONFIG_FS_WRITABLE is not set
# CONFIG_FS_NAMED_SEMAPHORES is not set
# CONFIG_FS_RAMMAP is not set
# CONFIG_FS_PROCFS is not set
# CONFIG_FS_UNIONFS is not set
#
# Graphics Support
#
# CONFIG_NX is not set
#
# Memory Management
#
CONFIG_MM_SMALL=y
CONFIG_MM_REGIONS=1
# CONFIG_ARCH_HAVE_HEAP2 is not set
# CONFIG_GRAN is not set
#
# Audio Support
#
# CONFIG_AUDIO is not set
#
# Wireless Support
#
#
# Binary Loader
#
CONFIG_BINFMT_DISABLE=y
# CONFIG_PIC is not set
CONFIG_SYMTAB_ORDEREDBYNAME=y
#
# Library Routines
#
#
# Standard C Library Options
#
CONFIG_STDIO_BUFFER_SIZE=64
# CONFIG_STDIO_LINEBUFFER is not set
CONFIG_NUNGET_CHARS=0
# CONFIG_LIBM is not set
# CONFIG_NOPRINTF_FIELDWIDTH is not set
# CONFIG_LIBC_FLOATINGPOINT is not set
# CONFIG_LIBC_LONG_LONG is not set
# CONFIG_LIBC_IOCTL_VARIADIC is not set
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_POSIX_SPAWN_PROXY_STACKSIZE=768
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=768
# CONFIG_LIBC_STRERROR is not set
# CONFIG_LIBC_PERROR_STDOUT is not set
# CONFIG_ARCH_LOWPUTC is not set
# CONFIG_TIME_EXTENDED is not set
CONFIG_LIB_SENDFILE_BUFSIZE=0
# CONFIG_ARCH_ROMGETC is not set
# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
CONFIG_ARCH_HAVE_TLS=y
# CONFIG_TLS is not set
# CONFIG_LIBC_NETDB is not set
#
# Non-standard Library Support
#
# CONFIG_LIB_CRC64_FAST is not set
# 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
#
#
# CAN Utilities
#
#
# Examples
#
# CONFIG_EXAMPLES_CHAT is not set
# CONFIG_EXAMPLES_CONFIGDATA is not set
# CONFIG_EXAMPLES_CPUHOG 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_HIDKBD is not set
# CONFIG_EXAMPLES_IGMP is not set
# CONFIG_EXAMPLES_JSON is not set
# CONFIG_EXAMPLES_KEYPADTEST is not set
# CONFIG_EXAMPLES_MEDIA is not set
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MODBUS is not set
# CONFIG_EXAMPLES_MOUNT is not set
# CONFIG_EXAMPLES_NRF24L01TERM is not set
# CONFIG_EXAMPLES_NSH is not set
CONFIG_EXAMPLES_NULL=y
# CONFIG_EXAMPLES_NXFFS is not set
# CONFIG_EXAMPLES_NXHELLO is not set
# CONFIG_EXAMPLES_NXIMAGE is not set
# CONFIG_EXAMPLES_NX is not set
# CONFIG_EXAMPLES_NXLINES is not set
# CONFIG_EXAMPLES_NXTERM is not set
# CONFIG_EXAMPLES_NXTEXT is not set
# CONFIG_EXAMPLES_OSTEST is not set
# CONFIG_EXAMPLES_PCA9635 is not set
# CONFIG_EXAMPLES_PIPE is not set
# CONFIG_EXAMPLES_POLL is not set
# CONFIG_EXAMPLES_POSIXSPAWN is not set
# CONFIG_EXAMPLES_PPPD is not set
# CONFIG_EXAMPLES_RGBLED is not set
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
# CONFIG_EXAMPLES_SERIALBLASTER is not set
# CONFIG_EXAMPLES_SERIALRX is not set
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_SLCD is not set
# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_SMP is not set
# CONFIG_EXAMPLES_TCPECHO is not set
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_TIFF is not set
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
# CONFIG_EXAMPLES_WEBSERVER is not set
#
# File System Utilities
#
# CONFIG_FSUTILS_INIFILE is not set
#
# GPS Utilities
#
# CONFIG_GPSUTILS_MINMEA_LIB is not set
#
# Graphics Support
#
# CONFIG_TIFF is not set
# CONFIG_GRAPHICS_TRAVELER is not set
#
# Interpreters
#
# CONFIG_INTERPRETERS_FICL is not set
# CONFIG_INTERPRETERS_MICROPYTHON is not set
# CONFIG_INTERPRETERS_PCODE is not set
#
# FreeModBus
#
# CONFIG_MODBUS is not set
#
# Network Utilities
#
# CONFIG_NETUTILS_CODECS is not set
# CONFIG_NETUTILS_ESP8266 is not set
# CONFIG_NETUTILS_FTPC is not set
# CONFIG_NETUTILS_JSON is not set
# CONFIG_NETUTILS_SMTP is not set
#
# NSH Library
#
# CONFIG_NSH_LIBRARY is not set
#
# NxWidgets/NxWM
#
#
# Platform-specific Support
#
# CONFIG_PLATFORM_CONFIGDATA is not set
#
# System Libraries and NSH Add-Ons
#
# CONFIG_SYSTEM_CLE is not set
# CONFIG_SYSTEM_CUTERM is not set
# CONFIG_SYSTEM_FREE is not set
# CONFIG_SYSTEM_HEX2BIN is not set
# CONFIG_SYSTEM_HEXED is not set
# CONFIG_SYSTEM_INSTALL is not set
# CONFIG_SYSTEM_RAMTEST is not set
# CONFIG_READLINE_HAVE_EXTMATCH is not set
# CONFIG_SYSTEM_READLINE is not set
# CONFIG_SYSTEM_SUDOKU is not set
# CONFIG_SYSTEM_UBLOXMODEM is not set
# CONFIG_SYSTEM_VI is not set
# CONFIG_SYSTEM_ZMODEM is not set

View File

@ -0,0 +1,80 @@
#!/bin/bash
# configs/s2740vc/bootloader/setenv.sh
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
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 is 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"
#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# This is 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"
# These are the Cygwin paths to the locations where I installed the Atollic
# toolchain under windows. You will also have to edit this if you install
# the Atollic toolchain in any other location. /usr/bin is added before
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
# at those locations as well.
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2014q4/bin"
# This is 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}"

View File

@ -0,0 +1,2 @@
This directory contains header files unique to the
S2740VC board using STM32F302K8

View File

@ -0,0 +1,186 @@
/************************************************************************************
* configs/s2740vc/include/board.h
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* 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 <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#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 */

View File

@ -0,0 +1 @@
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!

View File

@ -0,0 +1,159 @@
############################################################################
# configs/s2740vc-v1/nsh/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_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${HOST_OS_FIRST_LETTER}
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 = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# 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)/scripts/$(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)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(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}
# Optimization 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 = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
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 =

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,80 @@
#!/bin/bash
# configs/s2740vc-v1/nsh/setenv.sh
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
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 is 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"
#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# This is 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"
# These are the Cygwin paths to the locations where I installed the Atollic
# toolchain under windows. You will also have to edit this if you install
# the Atollic toolchain in any other location. /usr/bin is added before
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
# at those locations as well.
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2014q4/bin"
# This is 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}"

View File

@ -0,0 +1,127 @@
/****************************************************************************
* configs/s2740vc/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* 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.
* The bootloader only uses the first 8KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 8K
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(.);
} > 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 STM32F103CB has 20Kb 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) }
}

View File

@ -0,0 +1,141 @@
/****************************************************************************
* configs/s2740vc-v1/scripts/ld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* 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)
_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) }
}

View File

@ -0,0 +1,100 @@
############################################################################
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# 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))
ifeq ($(CONFIG_BOOTLOADER),)
CSRCS = empty.c
endif
ifeq ($(CONFIG_BOOTLOADER),y)
SRC_SEARCH = bootloader/can bootloader/src bootloader/common bootloader/uavcan
CSRCS = ostubs.c
CFLAGS += $(addprefix -I,$(SRC_SEARCH))
DEPOPTS = $(addprefix --dep-path ,$(SRC_SEARCH))
VPATH= $(SRC_SEARCH)
endif
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)
ifneq ($(BOARD_CONTEXT),y)
context:
endif
-include Make.dep

View File

@ -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.
*/

View File

@ -0,0 +1,171 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane <david_s5@nscdg.com>
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/init.h>
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <syslog.h>
#include <errno.h>
#include <nuttx/board.h>
#include "up_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
volatile dq_queue_t g_readytorun;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
void timer_init(void);
int __wrap_up_svcall(int irq, FAR void *context);
/****************************************************************************
* Name: os_start
*
* Description:
* This function hijacks the entry point of the OS. Normally called by the
* statup code for a given architecture
*
****************************************************************************/
void os_start(void)
{
/* Initialize the timer software subsystem */
timer_init();
/* Initialize the interrupt subsystem */
up_irqinitialize();
/* Initialize the OS's timer subsystem */
#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS) && \
!defined(CONFIG_SYSTEMTICK_EXTCLK)
up_timer_initialize();
#endif
/* Keep the compiler happy for a no return function */
while (1)
{
main(0, 0);
}
}
/****************************************************************************
* Name: malloc
*
* Description:
* This function hijacks the OS's malloc and provides no allocation
*
****************************************************************************/
FAR void *malloc(size_t size)
{
return NULL;
}
/****************************************************************************
* Name: malloc
*
* Description:
* This function hijacks the systems exit
*
****************************************************************************/
void exit(int status)
{
while (1);
}
/****************************************************************************
* Name: sched_ufree
*
* Description:
* This function hijacks the systems sched_ufree that my be called during
* exception processing.
*
****************************************************************************/
void sched_ufree(FAR void *address)
{
}
/****************************************************************************
* Name: up_svcall
*
* Description:
* This function hijacks by the way of a compile time wrapper the systems
* up_svcall
*
****************************************************************************/
int __wrap_up_svcall(int irq, FAR void *context)
{
return 0;
}

View File

@ -0,0 +1,77 @@
############################################################################
#
# 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-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"DO NOT RUN THIS ON HW")
message(WARNING-"IT IS NOT PINED OUT TO HW")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
include_directories(../../bootloaders/include)
set(SRCS)
list(APPEND SRCS
../common/board_name.c
s2740vc_init.c
s2740vc_can.c
../../../drivers/bootloaders/src/common/boot_app_shared.c
../../../drivers/bootloaders/src/util/crc.c
)
if(${OS} STREQUAL "nuttx")
if (NOT ${BOARD} STREQUAL "sim")
list(APPEND SRCS
../../../drivers/device/device_nuttx.cpp
../../../drivers/device/cdev.cpp
)
endif()
else()
list(APPEND SRCS
../../../drivers/device/device_posix.cpp
../../../drivers/device/vdev.cpp
)
endif()
px4_add_module(
MODULE drivers__boards__s2740vc-v1
COMPILE_FLAGS
-Os
SRCS ${SRCS}
DEPENDS
platforms__common
)

View File

@ -0,0 +1,133 @@
/****************************************************************************
*
* 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 <px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
/************************************************************************************
* 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)
#define BOARD_NAME "S2740VC_V1"
__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 "../common/board_common.h"
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -0,0 +1,64 @@
############################################################################
#
# 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.
#
############################################################################
add_definitions(
-DHW_UAVCAN_NAME=${uavcanblid_name}
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
)
include_directories(${px4_bootloader_base}include)
include_directories(${px4_module_base}systemlib)
include_directories(.)
px4_add_module(
MODULE drivers__boards__s2740vc-v1__bootloader
COMPILE_FLAGS
-Os
SRCS
boot.c
${px4_bootloader_base}src/uavcan/main.c
${px4_bootloader_base}src/common/boot_app_shared.c
${px4_bootloader_base}src/sched/timer.c
${px4_bootloader_base}src/fs/flash.c
${px4_bootloader_base}src/util/crc.c
${px4_bootloader_base}src/util/random.c
${px4_bootloader_base}src/arch/stm32/drivers/can/driver.c
${px4_bootloader_base}src/protocol/uavcan.c
DEPENDS
nuttx_export_${BOARD}
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -0,0 +1,195 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private 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)
{
putreg32(getreg32(STM32_RCC_AHBENR) | RCC_AHBENR_IOPAEN |
RCC_AHBENR_IOPBEN, STM32_RCC_AHBENR);
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
stm32_configgpio(GPIO_CAN_RX_2);
stm32_configgpio(GPIO_CAN_TX_2);
stm32_configgpio(GPIO_CAN_SILENT);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
size_t length = 12;
memset(hw_version, 0 , sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
memcpy(hw_version->unique_id, (void *) STM32_SYSMEM_UID, length);
return length;
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
void board_indicate(uiindication_t indication)
{
}

View File

@ -0,0 +1,139 @@
/****************************************************************************
*
* 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 boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 10
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*/
#define OPT_WAIT_FOR_GETNODEINFO 1
/* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO */
/* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1 */
/* #define OPT_ENABLE_WD */
#define OPT_RESTART_TIMEOUT_MS 20000u
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*8)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K 0
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES 32
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE (FLASH_NUMBER_PAGES*FLASH_PAGE_SIZE)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif
/* Bootloader Option*****************************************************************
*
* GPIO Function MPU Board
* Pin # Name
* -- ----- -------------------------------- ----------------------------
* * PC[09] PC9/TIM3_CH4 40 BOOT0
*/
#define GPIO_GETNODEINFO_JUMPER (BUTTON_BOOT0n&~(GPIO_EXTI))

View File

@ -0,0 +1,131 @@
/****************************************************************************
*
* 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 <px4_config.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/drivers/can.h>
#include <arch/board/board.h>
#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 */

View File

@ -0,0 +1,186 @@
/****************************************************************************
*
* 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 <px4_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <stm32.h>
#include "board_config.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <systemlib/cpuload.h>
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
#include <systemlib/systemlib.h>
#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;
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
/* run C++ ctors before we go any further */
up_cxxinitialize();
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
# endif
#else
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
#endif
/* configure the high-resolution time/callout interface */
hrt_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;
}