[chibios] add chibios-libopencm3 support

Only the realtime scheduler and SDIO driver from ChibiOS is used.
This brings the support of the SD log on Apogee boards. The current
solution is not fully satisfactory and is an intermediate solution
before switching to a 'pure' ChibiOS arch.
Some of the implementations can be cleaned and/or improved, but since it
is not a long term solution, I doubt it is worth the effort here.
Normal bare-metal libopencm3 code is of course still working.
Git submodules:
- chibios: 2.6.2
- fatfs: patched version for chibios+pprz
This commit is contained in:
Gautier Hattenberger
2014-01-23 17:32:40 +01:00
committed by Felix Ruess
parent daf9408171
commit 6ff0fc973b
58 changed files with 7521 additions and 49 deletions

6
.gitmodules vendored
View File

@@ -4,3 +4,9 @@
[submodule "sw/ext/luftboot"]
path = sw/ext/luftboot
url = https://github.com/paparazzi/luftboot.git
[submodule "sw/ext/chibios"]
path = sw/ext/chibios
url = https://github.com/ChibiOS/ChibiOS-RT.git
[submodule "sw/ext/fatfs"]
path = sw/ext/fatfs
url = https://github.com/enacuavlab/fatfs.git

View File

@@ -0,0 +1,332 @@
# Hey Emacs, this is a -*- makefile -*-
#
# Copyright (C) 2012 The Paparazzi Team
#
# This file is part of paparazzi.
#
# paparazzi is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 2, or (at your option)
# any later version.
#
# paparazzi is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with paparazzi; see the file COPYING. If not, write to
# the Free Software Foundation, 59 Temple Place - Suite 330,
# Boston, MA 02111-1307, USA.
#
# Verify that libopencm3 is compiled with chibios compatible float abi
# correct abi is -mfloat-abi=softfp
# on non chibios branches, libopencm3 is compiled with more optimised -mfloat-abi=hard
TAG_ABI_VFP_COUNT= \
$(shell (readelf -A $(PAPARAZZI_SRC)/sw/ext/libopencm3/lib/libopencm3_stm32f4.a | \
grep -c Tag_ABI_VFP_args))
ifneq ($(TAG_ABI_VFP_COUNT),0)
$(error libopencm3_stm32f4.a is generated with chibios incompatible -mfloat-abi=hard, \
please recompile with -mfloat-abi=softfp))
endif
#
# This is the common Makefile for target using chibios
CHIBIOS_BOARD_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD)/chibios-libopencm3
CHIBIOS_LIB_DIR = $(PAPARAZZI_SRC)/sw/airborne/subsystems/chibios-libopencm3
CHIBIOS_EXT = $(PAPARAZZI_SRC)/sw/ext/chibios
OPENCM3_EXT = $(PAPARAZZI_SRC)/sw/ext/libopencm3
# Launch with "make Q=''" to get full command display
Q=@
#
# General rules
#
$(TARGET).srcsnd = $(notdir $($(TARGET).srcs))
$(TARGET).objso = $($(TARGET).srcs:%.c=$(OBJDIR)/%.o)
$(TARGET).objs = $($(TARGET).objso:%.S=$(OBJDIR)/%.o)
##############################################################################
# Build global options
# NOTE: Can be overridden externally.
#
# Paparazzi options here.
ifeq ($(PPRZ_DEFINITION),)
PPRZ_DEFINITION = -DRTOS_IS_CHIBIOS -DUSE_ADC_WATCHDOG -DSYS_TIME_FREQUENCY=1000 -DADC_TIMER_PRESCALER=0x02
endif
# Compiler options here.
ifeq ($(USE_OPT),)
USE_OPT = -std=gnu11 -g -O0 -ggdb3 -fno-inline \
-falign-functions=16 -fno-omit-frame-pointer\
-W -Wall -Werror -Wno-error=unused-variable -Wno-error=format \
-Wno-error=unused-function -Wno-error=unused-parameter \
$(PPRZ_DEFINITION)
endif
ifeq ($(USE_OPT),)
USE_OPT = -std=gnu11 -O2 \
-falign-functions=16 -fno-omit-frame-pointer\
-W -Wall -Werror -Wno-error=unused-variable -Wno-error=format \
-Wno-error=unused-function -Wno-error=unused-parameter \
$(PPRZ_DEFINITION)
endif
# ifeq ($(USE_OPT),)
# USE_OPT = -std=gnu11 -Os \
# -falign-functions=16 -fomit-frame-pointer\
# -W -Wall -DRTOS_IS_CHIBIOS
# endif
# C specific options here (added to USE_OPT).
ifeq ($(USE_COPT),)
USE_COPT =
endif
# C++ specific options here (added to USE_OPT).
ifeq ($(USE_CPPOPT),)
USE_CPPOPT = -fno-rtti
endif
# Enable this if you want the linker to remove unused code and data
ifeq ($(USE_LINK_GC),)
USE_LINK_GC = yes
endif
# If enabled, this option allows to compile the application in THUMB mode.
ifeq ($(USE_THUMB),)
USE_THUMB = yes
endif
# Enable this if you want to see the full log while compiling.
ifeq ($(USE_VERBOSE_COMPILE),)
ifeq ($(Q),@)
USE_VERBOSE_COMPILE = no
else
USE_VERBOSE_COMPILE = yes
endif
endif
#
# Build global options
##############################################################################
##############################################################################
# Architecture or project specific options
#
# Enables the use of FPU on Cortex-M4.
ifeq ($(USE_FPU),)
USE_FPU = yes
endif
#
# Architecture or project specific options
##############################################################################
##############################################################################
# Project, sources and paths
#
# Define project name here
PROJECT = ap
# Imported source files and paths
CHIBIOS = $(CHIBIOS_EXT)
OPENCM3 = $(OPENCM3_EXT)
OPENCM3_INC = $(OPENCM3)/include
OPENCM3_LIB = $(OPENCM3)/lib/
include $(CHIBIOS_BOARD_DIR)/board.mk
include $(CHIBIOS)/os/hal/platforms/STM32F4xx/platform.mk
include $(CHIBIOS)/os/hal/hal.mk
include $(CHIBIOS)/os/ports/GCC/ARMCMx/STM32F4xx/port.mk
#include $(CHIBIOS)/os/various/fatfs_bindings/fatfs.mk
include $(PAPARAZZI_HOME)/conf/chibios/fatfs.mk
include $(PAPARAZZI_HOME)/conf/chibios/chibi_lib_for_pprz.mk
# HACK : in order to make chibios to work with opencm3, we need a specially crafted
# vector.c file, with some vectors for chibios, and others for opencm3
# shunting should be done in mcuconf.h
PORTSRC := $(subst $(CHIBIOS)/os/ports/GCC/ARMCMx/STM32F4xx/vectors.c,\
$(PAPARAZZI_SRC)/sw/airborne/arch/stm32/stm32f4_chibios_vectors.c,\
$(PORTSRC))
include $(CHIBIOS)/os/kernel/kernel.mk
# Define linker script file here
LDSCRIPT= $($(TARGET).LDSCRIPT)
# C sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
CSRC = $(PORTSRC) \
$(KERNSRC) \
$(TESTSRC) \
$(HALSRC) \
$(PLATFORMSRC) \
$(BOARDSRC) \
$(FATFSSRC) \
$(CHIBIOSLIBSRC) \
$(CHIBIOS)/os/various/chrtclib.c \
$(CHIBIOS)/os/various/syscalls.c
ECSRC = $($(TARGET).srcs)
# C++ sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
CPPSRC =
# C sources to be compiled in ARM mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
ACSRC =
# C++ sources to be compiled in ARM mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
ACPPSRC =
# C sources to be compiled in THUMB mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
TCSRC =
# C sources to be compiled in THUMB mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
TCPPSRC =
# List ASM source files here
ASMSRC = $(PORTASM)
INCDIR = $(PORTINC) $(KERNINC) $(TESTINC) \
$(HALINC) $(PLATFORMINC) $(BOARDINC) \
$(CHIBIOS)/os/various $(OPENCM3_INC) \
$(CHIBIOS_BOARD_DIR) $(CHIBIOS_LIB_DIR) \
$(FATFSINC)
BUILDDIR := $(OBJDIR)
#
# Project, sources and paths
##############################################################################
##############################################################################
# Compiler settings
#
MCU = cortex-m4
#TRGT = arm-elf-
TRGT = arm-none-eabi-
CC = $(TRGT)gcc
CPPC = $(TRGT)g++
# Enable loading with g++ only if you need C++ runtime support.
# NOTE: You can use C++ even without C++ support if you are careful. C++
# runtime support makes code size explode.
LD = $(TRGT)gcc
#LD = $(TRGT)g++
CP = $(TRGT)objcopy
AS = $(TRGT)gcc -x assembler-with-cpp
OD = $(TRGT)objdump
HEX = $(CP) -O ihex
BIN = $(CP) -O binary
# ARM-specific options here
AOPT =
# THUMB-specific options here
TOPT = -mthumb -DTHUMB
# Define C warning options here
CWARN = -Wall -Wextra -Wstrict-prototypes
# Define C++ warning options here
CPPWARN = -Wall -Wextra
#
# Compiler settings
##############################################################################
##############################################################################
# Start of default section
#
# List all default C defines here, like -D_DEBUG=1
DDEFS = -DSTM32F4
#DDEFS =
# List all default ASM defines here, like -D_DEBUG=1
DADEFS =
# List all default directories to look for include files here
DINCDIR =
# List the default directory to look for the libraries here
DLIBDIR = $(OPENCM3_LIB)
# List all default libraries here
DLIBS = -lm -lopencm3_stm32f4
#DLIBS = -lm -lc -lnosys -nostartfiles -Wl,--gc-sections
#
# End of default section
##############################################################################
##############################################################################
# Start of user section
#
# List all user C define here, like -D_DEBUG=1
UDEFS = $($(TARGET).CFLAGS) $(LOCAL_CFLAGS) -DUSE_OCM3_SYSTICK_INIT=0
# Define ASM defines here
UADEFS =
# List all user directories here
# remove -I before include dir because ChibiOS is adding them again
UINCDIR = $(patsubst -I%,%,$(INCLUDES))
# List the user directory to look for the libraries here
ULIBDIR =
# List all user libraries here
ULIBS =
#
# End of user defines
##############################################################################
#
# Include upload rules
##############################################################################
include $(PAPARAZZI_HOME)/conf/Makefile.arm-embedded-toolchain
include $(PAPARAZZI_HOME)/conf/Makefile.stm32-upload
ifeq ($(USE_FPU),yes)
USE_OPT += -mfloat-abi=softfp -mfpu=fpv4-sp-d16 -fsingle-precision-constant
DDEFS += -DCORTEX_USE_FPU=TRUE
else
DDEFS += -DCORTEX_USE_FPU=FALSE
endif
EXTRA_RULES_INCLUDE_PATH = $(PAPARAZZI_HOME)/conf/chibios/chibios_extra_rules.mk
include $(PAPARAZZI_HOME)/conf/chibios/chibios_rules.mk
#include $(CHIBIOS_EXT)/os/ports/GCC/ARMCMx/rules.mk

View File

@@ -79,7 +79,7 @@ else ifeq ($(ARCH_L),f4)
ifndef HARD_FLOAT
CFLAGS += -msoft-float
else
CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
CFLAGS += -mfloat-abi=softfp -mfpu=fpv4-sp-d16
endif
endif
@@ -130,7 +130,7 @@ ifndef HARD_FLOAT
LDFLAGS += -mfix-cortex-m3-ldrd -msoft-float
else
LDFLAGS += -lnosys -D__thumb2__\
-mfloat-abi=hard -mfpu=fpv4-sp-d16
-mfloat-abi=softfp -mfpu=fpv4-sp-d16
endif
endif

View File

@@ -8,14 +8,14 @@
<modules>
<!--load name="sys_mon.xml"/-->
<load name="mcp355x.xml">
<define name="USE_SPI1"/>
</load>
<!-- <load name="mcp355x.xml"> -->
<!-- <define name="USE_SPI1"/> -->
<!-- </load> -->
</modules>
<firmware name="fixedwing">
<define name="USE_I2C1"/>
<define name="USE_I2C2"/>
<!--define name="USE_I2C2"/-->
<!--define name="AGR_CLIMB"/-->
<!--define name="LOITER_TRIM"/-->
<!--define name="PITCH_TRIM"/-->
@@ -23,8 +23,8 @@
<configure name="PERIODIC_FREQUENCY" value="100"/>
<target name="sim" board="pc"/>
<target name="ap" board="apogee_1.0"/>
<!--configure name="FLASH_MODE" value="SWD"/-->
<target name="ap" board="apogee_1.0_chibios"/>
<configure name="FLASH_MODE" value="SWD"/>
<subsystem name="radio_control" type="sbus"/>
@@ -43,6 +43,12 @@
<subsystem name="spi_master"/>
</firmware>
<firmware name="lisa_test_progs">
<target name="test_led" board="apogee_1.0_chibios">
<define name="BOARD_LISA_M"/>
</target>
</firmware>
<!-- commands section -->
<servos>
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>

View File

@@ -8,14 +8,14 @@
<define name="MAG_HMC58XX_I2C_DEV" value="i2c2"/>
</load>
<load name="airspeed_adc.xml">
<configure name="ADC_AIRSPEED" value="ADC_2"/>
<configure name="ADC_AIRSPEED" value="ADC_1"/>
<define name="AIRSPEED_QUADRATIC_SCALE" value="0.5"/>
<define name="AIRSPEED_BIAS" value="430"/>
<define name="MEASURE_AIRSPEED"/>
<define name="AIRSPEED_SEND_RAW"/>
</load>
<!--load name="gps_ubx_ucenter.xml"/-->
<load name="sys_mon.xml"/>
<load name="gps_ubx_ucenter.xml"/>
<!--load name="sys_mon.xml"/-->
</modules>
<firmware name="fixedwing">
@@ -24,7 +24,7 @@
<define name="USE_GYRO_PITCH_RATE"/>
<configure name="PERIODIC_FREQUENCY" value="125"/>
<target name="ap" board="apogee_0.99"/>
<target name="ap" board="apogee_1.0_chibios"/>
<target name="sim" board="pc"/>
<target name="nps" board="pc">
<!-- Note NPS needs the ppm type radio_control subsystem -->
@@ -41,9 +41,6 @@
<define name="USE_MAGNETOMETER"/>
<define name="APOGEE_LOWPASS_FILTER" value="MPU60X0_DLPF_20HZ"/>
<define name="APOGEE_SMPLRT_DIV" value="7"/>
<!--define name="INS_COEF"/-->
<!--define name="USE_BAROMETER"/-->
<!--define name="BOARD_HAS_BARO"/-->
</subsystem>
<subsystem name="ins" type="float_invariant">
<configure name="AHRS_PROPAGATE_FREQUENCY" value="125"/>
@@ -54,14 +51,20 @@
<subsystem name="control" type="new"/>
<subsystem name="navigation"/>
<!-- Sensors -->
<subsystem name="gps" type="ublox"/>
<subsystem name="gps" type="ublox">
<configure name="GPS_BAUD" value="B115200"/>
<define name="GPS_UBX_UCENTER_RATE" value="200"/>
<define name="USE_GPS_UBX_RXM_RAW"/>
<define name="USE_GPS_UBX_RXM_SFRB"/>
<define name="LOG_RAW_GPS"/>
</subsystem>
<subsystem name="current_sensor">
<configure name="ADC_CURRENT_SENSOR" value="ADC_1"/>
<configure name="ADC_CURRENT_SENSOR" value="ADC_2"/>
</subsystem>
</firmware>
<!-- commands section -->
<!-- commands section -->
<servos>
<servo name="MOTOR" no="0" min="1040" neutral="1040" max="2000"/>
<servo name="AILEVON_RIGHT" no="1" max="1100" neutral="1400" min="1900"/>
@@ -113,18 +116,19 @@
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="ACCEL_X_NEUTRAL" value="109"/>
<define name="ACCEL_X_NEUTRAL" value="29"/>
<define name="ACCEL_Y_NEUTRAL" value="38"/>
<define name="ACCEL_Z_NEUTRAL" value="117"/>
<define name="ACCEL_X_SENS" value="2.4633147596" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44625155655" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.44963539606" integer="16"/>
<!--define name="ACCEL_X_NEUTRAL" value="109"/>
<define name="ACCEL_Y_NEUTRAL" value="13"/>
<define name="ACCEL_Z_NEUTRAL" value="-404"/>
<define name="ACCEL_X_SENS" value="2.45045342816" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.44747844234" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.42689216106" integer="16"/>
<!--define name="ACCEL_X_NEUTRAL" value="148"/>
<define name="ACCEL_Y_NEUTRAL" value="-8"/>
<define name="ACCEL_Z_NEUTRAL" value="12"/>
<define name="ACCEL_X_SENS" value="2.45197002728" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.45528611115" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.4328991225" integer="16"/-->
<define name="ACCEL_Z_SENS" value="2.42689216106" integer="16"/-->
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="-1"/>
@@ -225,11 +229,11 @@
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.743"/>
<define name="ROLL_MAX_SETPOINT" value="0.8" unit="rad"/>
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="rad"/>
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="rad"/>
<define name="ROLL_MAX_SETPOINT" value="30." unit="deg"/>
<define name="PITCH_MAX_SETPOINT" value="30." unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-30." unit="deg"/>
<define name="ROLL_ATTITUDE_GAIN" value="11000."/>
<define name="ROLL_ATTITUDE_GAIN" value="8000."/>
<define name="ROLL_RATE_GAIN" value="1000."/>
<define name="ROLL_IGAIN" value="100."/>
<define name="ROLL_KFFA" value="0"/>

View File

@@ -0,0 +1,59 @@
# Hey Emacs, this is a -*- makefile -*-
#
# apogee_0.99_chibios.makefile
#
#
BOARD=apogee
BOARD_VERSION=0.99
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ARCH=stm32
ARCH_L=f4
ARCH_DIR=stm32
RTOS=chibios-libopencm3
SRC_ARCH=arch/$(ARCH_DIR)
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/stm32f4_chibios.ld
HARD_FLOAT=yes
# include Makefile.chibios-libopencm3 instead of Makefile.stm32
$(TARGET).MAKEFILE = chibios-libopencm3
# default flash mode is via usb dfu bootloader
# possibilities: DFU, SWD
FLASH_MODE ?= DFU
STLINK ?= y
DFU_UTIL ?= y
#
# default LED configuration
#
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 2
GPS_LED ?= none
SYS_TIME_LED ?= 1
#
# default MODEM and GPS configuration
#
MODEM_PORT ?= UART1
MODEM_BAUD ?= B57600
GPS_PORT ?= UART4
GPS_BAUD ?= B38400
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm

View File

@@ -0,0 +1,61 @@
# Hey Emacs, this is a -*- makefile -*-
#
# apogee_1.0_chibios.makefile
#
#
BOARD=apogee
BOARD_VERSION=1.0
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ARCH=stm32
ARCH_L=f4
ARCH_DIR=stm32
RTOS=chibios-libopencm3
SRC_ARCH=arch/$(ARCH_DIR)
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/stm32f4_chibios.ld
HARD_FLOAT=yes
# include Makefile.chibios-libopencm3 instead of Makefile.stm32
$(TARGET).MAKEFILE = chibios-libopencm3
# default flash mode is via usb dfu bootloader
# possibilities: DFU, SWD
FLASH_MODE ?= DFU
STLINK ?= y
DFU_UTIL ?= y
#
# default LED configuration
#
RADIO_CONTROL_LED ?= 4
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 2
GPS_LED ?= 3
SYS_TIME_LED ?= 1
#
# default UART configuration (modem, gps, spektrum)
#
MODEM_PORT ?= UART1
MODEM_BAUD ?= B57600
GPS_PORT ?= UART4
GPS_BAUD ?= B38400
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2
SBUS_PORT ?= UART2
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm

View File

@@ -0,0 +1,10 @@
# List of all the board related files.
CHIBIOSLIBSRC = ${CHIBIOS_LIB_DIR}/ringBuffer.c \
${CHIBIOS_LIB_DIR}/chibios_stub.c \
${CHIBIOS_LIB_DIR}/pprz_stub.c \
${CHIBIOS_LIB_DIR}/varLengthMsgQ.c \
${CHIBIOS_LIB_DIR}/rtcAccess.c \
${CHIBIOS_LIB_DIR}/sdLog.c \
${CHIBIOS_LIB_DIR}/chibios_sdlog.c \
${CHIBIOS_LIB_DIR}/sdio.c \
${CHIBIOS_LIB_DIR}/printf.c

View File

@@ -0,0 +1,24 @@
# Extra rules for ChibiOS rules.mk
#
# Initial directory tree is preserved for the build
#
ECOBJS = $(addprefix $(OBJDIR)/, $(ECSRC:.c=.o))
$(ECOBJS) : $(OBJDIR)/%.o : %.c Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
VPATH=
test -d $(dir $@) || mkdir -p $(dir $@)
$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@VPATH=
@test -d $(dir $@) || mkdir -p $(dir $@)
@$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
endif
OBJS += $(ECOBJS)
# *** EOF ***

View File

@@ -0,0 +1,228 @@
# ARM Cortex-Mx common makefile scripts and rules.
# Output directory and files
ifeq ($(BUILDDIR),)
BUILDDIR = build
endif
ifeq ($(BUILDDIR),.)
BUILDDIR = build
endif
OUTFILES = $(BUILDDIR)/$(PROJECT).elf $(BUILDDIR)/$(PROJECT).hex \
$(BUILDDIR)/$(PROJECT).bin $(BUILDDIR)/$(PROJECT).dmp
# Automatic compiler options
OPT = $(USE_OPT)
COPT = $(USE_COPT)
CPPOPT = $(USE_CPPOPT)
ifeq ($(USE_LINK_GC),yes)
OPT += -ffunction-sections -fdata-sections -fno-common
endif
# Source files groups and paths
ifeq ($(USE_THUMB),yes)
TCSRC += $(CSRC)
TCPPSRC += $(CPPSRC)
else
ACSRC += $(CSRC)
ACPPSRC += $(CPPSRC)
endif
ASRC = $(ACSRC)$(ACPPSRC)
TSRC = $(TCSRC)$(TCPPSRC)
SRCPATHS = $(sort $(dir $(ASMXSRC)) $(dir $(ASMSRC)) $(dir $(ASRC)) $(dir $(TSRC)))
# Various directories
OBJDIR = $(BUILDDIR)/obj
LSTDIR = $(BUILDDIR)/lst
# Object files groups
ACOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ACSRC:.c=.o)))
ACPPOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ACPPSRC:.cpp=.o)))
TCOBJS = $(addprefix $(OBJDIR)/, $(notdir $(TCSRC:.c=.o)))
TCPPOBJS = $(addprefix $(OBJDIR)/, $(notdir $(TCPPSRC:.cpp=.o)))
ASMOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ASMSRC:.s=.o)))
ASMXOBJS = $(addprefix $(OBJDIR)/, $(notdir $(ASMXSRC:.S=.o)))
OBJS = $(ASMXOBJS) $(ASMOBJS) $(ACOBJS) $(TCOBJS) $(ACPPOBJS) $(TCPPOBJS)
# Paths
IINCDIR = $(patsubst %,-I%,$(INCDIR) $(DINCDIR) $(UINCDIR))
LLIBDIR = $(patsubst %,-L%,$(DLIBDIR) $(ULIBDIR))
# Macros
DEFS = $(DDEFS) $(UDEFS)
ADEFS = $(DADEFS) $(UADEFS)
# Libs
LIBS = $(DLIBS) $(ULIBS)
# Various settings
MCFLAGS = -mcpu=$(MCU)
ODFLAGS = -x --syms
ASFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.s=.lst)) $(ADEFS)
ASXFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.S=.lst)) $(ADEFS)
CFLAGS = $(MCFLAGS) $(OPT) $(COPT) $(CWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.c=.lst)) $(DEFS)
CPPFLAGS = $(MCFLAGS) $(OPT) $(CPPOPT) $(CPPWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.cpp=.lst)) $(DEFS)
ifeq ($(USE_LINK_GC),yes)
LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch,--gc-sections $(LLIBDIR)
else
LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch $(LLIBDIR)
endif
# Thumb interwork enabled only if needed because it kills performance.
ifneq ($(TSRC),)
CFLAGS += -DTHUMB_PRESENT
CPPFLAGS += -DTHUMB_PRESENT
ASFLAGS += -DTHUMB_PRESENT
ifneq ($(ASRC),)
# Mixed ARM and THUMB mode.
CFLAGS += -mthumb-interwork
CPPFLAGS += -mthumb-interwork
ASFLAGS += -mthumb-interwork
LDFLAGS += -mthumb-interwork
else
# Pure THUMB mode, THUMB C code cannot be called by ARM asm code directly.
CFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING
CPPFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING
ASFLAGS += -mno-thumb-interwork -DTHUMB_NO_INTERWORKING -mthumb
LDFLAGS += -mno-thumb-interwork -mthumb
endif
else
# Pure ARM mode
CFLAGS += -mno-thumb-interwork
CPPFLAGS += -mno-thumb-interwork
ASFLAGS += -mno-thumb-interwork
LDFLAGS += -mno-thumb-interwork
endif
# Generate dependency information
#CFLAGS += -MD -MP -MF $(BUILDDIR)/.dep/$(@F).d
#CFLAGS += -MD -MP -MF .dep/$(@F).d
CPPFLAGS += -MD -MP -MF .dep/$(@F).d
# Paths where to search for sources
VPATH = $(SRCPATHS)
#
# Include user extra rules if any
#
ifneq ($(EXTRA_RULES_INCLUDE_PATH),)
include $(EXTRA_RULES_INCLUDE_PATH)
endif
#
# Makefile rules
#
all: $(OBJS) $(OUTFILES) MAKE_ALL_RULE_HOOK
MAKE_ALL_RULE_HOOK:
$(OBJS): | $(BUILDDIR)
$(BUILDDIR) $(OBJDIR) $(LSTDIR):
ifneq ($(USE_VERBOSE_COMPILE),yes)
@echo Compiler Options
@echo $(CC) -c $(CFLAGS) -I. $(IINCDIR) main.c -o main.o
@echo
endif
mkdir -p $(OBJDIR)
mkdir -p $(LSTDIR)
$(ACPPOBJS) : $(OBJDIR)/%.o : %.cpp Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(CPPC) -c $(CPPFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(CPPC) -c $(CPPFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
endif
$(TCPPOBJS) : $(OBJDIR)/%.o : %.cpp Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(CPPC) -c $(CPPFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(CPPC) -c $(CPPFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
endif
$(ACOBJS) : $(OBJDIR)/%.o : %.c Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(CC) -c $(CFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(CC) -c $(CFLAGS) $(AOPT) -I. $(IINCDIR) $< -o $@
endif
$(TCOBJS) : $(OBJDIR)/%.o : %.c Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(CC) -c $(CFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
endif
$(ASMOBJS) : $(OBJDIR)/%.o : %.s Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(AS) -c $(ASFLAGS) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(AS) -c $(ASFLAGS) -I. $(IINCDIR) $< -o $@
endif
$(ASMXOBJS) : $(OBJDIR)/%.o : %.S Makefile
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(CC) -c $(ASXFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
else
@echo Compiling $(<F)
@$(CC) -c $(ASXFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
endif
%.elf: $(OBJS) $(LDSCRIPT)
ifeq ($(USE_VERBOSE_COMPILE),yes)
@echo
$(LD) $(OBJS) $(LDFLAGS) $(LIBS) -o $@
else
@echo Linking $@
@$(LD) $(OBJS) $(LDFLAGS) $(LIBS) -o $@
endif
%.hex: %.elf $(LDSCRIPT)
ifeq ($(USE_VERBOSE_COMPILE),yes)
$(HEX) $< $@
else
@echo Creating $@
@$(HEX) $< $@
endif
%.bin: %.elf $(LDSCRIPT)
ifeq ($(USE_VERBOSE_COMPILE),yes)
$(BIN) $< $@
else
@echo Creating $@
@$(BIN) $< $@
endif
%.dmp: %.elf $(LDSCRIPT)
ifeq ($(USE_VERBOSE_COMPILE),yes)
$(OD) $(ODFLAGS) $< > $@
else
@echo Creating $@
@$(OD) $(ODFLAGS) $< > $@
@echo Done
endif
clean:
@echo Cleaning
-rm -fR .dep $(BUILDDIR)
@echo Done
#
# Include the dependency files, should be the last of the makefile
#
-include $(shell mkdir $(BUILDDIR)/.dep 2>/dev/null) $(wildcard $(BUILDDIR)/.dep/*)
# *** EOF ***

7
conf/chibios/fatfs.mk Normal file
View File

@@ -0,0 +1,7 @@
# FATFS files.
FATFSSRC = ${CHIBIOS}/os/various/fatfs_bindings/fatfs_diskio.c \
${CHIBIOS}/os/various/fatfs_bindings/fatfs_syscall.c \
${PAPARAZZI_SRC}/sw/ext/fatfs/src/ff.c \
${PAPARAZZI_SRC}/sw/ext/fatfs/src/option/ccsbcs.c
FATFSINC = ${PAPARAZZI_SRC}/sw/ext/fatfs/src

View File

@@ -99,7 +99,12 @@ endif
#
# Main
#
ns_srcs += $(SRC_FIRMWARE)/main.c
ifeq ($(RTOS), chibios-libopencm3)
ns_srcs += $(SRC_FIRMWARE)/main_chibios_libopencm3.c
ns_srcs += $(SRC_FIRMWARE)/chibios-libopencm3/chibios_init.c
else
ns_srcs += $(SRC_FIRMWARE)/main.c
endif
#
# LEDs

View File

@@ -70,6 +70,4 @@ warn_conf :
@echo '###########################################################'
@echo
clean :
$(Q)rm -f *~ a.out *.elf
.PHONY: clean

View File

@@ -67,5 +67,14 @@ PRINT_CONFIG_MSG("Using 16MHz external clock to PLL it to 168MHz.")
#else
#error EXT_CLK is either set to an unsupported frequency or not defined at all. Please check!
#endif
/* Configure priority grouping 0 bits for pre-emption priority and 4 bits for sub-priority.
* this was previously in i2c driver
* FIXME is it really needed ?
*/
#ifndef RTOS_IS_CHIBIOS
scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16);
#endif
}

View File

@@ -455,6 +455,8 @@ static inline enum STMI2CSubTransactionStatus stmi2c_readmany(uint32_t i2c, stru
PPRZ_I2C_SEND_STOP(i2c);
__I2C_REG_CRITICAL_ZONE_STOP;
// --- end of critical zone -----------
// Document the current Status
@@ -908,9 +910,6 @@ void i2c1_hw_init(void) {
/* reset peripheral to default state ( sometimes not achieved on reset :( ) */
//i2c_reset(I2C1);
/* Configure priority grouping 0 bits for pre-emption priority and 4 bits for sub-priority. */
scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16);
/* Configure and enable I2C1 event interrupt --------------------------------*/
nvic_set_priority(NVIC_I2C1_EV_IRQ, NVIC_I2C1_IRQ_PRIO);
nvic_enable_irq(NVIC_I2C1_EV_IRQ);
@@ -997,9 +996,6 @@ void i2c2_hw_init(void) {
/* reset peripheral to default state ( sometimes not achieved on reset :( ) */
//i2c_reset(I2C2);
/* Configure priority grouping 0 bits for pre-emption priority and 4 bits for sub-priority. */
scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16);
/* Configure and enable I2C2 event interrupt --------------------------------*/
nvic_set_priority(NVIC_I2C2_EV_IRQ, NVIC_I2C2_IRQ_PRIO);
nvic_enable_irq(NVIC_I2C2_EV_IRQ);
@@ -1087,9 +1083,6 @@ void i2c3_hw_init(void) {
/* reset peripheral to default state ( sometimes not achieved on reset :( ) */
//i2c_reset(I2C3);
/* Configure priority grouping 0 bits for pre-emption priority and 4 bits for sub-priority. */
scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16);
/* Configure and enable I2C3 event interrupt --------------------------------*/
nvic_set_priority(NVIC_I2C3_EV_IRQ, NVIC_I2C3_IRQ_PRIO);
nvic_enable_irq(NVIC_I2C3_EV_IRQ);

View File

@@ -35,19 +35,26 @@
#include "led.h"
#endif
#ifndef USE_OCM3_SYSTICK_INIT
#define USE_OCM3_SYSTICK_INIT 1
#endif
void sys_tick_handler(void);
/** Initialize SysTick.
* Generate SysTick interrupt every sys_time.resolution_cpu_ticks
*/
void sys_time_arch_init( void ) {
/* run cortex systick timer with 72MHz */
/* run cortex systick timer with 72MHz (FIXME only 72 or does it work with 168MHz???) */
#if USE_OCM3_SYSTICK_INIT
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB);
#endif
sys_time.cpu_ticks_per_sec = AHB_CLK;
/* cpu ticks per desired sys_time timer step */
sys_time.resolution_cpu_ticks = (uint32_t)(sys_time.resolution * sys_time.cpu_ticks_per_sec + 0.5);
#if USE_OCM3_SYSTICK_INIT
/* The timer interrupt is activated on the transition from 1 to 0,
* therefore it activates every n+1 clock ticks.
*/
@@ -55,6 +62,7 @@ void sys_time_arch_init( void ) {
systick_interrupt_enable();
systick_counter_enable();
#endif
}
@@ -65,10 +73,12 @@ void sys_time_arch_init( void ) {
//
void sys_tick_handler(void) {
sys_time.nb_tick++;
sys_time.nb_sec_rem += sys_time.resolution_cpu_ticks;
if (sys_time.nb_sec_rem >= sys_time.cpu_ticks_per_sec) {
sys_time.nb_sec_rem -= sys_time.cpu_ticks_per_sec;
sys_time.nb_sec++;
#ifdef SYS_TIME_LED
LED_TOGGLE(SYS_TIME_LED);
#endif

View File

@@ -38,6 +38,9 @@
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/cm3/systick.h>
#include "std.h"
#ifdef RTOS_IS_CHIBIOS
#include "chibios_stub.h"
#endif
/**
* Get the time in microseconds since startup.
@@ -45,9 +48,13 @@
* @return current system time as uint32_t
*/
static inline uint32_t get_sys_time_usec(void) {
#ifdef RTOS_IS_CHIBIOS
return chibios_chTimeNow();
#else
return sys_time.nb_sec * 1000000 +
usec_of_cpu_ticks(sys_time.nb_sec_rem) +
usec_of_cpu_ticks(systick_get_reload() - systick_get_value());
#endif
}
/* Generic timer macros */
@@ -60,6 +67,9 @@ static inline uint32_t get_sys_time_usec(void) {
* 2^32 / 1000000 = 4294s = ~72min
*/
static inline void sys_time_usleep(uint32_t us) {
#ifdef RTOS_IS_CHIBIOS
chibios_chThdSleepMicroseconds (us);
#else
/* duration and end time in SYS_TIME_TICKS */
uint32_t d_sys_ticks = sys_time_ticks_of_usec(us);
uint32_t end_nb_tick = sys_time.nb_tick + d_sys_ticks;
@@ -73,6 +83,7 @@ static inline void sys_time_usleep(uint32_t us) {
while (sys_time.nb_tick < end_nb_tick);
/* then wait remaining cpu ticks */
while (systick_get_value() > end_cpu_ticks);
#endif
}
#endif /* SYS_TIME_ARCH_H */

View File

@@ -0,0 +1,199 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* ST32F407xG memory setup.
*/
/*
__main_stack_size__ is the size of INTERRUPTS stack
__process_stack_size__ is the stack of the C-runtime
*/
__main_stack_size__ = 0x01000;
__process_stack_size__ = 0x02000;
MEMORY
{
flash : org = 0x08000000, len = 1M-128k
eemul : org = 0x080E0000, len = 128k
/* ram : org = 0x20000000, len = 112k */
/* ethram : org = 0x2001C000, len = 16k */
ram : org = 0x20000000, len = 128k
ccmram : org = 0x10000000, len = 64k
bkpsram : org = 0x40024000, len = 4k
}
__ram_start__ = ORIGIN(ram);
__ram_size__ = LENGTH(ram);
__ram_end__ = __ram_start__ + __ram_size__;
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(vectors))
} > flash
constructors : ALIGN(4) SUBALIGN(4)
{
PROVIDE(__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE(__init_array_end = .);
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
PROVIDE(__fini_array_start = .);
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
PROVIDE(__fini_array_end = .);
} > flash
.text : ALIGN(16) SUBALIGN(16)
{
*(.text.startup.*)
*(.text)
*(.text.*)
*(.rodata)
*(.rodata.*)
*(.glue_7t)
*(.glue_7)
*(.gcc*)
} > flash
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > flash
.ARM.exidx : {
PROVIDE(__exidx_start = .);
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
PROVIDE(__exidx_end = .);
} > flash
.eh_frame_hdr :
{
*(.eh_frame_hdr)
} > flash
.eh_frame : ONLY_IF_RO
{
*(.eh_frame)
} > flash
.textalign : ONLY_IF_RO
{
. = ALIGN(8);
} > flash
. = ALIGN(4);
_etext = .;
_textdata = _etext;
.stacks :
{
. = ALIGN(8);
__main_stack_base__ = .;
. += __main_stack_size__;
. = ALIGN(8);
__main_stack_end__ = .;
__process_stack_base__ = .;
__main_thread_stack_base__ = .;
. += __process_stack_size__;
. = ALIGN(8);
__process_stack_end__ = .;
__main_thread_stack_end__ = .;
} > ram
.ccm (NOLOAD):
{
. = ALIGN(4);
*(.ccmram)
. = ALIGN(4);
} > ccmram
.bkp (NOLOAD):
{
. = ALIGN(4);
*(.bkpsram)
. = ALIGN(4);
} > bkpsram
/* .ccm : */
/* { */
/* PROVIDE(_cmm_start = .); */
/* . = ALIGN(4); */
/* *(.bss.mainthread.*) */
/* . = ALIGN(4); */
/* *(.bss._idle_thread_wa) */
/* . = ALIGN(4); */
/* *(.bss.rlist) */
/* . = ALIGN(4); */
/* *(.bss.vtlist) */
/* . = ALIGN(4); */
/* *(.bss.endmem) */
/* . = ALIGN(4); */
/* *(.bss.nextmem) */
/* . = ALIGN(4); */
/* *(.bss.default_heap) */
/* . = ALIGN(4); */
/* PROVIDE(_cmmend = .); */
/* } > ccmram */
.data :
{
. = ALIGN(4);
PROVIDE(_data = .);
*(.data)
. = ALIGN(4);
*(.data.*)
. = ALIGN(4);
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
} > ram AT > flash
.bss :
{
. = ALIGN(4);
PROVIDE(_bss_start = .);
*(.bss)
. = ALIGN(4);
*(.bss.*)
. = ALIGN(4);
*(COMMON)
. = ALIGN(4);
PROVIDE(_bss_end = .);
} > ram
}
PROVIDE(end = .);
_end = .;
__heap_base__ = _end;
__heap_end__ = __ram_end__;

View File

@@ -0,0 +1,380 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012,2013 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
File is modified to route IRQ_HANDLERS to opencm3 handlers
*/
#include "stm32f4_chibios_vectors.h"
#include "mcuconf.h"
/**
* @file GCC/ARMCMx/STM32F4xx/vectors.c
* @brief Interrupt vectors for the STM32F4xx family.
*
* @defgroup ARMCMx_STM32F4xx_VECTORS STM32F4xx Interrupt Vectors
* @ingroup ARMCMx_SPECIFIC
* @details Interrupt vectors for the STM32F4xx family.
* @{
*/
#include <ch.h>
/**
* @brief Type of an IRQ vector.
*/
typedef void (*irq_vector_t)(void);
enum HardwareFaultType {HardwareFault_NONE, HardwareFault_BUS, HardwareFault_MEM, HardwareFault_USAGE};
static enum HardwareFaultType hardwareFaultType = HardwareFault_NONE;
void prvGetRegistersFromStack( uint32_t *pulFaultStackAddress ) __attribute__((unused));
/**
* @brief Type of a structure representing the whole vectors table.
*/
typedef struct {
uint32_t *init_stack;
irq_vector_t reset_vector;
irq_vector_t nmi_vector;
irq_vector_t hardfault_vector;
irq_vector_t memmanage_vector;
irq_vector_t busfault_vector;
irq_vector_t usagefault_vector;
irq_vector_t vector1c;
irq_vector_t vector20;
irq_vector_t vector24;
irq_vector_t vector28;
irq_vector_t svcall_vector;
irq_vector_t debugmonitor_vector;
irq_vector_t vector34;
irq_vector_t pendsv_vector;
irq_vector_t systick_vector;
irq_vector_t vectors[82];
} vectors_t;
#if !defined(__DOXYGEN__)
extern uint32_t __main_stack_end__;
extern void ResetHandler(void);
extern void NMIVector(void);
extern void HardFaultVector(void);
extern void MemManageVector(void);
extern void BusFaultVector(void);
extern void UsageFaultVector(void);
extern void Vector1C(void);
extern void Vector20(void);
extern void Vector24(void);
extern void Vector28(void);
extern void SVCallVector(void);
extern void DebugMonitorVector(void);
extern void Vector34(void);
extern void PendSVVector(void);
extern void SysTickVector(void);
extern void Vector40(void);
extern void Vector44(void);
extern void Vector48(void);
extern void Vector4C(void);
extern void Vector50(void);
extern void Vector54(void);
extern void Vector58(void);
extern void Vector5C(void);
extern void Vector60(void);
extern void Vector64(void);
extern void Vector68(void);
extern void Vector6C(void);
extern void Vector70(void);
extern void Vector74(void);
extern void Vector78(void);
extern void Vector7C(void);
extern void Vector80(void);
extern void Vector84(void);
extern void Vector88(void);
extern void Vector8C(void);
extern void Vector90(void);
extern void Vector94(void);
extern void Vector98(void);
extern void Vector9C(void);
extern void VectorA0(void);
extern void VectorA4(void);
extern void VectorA8(void);
extern void VectorAC(void);
extern void VectorB0(void);
extern void VectorB4(void);
extern void VectorB8(void);
extern void VectorBC(void);
extern void VectorC0(void);
extern void VectorC4(void);
extern void VectorC8(void);
extern void VectorCC(void);
extern void VectorD0(void);
extern void VectorD4(void);
extern void VectorD8(void);
extern void VectorDC(void);
extern void VectorE0(void);
extern void VectorE4(void);
extern void VectorE8(void);
extern void VectorEC(void);
extern void VectorF0(void);
extern void VectorF4(void);
extern void VectorF8(void);
extern void VectorFC(void);
extern void Vector100(void);
extern void Vector104(void);
extern void Vector108(void);
extern void Vector10C(void);
extern void Vector110(void);
extern void Vector114(void);
extern void Vector118(void);
extern void Vector11C(void);
extern void Vector120(void);
extern void Vector124(void);
extern void Vector128(void);
extern void Vector12C(void);
extern void Vector130(void);
extern void Vector134(void);
extern void Vector138(void);
extern void Vector13C(void);
extern void Vector140(void);
extern void Vector144(void);
extern void Vector148(void);
extern void Vector14C(void);
extern void Vector150(void);
extern void Vector154(void);
extern void Vector158(void);
extern void Vector15C(void);
extern void Vector160(void);
extern void Vector164(void);
extern void Vector168(void);
extern void Vector16C(void);
extern void Vector170(void);
extern void Vector174(void);
extern void Vector178(void);
extern void Vector17C(void);
extern void Vector180(void);
extern void Vector184(void);
#endif
/**
* @brief STM32 vectors table.
*/
#if !defined(__DOXYGEN__)
__attribute__ ((used, section("vectors")))
#endif
vectors_t _vectors = {
&__main_stack_end__,ResetHandler, NMIVector, HardFaultVector,
MemManageVector, BusFaultVector, UsageFaultVector, Vector1C,
Vector20, Vector24, Vector28, SVCallVector,
DebugMonitorVector, Vector34, PendSVVector, SysTickVector,
{
DECLARE_IRQS
}
};
/**
* @brief Unhandled exceptions handler.
* @details Any undefined exception vector points to this function by default.
* This function simply stops the system into an infinite loop.
*
* @notapi
*/
static void _unhandled_exception ( void ) __attribute__( ( naked ) );
void _unhandled_exception (void) {
__asm volatile
(
" tst lr, #4 \n"
" ite eq \n"
" mrseq r0, msp \n"
" mrsne r0, psp \n"
" ldr r1, [r0, #24] \n"
" ldr r2, handler2_address_const \n"
" bx r2 \n"
" handler2_address_const: .word prvGetRegistersFromStack \n"
);
}
void _unhandled_exception_NMIVector(void) {
while (TRUE);
}
void _unhandled_exception_MemManageVector(void) {
hardwareFaultType = HardwareFault_MEM;
_unhandled_exception();
}
void _unhandled_exception_BusFaultVector(void) {
hardwareFaultType = HardwareFault_BUS;
_unhandled_exception();
}
void _unhandled_exception_UsageFaultVector(void) {
hardwareFaultType = HardwareFault_USAGE;
_unhandled_exception();
}
void NMIVector(void) __attribute__((weak, alias("_unhandled_exception_NMIVector")));
void HardFaultVector(void) __attribute__((weak, alias("_unhandled_exception")));
void MemManageVector(void) __attribute__((weak, alias("_unhandled_exception_MemManageVector")));
void BusFaultVector(void) __attribute__((weak, alias("_unhandled_exception_BusFaultVector")));
void UsageFaultVector(void) __attribute__((weak, alias("_unhandled_exception_UsageFaultVector")));
void Vector1C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector20(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector24(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector28(void) __attribute__((weak, alias("_unhandled_exception")));
void SVCallVector(void) __attribute__((weak, alias("_unhandled_exception")));
void DebugMonitorVector(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector34(void) __attribute__((weak, alias("_unhandled_exception")));
void PendSVVector(void) __attribute__((weak, alias("_unhandled_exception")));
void SysTickVector(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector40(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector44(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector48(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector4C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector50(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector54(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector58(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector5C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector60(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector64(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector68(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector6C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector70(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector74(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector78(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector7C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector80(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector84(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector88(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector8C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector90(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector94(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector98(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector9C(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorA0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorA4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorA8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorAC(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorB0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorB4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorB8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorBC(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorC0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorC4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorC8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorCC(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorD0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorD4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorD8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorDC(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorE0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorE4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorE8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorEC(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorF0(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorF4(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorF8(void) __attribute__((weak, alias("_unhandled_exception")));
void VectorFC(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector100(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector104(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector108(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector10C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector110(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector114(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector118(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector11C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector120(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector124(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector128(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector12C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector130(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector134(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector138(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector13C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector140(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector144(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector148(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector14C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector150(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector154(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector158(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector15C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector160(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector164(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector168(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector16C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector170(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector174(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector178(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector17C(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector180(void) __attribute__((weak, alias("_unhandled_exception")));
void Vector184(void) __attribute__((weak, alias("_unhandled_exception")));
void prvGetRegistersFromStack( uint32_t *pulFaultStackAddress )
{
/* These are volatile to try and prevent the compiler/linker optimising them
away as the variables never actually get used. If the debugger won't show the
values of the variables, make them global my moving their declaration outside
of this function. */
/*
When entering hard fault, the stm32 push the value of register on the stack, and loop forever.
You can easily retrieve address of faulty instruction in variable pc,
status in variable psr.
in gdb, after when hard-fault is triggered, you just have to type some commands :
° print /x pc => retrieve instruction
° info line *pc : see the source code of the line which has triggered exception
° disassemble pc : see the assembly of the address which has triggered exception
*/
volatile uint32_t r0 __attribute__((unused));
volatile uint32_t r1 __attribute__((unused));
volatile uint32_t r2 __attribute__((unused));
volatile uint32_t r3 __attribute__((unused));
volatile uint32_t r12 __attribute__((unused));
volatile uint32_t lr __attribute__((unused)); /* Link register. */
volatile uint32_t pc __attribute__((unused)); /* Program counter. */
volatile uint32_t psr __attribute__((unused));/* Program status register. */
r0 = pulFaultStackAddress[ 0 ];
r1 = pulFaultStackAddress[ 1 ];
r2 = pulFaultStackAddress[ 2 ];
r3 = pulFaultStackAddress[ 3 ];
r12 = pulFaultStackAddress[ 4 ];
lr = pulFaultStackAddress[ 5 ];
pc = pulFaultStackAddress[ 6 ];
psr = pulFaultStackAddress[ 7 ];
/* When the following line is hit, the variables contain the register values. */
while (1);
}
/** @} */

View File

@@ -0,0 +1,348 @@
#pragma once
/*
# ______
# | ____|
# | |__ _ __ ___ _ __ ___
# | __| | '__| / _ \ | '_ ` _ \
# | | | | | (_) | | | | | | |
# |_| |_| \___/ |_| |_| |_|
# ____ _ __ _____ __ __ ____
# / __ \ | '_ \ / ____| | \/ | |___ \
# | | | | | |_) | ___ _ __ | | | \ / | __) |
# | | | | | .__/ / _ \ | '_ \ | | | |\/| | |__ <
# | |__| | | | | __/ | | | | | |____ | | | | ___) |
# \____/ |_| \___| |_| |_| \_____| |_| |_| |____/
*/
#define NVIC_NVIC_WWDG_IRQ 0
#define NVIC_PVD_IRQ 1
#define NVIC_TAMP_STAMP_IRQ 2
#define NVIC_RTC_WKUP_IRQ 3
#define NVIC_FLASH_IRQ 4
#define NVIC_RCC_IRQ 5
#define NVIC_EXTI0_IRQ 6
#define NVIC_EXTI1_IRQ 7
#define NVIC_EXTI2_IRQ 8
#define NVIC_EXTI3_IRQ 9
#define NVIC_EXTI4_IRQ 10
#define NVIC_DMA1_STREAM0_IRQ 11
#define NVIC_DMA1_STREAM1_IRQ 12
#define NVIC_DMA1_STREAM2_IRQ 13
#define NVIC_DMA1_STREAM3_IRQ 14
#define NVIC_DMA1_STREAM4_IRQ 15
#define NVIC_DMA1_STREAM5_IRQ 16
#define NVIC_DMA1_STREAM6_IRQ 17
#define NVIC_ADC_IRQ 18
#define NVIC_CAN1_TX_IRQ 19
#define NVIC_CAN1_RX0_IRQ 20
#define NVIC_CAN1_RX1_IRQ 21
#define NVIC_CAN1_SCE_IRQ 22
#define NVIC_EXTI9_5_IRQ 23
#define NVIC_TIM1_BRK_TIM9_IRQ 24
#define NVIC_TIM1_UP_TIM10_IRQ 25
#define NVIC_TIM1_TRG_COM_TIM11_IRQ 26
#define NVIC_TIM1_CC_IRQ 27
#define NVIC_TIM2_IRQ 28
#define NVIC_TIM3_IRQ 29
#define NVIC_TIM4_IRQ 30
#define NVIC_I2C1_EV_IRQ 31
#define NVIC_I2C1_ER_IRQ 32
#define NVIC_I2C2_EV_IRQ 33
#define NVIC_I2C2_ER_IRQ 34
#define NVIC_SPI1_IRQ 35
#define NVIC_SPI2_IRQ 36
#define NVIC_USART1_IRQ 37
#define NVIC_USART2_IRQ 38
#define NVIC_USART3_IRQ 39
#define NVIC_EXTI15_10_IRQ 40
#define NVIC_RTC_ALARM_IRQ 41
#define NVIC_USB_FS_WKUP_IRQ 42
#define NVIC_TIM8_BRK_TIM12_IRQ 43
#define NVIC_TIM8_UP_TIM13_IRQ 44
#define NVIC_TIM8_TRG_COM_TIM14_IRQ 45
#define NVIC_TIM8_CC_IRQ 46
#define NVIC_DMA1_STREAM7_IRQ 47
#define NVIC_FSMC_IRQ 48
#define NVIC_SDIO_IRQ 49
#define NVIC_TIM5_IRQ 50
#define NVIC_SPI3_IRQ 51
#define NVIC_UART4_IRQ 52
#define NVIC_UART5_IRQ 53
#define NVIC_TIM6_DAC_IRQ 54
#define NVIC_TIM7_IRQ 55
#define NVIC_DMA2_STREAM0_IRQ 56
#define NVIC_DMA2_STREAM1_IRQ 57
#define NVIC_DMA2_STREAM2_IRQ 58
#define NVIC_DMA2_STREAM3_IRQ 59
#define NVIC_DMA2_STREAM4_IRQ 60
#define NVIC_ETH_IRQ 61
#define NVIC_ETH_WKUP_IRQ 62
#define NVIC_CAN2_TX_IRQ 63
#define NVIC_CAN2_RX0_IRQ 64
#define NVIC_CAN2_RX1_IRQ 65
#define NVIC_CAN2_SCE_IRQ 66
#define NVIC_OTG_FS_IRQ 67
#define NVIC_DMA2_STREAM5_IRQ 68
#define NVIC_DMA2_STREAM6_IRQ 69
#define NVIC_DMA2_STREAM7_IRQ 70
#define NVIC_USART6_IRQ 71
#define NVIC_I2C3_EV_IRQ 72
#define NVIC_I2C3_ER_IRQ 73
#define NVIC_OTG_HS_EP1_OUT_IRQ 74
#define NVIC_OTG_HS_EP1_IN_IRQ 75
#define NVIC_OTG_HS_WKUP_IRQ 76
#define NVIC_OTG_HS_IRQ 77
#define NVIC_DCMI_IRQ 78
#define NVIC_CRYP_IRQ 79
#define NVIC_HASH_RNG_IRQ 80
#define NVIC_IRQ_COUNT 81
#define CM3_WEAK extern void __attribute__ ((weak))
CM3_WEAK nvic_wwdg_isr(void);
CM3_WEAK pvd_isr(void);
CM3_WEAK tamp_stamp_isr(void);
CM3_WEAK rtc_wkup_isr(void);
CM3_WEAK flash_isr(void);
CM3_WEAK rcc_isr(void);
CM3_WEAK exti0_isr(void);
CM3_WEAK exti1_isr(void);
CM3_WEAK exti2_isr(void);
CM3_WEAK exti3_isr(void);
CM3_WEAK exti4_isr(void);
CM3_WEAK dma1_stream0_isr(void);
CM3_WEAK dma1_stream1_isr(void);
CM3_WEAK dma1_stream2_isr(void);
CM3_WEAK dma1_stream3_isr(void);
CM3_WEAK dma1_stream4_isr(void);
CM3_WEAK dma1_stream5_isr(void);
CM3_WEAK dma1_stream6_isr(void);
CM3_WEAK adc_isr(void);
CM3_WEAK can1_tx_isr(void);
CM3_WEAK can1_rx0_isr(void);
CM3_WEAK can1_rx1_isr(void);
CM3_WEAK can1_sce_isr(void);
CM3_WEAK exti9_5_isr(void);
CM3_WEAK tim1_brk_tim9_isr(void);
CM3_WEAK tim1_up_tim10_isr(void);
CM3_WEAK tim1_trg_com_tim11_isr(void);
CM3_WEAK tim1_cc_isr(void);
CM3_WEAK tim2_isr(void);
CM3_WEAK tim3_isr(void);
CM3_WEAK tim4_isr(void);
CM3_WEAK i2c1_ev_isr(void);
CM3_WEAK i2c1_er_isr(void);
CM3_WEAK i2c2_ev_isr(void);
CM3_WEAK i2c2_er_isr(void);
CM3_WEAK spi1_isr(void);
CM3_WEAK spi2_isr(void);
CM3_WEAK usart1_isr(void);
CM3_WEAK usart2_isr(void);
CM3_WEAK usart3_isr(void);
CM3_WEAK exti15_10_isr(void);
CM3_WEAK rtc_alarm_isr(void);
CM3_WEAK usb_fs_wkup_isr(void);
CM3_WEAK tim8_brk_tim12_isr(void);
CM3_WEAK tim8_up_tim13_isr(void);
CM3_WEAK tim8_trg_com_tim14_isr(void);
CM3_WEAK tim8_cc_isr(void);
CM3_WEAK dma1_stream7_isr(void);
CM3_WEAK fsmc_isr(void);
CM3_WEAK sdio_isr(void);
CM3_WEAK tim5_isr(void);
CM3_WEAK spi3_isr(void);
CM3_WEAK uart4_isr(void);
CM3_WEAK uart5_isr(void);
CM3_WEAK tim6_dac_isr(void);
CM3_WEAK tim7_isr(void);
CM3_WEAK dma2_stream0_isr(void);
CM3_WEAK dma2_stream1_isr(void);
CM3_WEAK dma2_stream2_isr(void);
CM3_WEAK dma2_stream3_isr(void);
CM3_WEAK dma2_stream4_isr(void);
CM3_WEAK eth_isr(void);
CM3_WEAK eth_wkup_isr(void);
CM3_WEAK can2_tx_isr(void);
CM3_WEAK can2_rx0_isr(void);
CM3_WEAK can2_rx1_isr(void);
CM3_WEAK can2_sce_isr(void);
CM3_WEAK otg_fs_isr(void);
CM3_WEAK dma2_stream5_isr(void);
CM3_WEAK dma2_stream6_isr(void);
CM3_WEAK dma2_stream7_isr(void);
CM3_WEAK usart6_isr(void);
CM3_WEAK i2c3_ev_isr(void);
CM3_WEAK i2c3_er_isr(void);
CM3_WEAK otg_hs_ep1_out_isr(void);
CM3_WEAK otg_hs_ep1_in_isr(void);
CM3_WEAK otg_hs_wkup_isr(void);
CM3_WEAK otg_hs_isr(void);
CM3_WEAK dcmi_isr(void);
CM3_WEAK cryp_isr(void);
CM3_WEAK hash_rng_isr(void);
#define NVIC_NVIC_WWDG_IRQ_VEC_CHIBIOS Vector40
#define NVIC_NVIC_WWDG_IRQ_VEC_OPENCM3 nvic_wwdg_isr
#define NVIC_PVD_IRQ_VEC_CHIBIOS Vector44
#define NVIC_PVD_IRQ_VEC_OPENCM3 pvd_isr
#define NVIC_TAMP_STAMP_IRQ_VEC_CHIBIOS Vector48
#define NVIC_TAMP_STAMP_IRQ_VEC_OPENCM3 tamp_stamp_isr
#define NVIC_RTC_WKUP_IRQ_VEC_CHIBIOS Vector4C
#define NVIC_RTC_WKUP_IRQ_VEC_OPENCM3 rtc_wkup_isr
#define NVIC_FLASH_IRQ_VEC_CHIBIOS Vector50
#define NVIC_FLASH_IRQ_VEC_OPENCM3 flash_isr
#define NVIC_RCC_IRQ_VEC_CHIBIOS Vector54
#define NVIC_RCC_IRQ_VEC_OPENCM3 rcc_isr
#define NVIC_EXTI0_IRQ_VEC_CHIBIOS Vector58
#define NVIC_EXTI0_IRQ_VEC_OPENCM3 exti0_isr
#define NVIC_EXTI1_IRQ_VEC_CHIBIOS Vector5C
#define NVIC_EXTI1_IRQ_VEC_OPENCM3 exti1_isr
#define NVIC_EXTI2_IRQ_VEC_CHIBIOS Vector60
#define NVIC_EXTI2_IRQ_VEC_OPENCM3 exti2_isr
#define NVIC_EXTI3_IRQ_VEC_CHIBIOS Vector64
#define NVIC_EXTI3_IRQ_VEC_OPENCM3 exti3_isr
#define NVIC_EXTI4_IRQ_VEC_CHIBIOS Vector68
#define NVIC_EXTI4_IRQ_VEC_OPENCM3 exti4_isr
#define NVIC_DMA1_STREAM0_IRQ_VEC_CHIBIOS Vector6C
#define NVIC_DMA1_STREAM0_IRQ_VEC_OPENCM3 dma1_stream0_isr
#define NVIC_DMA1_STREAM1_IRQ_VEC_CHIBIOS Vector70
#define NVIC_DMA1_STREAM1_IRQ_VEC_OPENCM3 dma1_stream1_isr
#define NVIC_DMA1_STREAM2_IRQ_VEC_CHIBIOS Vector74
#define NVIC_DMA1_STREAM2_IRQ_VEC_OPENCM3 dma1_stream2_isr
#define NVIC_DMA1_STREAM3_IRQ_VEC_CHIBIOS Vector78
#define NVIC_DMA1_STREAM3_IRQ_VEC_OPENCM3 dma1_stream3_isr
#define NVIC_DMA1_STREAM4_IRQ_VEC_CHIBIOS Vector7C
#define NVIC_DMA1_STREAM4_IRQ_VEC_OPENCM3 dma1_stream4_isr
#define NVIC_DMA1_STREAM5_IRQ_VEC_CHIBIOS Vector80
#define NVIC_DMA1_STREAM5_IRQ_VEC_OPENCM3 dma1_stream5_isr
#define NVIC_DMA1_STREAM6_IRQ_VEC_CHIBIOS Vector84
#define NVIC_DMA1_STREAM6_IRQ_VEC_OPENCM3 dma1_stream6_isr
#define NVIC_ADC_IRQ_VEC_CHIBIOS Vector88
#define NVIC_ADC_IRQ_VEC_OPENCM3 adc_isr
#define NVIC_CAN1_TX_IRQ_VEC_CHIBIOS Vector8C
#define NVIC_CAN1_TX_IRQ_VEC_OPENCM3 can1_tx_isr
#define NVIC_CAN1_RX0_IRQ_VEC_CHIBIOS Vector90
#define NVIC_CAN1_RX0_IRQ_VEC_OPENCM3 can1_rx0_isr
#define NVIC_CAN1_RX1_IRQ_VEC_CHIBIOS Vector94
#define NVIC_CAN1_RX1_IRQ_VEC_OPENCM3 can1_rx1_isr
#define NVIC_CAN1_SCE_IRQ_VEC_CHIBIOS Vector98
#define NVIC_CAN1_SCE_IRQ_VEC_OPENCM3 can1_sce_isr
#define NVIC_EXTI9_5_IRQ_VEC_CHIBIOS Vector9C
#define NVIC_EXTI9_5_IRQ_VEC_OPENCM3 exti9_5_isr
#define NVIC_TIM1_BRK_TIM9_IRQ_VEC_CHIBIOS VectorA0
#define NVIC_TIM1_BRK_TIM9_IRQ_VEC_OPENCM3 tim1_brk_tim9_isr
#define NVIC_TIM1_UP_TIM10_IRQ_VEC_CHIBIOS VectorA4
#define NVIC_TIM1_UP_TIM10_IRQ_VEC_OPENCM3 tim1_up_tim10_isr
#define NVIC_TIM1_TRG_COM_TIM11_IRQ_VEC_CHIBIOS VectorA8
#define NVIC_TIM1_TRG_COM_TIM11_IRQ_VEC_OPENCM3 tim1_trg_com_tim11_isr
#define NVIC_TIM1_CC_IRQ_VEC_CHIBIOS VectorAC
#define NVIC_TIM1_CC_IRQ_VEC_OPENCM3 tim1_cc_isr
#define NVIC_TIM2_IRQ_VEC_CHIBIOS VectorB0
#define NVIC_TIM2_IRQ_VEC_OPENCM3 tim2_isr
#define NVIC_TIM3_IRQ_VEC_CHIBIOS VectorB4
#define NVIC_TIM3_IRQ_VEC_OPENCM3 tim3_isr
#define NVIC_TIM4_IRQ_VEC_CHIBIOS VectorB8
#define NVIC_TIM4_IRQ_VEC_OPENCM3 tim4_isr
#define NVIC_I2C1_EV_IRQ_VEC_CHIBIOS VectorBC
#define NVIC_I2C1_EV_IRQ_VEC_OPENCM3 i2c1_ev_isr
#define NVIC_I2C1_ER_IRQ_VEC_CHIBIOS VectorC0
#define NVIC_I2C1_ER_IRQ_VEC_OPENCM3 i2c1_er_isr
#define NVIC_I2C2_EV_IRQ_VEC_CHIBIOS VectorC4
#define NVIC_I2C2_EV_IRQ_VEC_OPENCM3 i2c2_ev_isr
#define NVIC_I2C2_ER_IRQ_VEC_CHIBIOS VectorC8
#define NVIC_I2C2_ER_IRQ_VEC_OPENCM3 i2c2_er_isr
#define NVIC_SPI1_IRQ_VEC_CHIBIOS VectorCC
#define NVIC_SPI1_IRQ_VEC_OPENCM3 spi1_isr
#define NVIC_SPI2_IRQ_VEC_CHIBIOS VectorD0
#define NVIC_SPI2_IRQ_VEC_OPENCM3 spi2_isr
#define NVIC_USART1_IRQ_VEC_CHIBIOS VectorD4
#define NVIC_USART1_IRQ_VEC_OPENCM3 usart1_isr
#define NVIC_USART2_IRQ_VEC_CHIBIOS VectorD8
#define NVIC_USART2_IRQ_VEC_OPENCM3 usart2_isr
#define NVIC_USART3_IRQ_VEC_CHIBIOS VectorDC
#define NVIC_USART3_IRQ_VEC_OPENCM3 usart3_isr
#define NVIC_EXTI15_10_IRQ_VEC_CHIBIOS VectorE0
#define NVIC_EXTI15_10_IRQ_VEC_OPENCM3 exti15_10_isr
#define NVIC_RTC_ALARM_IRQ_VEC_CHIBIOS VectorE4
#define NVIC_RTC_ALARM_IRQ_VEC_OPENCM3 rtc_alarm_isr
#define NVIC_USB_FS_WKUP_IRQ_VEC_CHIBIOS VectorE8
#define NVIC_USB_FS_WKUP_IRQ_VEC_OPENCM3 usb_fs_wkup_isr
#define NVIC_TIM8_BRK_TIM12_IRQ_VEC_CHIBIOS VectorEC
#define NVIC_TIM8_BRK_TIM12_IRQ_VEC_OPENCM3 tim8_brk_tim12_isr
#define NVIC_TIM8_UP_TIM13_IRQ_VEC_CHIBIOS VectorF0
#define NVIC_TIM8_UP_TIM13_IRQ_VEC_OPENCM3 tim8_up_tim13_isr
#define NVIC_TIM8_TRG_COM_TIM14_IRQ_VEC_CHIBIOS VectorF4
#define NVIC_TIM8_TRG_COM_TIM14_IRQ_VEC_OPENCM3 tim8_trg_com_tim14_isr
#define NVIC_TIM8_CC_IRQ_VEC_CHIBIOS VectorF8
#define NVIC_TIM8_CC_IRQ_VEC_OPENCM3 tim8_cc_isr
#define NVIC_DMA1_STREAM7_IRQ_VEC_CHIBIOS VectorFC
#define NVIC_DMA1_STREAM7_IRQ_VEC_OPENCM3 dma1_stream7_isr
#define NVIC_FSMC_IRQ_VEC_CHIBIOS Vector100
#define NVIC_FSMC_IRQ_VEC_OPENCM3 fsmc_isr
#define NVIC_SDIO_IRQ_VEC_CHIBIOS Vector104
#define NVIC_SDIO_IRQ_VEC_OPENCM3 sdio_isr
#define NVIC_TIM5_IRQ_VEC_CHIBIOS Vector108
#define NVIC_TIM5_IRQ_VEC_OPENCM3 tim5_isr
#define NVIC_SPI3_IRQ_VEC_CHIBIOS Vector10C
#define NVIC_SPI3_IRQ_VEC_OPENCM3 spi3_isr
#define NVIC_UART4_IRQ_VEC_CHIBIOS Vector110
#define NVIC_UART4_IRQ_VEC_OPENCM3 uart4_isr
#define NVIC_UART5_IRQ_VEC_CHIBIOS Vector114
#define NVIC_UART5_IRQ_VEC_OPENCM3 uart5_isr
#define NVIC_TIM6_DAC_IRQ_VEC_CHIBIOS Vector118
#define NVIC_TIM6_DAC_IRQ_VEC_OPENCM3 tim6_dac_isr
#define NVIC_TIM7_IRQ_VEC_CHIBIOS Vector11C
#define NVIC_TIM7_IRQ_VEC_OPENCM3 tim7_isr
#define NVIC_DMA2_STREAM0_IRQ_VEC_CHIBIOS Vector120
#define NVIC_DMA2_STREAM0_IRQ_VEC_OPENCM3 dma2_stream0_isr
#define NVIC_DMA2_STREAM1_IRQ_VEC_CHIBIOS Vector124
#define NVIC_DMA2_STREAM1_IRQ_VEC_OPENCM3 dma2_stream1_isr
#define NVIC_DMA2_STREAM2_IRQ_VEC_CHIBIOS Vector128
#define NVIC_DMA2_STREAM2_IRQ_VEC_OPENCM3 dma2_stream2_isr
#define NVIC_DMA2_STREAM3_IRQ_VEC_CHIBIOS Vector12C
#define NVIC_DMA2_STREAM3_IRQ_VEC_OPENCM3 dma2_stream3_isr
#define NVIC_DMA2_STREAM4_IRQ_VEC_CHIBIOS Vector130
#define NVIC_DMA2_STREAM4_IRQ_VEC_OPENCM3 dma2_stream4_isr
#define NVIC_ETH_IRQ_VEC_CHIBIOS Vector134
#define NVIC_ETH_IRQ_VEC_OPENCM3 eth_isr
#define NVIC_ETH_WKUP_IRQ_VEC_CHIBIOS Vector138
#define NVIC_ETH_WKUP_IRQ_VEC_OPENCM3 eth_wkup_isr
#define NVIC_CAN2_TX_IRQ_VEC_CHIBIOS Vector13C
#define NVIC_CAN2_TX_IRQ_VEC_OPENCM3 can2_tx_isr
#define NVIC_CAN2_RX0_IRQ_VEC_CHIBIOS Vector140
#define NVIC_CAN2_RX0_IRQ_VEC_OPENCM3 can2_rx0_isr
#define NVIC_CAN2_RX1_IRQ_VEC_CHIBIOS Vector144
#define NVIC_CAN2_RX1_IRQ_VEC_OPENCM3 can2_rx1_isr
#define NVIC_CAN2_SCE_IRQ_VEC_CHIBIOS Vector148
#define NVIC_CAN2_SCE_IRQ_VEC_OPENCM3 can2_sce_isr
#define NVIC_OTG_FS_IRQ_VEC_CHIBIOS Vector14C
#define NVIC_OTG_FS_IRQ_VEC_OPENCM3 otg_fs_isr
#define NVIC_DMA2_STREAM5_IRQ_VEC_CHIBIOS Vector150
#define NVIC_DMA2_STREAM5_IRQ_VEC_OPENCM3 dma2_stream5_isr
#define NVIC_DMA2_STREAM6_IRQ_VEC_CHIBIOS Vector154
#define NVIC_DMA2_STREAM6_IRQ_VEC_OPENCM3 dma2_stream6_isr
#define NVIC_DMA2_STREAM7_IRQ_VEC_CHIBIOS Vector158
#define NVIC_DMA2_STREAM7_IRQ_VEC_OPENCM3 dma2_stream7_isr
#define NVIC_USART6_IRQ_VEC_CHIBIOS Vector15C
#define NVIC_USART6_IRQ_VEC_OPENCM3 usart6_isr
#define NVIC_I2C3_EV_IRQ_VEC_CHIBIOS Vector160
#define NVIC_I2C3_EV_IRQ_VEC_OPENCM3 i2c3_ev_isr
#define NVIC_I2C3_ER_IRQ_VEC_CHIBIOS Vector164
#define NVIC_I2C3_ER_IRQ_VEC_OPENCM3 i2c3_er_isr
#define NVIC_OTG_HS_EP1_OUT_IRQ_VEC_CHIBIOS Vector168
#define NVIC_OTG_HS_EP1_OUT_IRQ_VEC_OPENCM3 otg_hs_ep1_out_isr
#define NVIC_OTG_HS_EP1_IN_IRQ_VEC_CHIBIOS Vector16C
#define NVIC_OTG_HS_EP1_IN_IRQ_VEC_OPENCM3 otg_hs_ep1_in_isr
#define NVIC_OTG_HS_WKUP_IRQ_VEC_CHIBIOS Vector170
#define NVIC_OTG_HS_WKUP_IRQ_VEC_OPENCM3 otg_hs_wkup_isr
#define NVIC_OTG_HS_IRQ_VEC_CHIBIOS Vector174
#define NVIC_OTG_HS_IRQ_VEC_OPENCM3 otg_hs_isr
#define NVIC_DCMI_IRQ_VEC_CHIBIOS Vector178
#define NVIC_DCMI_IRQ_VEC_OPENCM3 dcmi_isr
#define NVIC_CRYP_IRQ_VEC_CHIBIOS Vector17C
#define NVIC_CRYP_IRQ_VEC_OPENCM3 cryp_isr
#define NVIC_HASH_RNG_IRQ_VEC_CHIBIOS Vector180
#define NVIC_HASH_RNG_IRQ_VEC_OPENCM3 hash_rng_isr

View File

@@ -0,0 +1,112 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ch.h"
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
* This variable is used by the HAL when initializing the PAL driver.
*/
const PALConfig pal_default_config =
{
{VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
{VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
{VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
{VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
{VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH},
{VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH},
{VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH},
{VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH},
{VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}
};
#endif
/**
* @brief Early initialization code.
* @details This initialization must be performed just after stack setup
* and before any other initialization.
*/
void __early_init(void) {
stm32_clock_init();
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
*
*/
bool_t sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
return FALSE;
}
/**
*
*/
bool_t sdc_lld_is_card_inserted(SDCDriver *sdcp) {
(void)sdcp;
return !palReadPad(GPIOB, GPIOB_SDIO_DETECT);
}
/**
* @brief SDC card detection.
*/
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)
/**
* @brief MMC_SPI card detection.
*/
bool_t mmc_lld_is_card_inserted(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return TRUE;
}
/**
* @brief MMC_SPI card write protection detection.
*/
bool_t mmc_lld_is_write_protected(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return FALSE;
}
#endif
/**
* @brief Board-specific initialization code.
* @todo Add your board-specific code, if any.
*/
void boardInit(void) {
}

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,5 @@
# Required include directories
BOARDINC = $(CHIBIOS_BOARD_DIR)
# List of all the board related files.
BOARDSRC = ${BOARDINC}/board.c

View File

@@ -0,0 +1,26 @@
#pragma once
#include "chconf.h"
#include "chtypes.h"
#include "chlists.h"
#include "chcore.h"
#include "chsys.h"
#include "chvt.h"
#include "chschd.h"
#include "chsem.h"
#include "chbsem.h"
#include "chmtx.h"
#include "chcond.h"
#include "chevents.h"
#include "chmsg.h"
#include "chmboxes.h"
#include "chmemcore.h"
#include "chheap.h"
#include "chmempools.h"
#include "chthreads.h"
#include "chdynamic.h"
#include "chregistry.h"
#include "chqueues.h"
#include "chstreams.h"
#include "chfiles.h"
#include "chdebug.h"

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,344 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file templates/halconf.h
* @brief HAL configuration header.
* @details HAL configuration file, this file allows to enable or disable the
* various device drivers from your application. You may also use
* this file in order to override the device drivers default settings.
*
* @addtogroup HAL_CONF
* @{
*/
#ifndef _HALCONF_H_
#define _HALCONF_H_
#include "mcuconf.h"
/**
* @brief Enables the TM subsystem.
*/
#if !defined(HAL_USE_TM) || defined(__DOXYGEN__)
#define HAL_USE_TM FALSE
#endif
/**
* @brief Enables the PAL subsystem.
*/
#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__)
#define HAL_USE_PAL TRUE
#endif
/**
* @brief Enables the ADC subsystem.
*/
#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__)
#define HAL_USE_ADC FALSE
#endif
/**
* @brief Enables the CAN subsystem.
*/
#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__)
#define HAL_USE_CAN FALSE
#endif
/**
* @brief Enables the EXT subsystem.
*/
#if !defined(HAL_USE_EXT) || defined(__DOXYGEN__)
#define HAL_USE_EXT FALSE
#endif
/**
* @brief Enables the GPT subsystem.
*/
#if !defined(HAL_USE_GPT) || defined(__DOXYGEN__)
#define HAL_USE_GPT FALSE
#endif
/**
* @brief Enables the I2C subsystem.
*/
#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__)
#define HAL_USE_I2C FALSE
#endif
/**
* @brief Enables the ICU subsystem.
*/
#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
#define HAL_USE_ICU FALSE
#endif
/**
* @brief Enables the MAC subsystem.
*/
#if !defined(HAL_USE_MAC) || defined(__DOXYGEN__)
#define HAL_USE_MAC FALSE
#endif
/**
* @brief Enables the MMC_SPI subsystem.
*/
#if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__)
#define HAL_USE_MMC_SPI FALSE
#endif
/**
* @brief Enables the PWM subsystem.
*/
#if !defined(HAL_USE_PWM) || defined(__DOXYGEN__)
#define HAL_USE_PWM FALSE
#endif
/**
* @brief Enables the RTC subsystem.
*/
#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
#define HAL_USE_RTC TRUE
#endif
/**
* @brief Enables the SDC subsystem.
*/
#if !defined(HAL_USE_SDC) || defined(__DOXYGEN__)
#define HAL_USE_SDC TRUE
#endif
/**
* @brief Enables the SERIAL subsystem.
*/
#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL FALSE
#endif
/**
* @brief Enables the SERIAL over USB subsystem.
*/
#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL_USB FALSE
#endif
/**
* @brief Enables the SPI subsystem.
*/
#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__)
#define HAL_USE_SPI FALSE
#endif
/**
* @brief Enables the UART subsystem.
*/
#if !defined(HAL_USE_UART) || defined(__DOXYGEN__)
#define HAL_USE_UART FALSE
#endif
/**
* @brief Enables the USB subsystem.
*/
#if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
#define HAL_USE_USB FALSE
#endif
/*===========================================================================*/
/* ADC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__)
#define ADC_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define ADC_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* CAN driver related settings. */
/*===========================================================================*/
/**
* @brief Sleep mode related APIs inclusion switch.
*/
#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__)
#define CAN_USE_SLEEP_MODE TRUE
#endif
/*===========================================================================*/
/* I2C driver related settings. */
/*===========================================================================*/
/**
* @brief Enables the mutual exclusion APIs on the I2C bus.
*/
#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define I2C_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* MAC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables an event sources for incoming packets.
*/
#if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__)
#define MAC_USE_EVENTS TRUE
#endif
/*===========================================================================*/
/* MMC_SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Block size for MMC transfers.
*/
#if !defined(MMC_SECTOR_SIZE) || defined(__DOXYGEN__)
#define MMC_SECTOR_SIZE 512
#endif
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
* This option is recommended also if the SPI driver does not
* use a DMA channel and heavily loads the CPU.
*/
#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__)
#define MMC_NICE_WAITING TRUE
#endif
/**
* @brief Number of positive insertion queries before generating the
* insertion event.
*/
#if !defined(MMC_POLLING_INTERVAL) || defined(__DOXYGEN__)
#define MMC_POLLING_INTERVAL 10
#endif
/**
* @brief Interval, in milliseconds, between insertion queries.
*/
#if !defined(MMC_POLLING_DELAY) || defined(__DOXYGEN__)
#define MMC_POLLING_DELAY 10
#endif
/**
* @brief Uses the SPI polled API for small data transfers.
* @details Polled transfers usually improve performance because it
* saves two context switches and interrupt servicing. Note
* that this option has no effect on large transfers which
* are always performed using DMAs/IRQs.
*/
#if !defined(MMC_USE_SPI_POLLING) || defined(__DOXYGEN__)
#define MMC_USE_SPI_POLLING TRUE
#endif
/*===========================================================================*/
/* SDC driver related settings. */
/*===========================================================================*/
/**
* @brief Number of initialization attempts before rejecting the card.
* @note Attempts are performed at 10mS intervals.
*/
#if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__)
#define SDC_INIT_RETRY 100
#endif
/**
* @brief Include support for MMC cards.
* @note MMC support is not yet implemented so this option must be kept
* at @p FALSE.
*/
#if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__)
#define SDC_MMC_SUPPORT FALSE
#endif
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
*/
#if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__)
#define SDC_NICE_WAITING TRUE
#endif
/*===========================================================================*/
/* SERIAL driver related settings. */
/*===========================================================================*/
/**
* @brief Default bit rate.
* @details Configuration parameter, this is the baud rate selected for the
* default configuration.
*/
#if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__)
#define SERIAL_DEFAULT_BITRATE 38400
#endif
/**
* @brief Serial buffers size.
* @details Configuration parameter, you can change the depth of the queue
* buffers depending on the requirements of your application.
* @note The default is 64 bytes for both the transmission and receive
* buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 160
#endif
/*===========================================================================*/
/* SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__)
#define SPI_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define SPI_USE_MUTUAL_EXCLUSION TRUE
#endif
#endif /* _HALCONF_H_ */
/** @} */

View File

@@ -0,0 +1,352 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* STM32F4xx drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
* 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
#define STM32F4xx_MCUCONF
/*
* HAL driver system settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_HSI_ENABLED TRUE
#define STM32_LSI_ENABLED FALSE
#define STM32_HSE_ENABLED TRUE
#define STM32_LSE_ENABLED TRUE
#define STM32_CLOCK48_REQUIRED TRUE
#define STM32_SW STM32_SW_PLL
#define STM32_PLLSRC STM32_PLLSRC_HSE
#define STM32_PLLM_VALUE 16
#define STM32_PLLN_VALUE 336
#define STM32_PLLP_VALUE 2
#define STM32_PLLQ_VALUE 7
#define STM32_HPRE STM32_HPRE_DIV1
#define STM32_PPRE1 STM32_PPRE1_DIV4
#define STM32_PPRE2 STM32_PPRE2_DIV2
#define STM32_RTCSEL STM32_RTCSEL_LSE
#define STM32_RTCPRE_VALUE 8
#define STM32_MCO1SEL STM32_MCO1SEL_HSI
#define STM32_MCO1PRE STM32_MCO1PRE_DIV1
#define STM32_MCO2SEL STM32_MCO2SEL_SYSCLK
#define STM32_MCO2PRE STM32_MCO2PRE_DIV5
#define STM32_I2SSRC STM32_I2SSRC_CKIN
#define STM32_PLLI2SN_VALUE 192
#define STM32_PLLI2SR_VALUE 5
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
/*
* ADC driver system settings.
*/
#define STM32_ADC_ADCPRE ADC_CCR_ADCPRE_DIV4
#define STM32_ADC_USE_ADC1 FALSE
#define STM32_ADC_USE_ADC2 FALSE
#define STM32_ADC_USE_ADC3 FALSE
#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(2, 4)
#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
#define STM32_ADC_ADC1_DMA_PRIORITY 2
#define STM32_ADC_ADC2_DMA_PRIORITY 2
#define STM32_ADC_ADC3_DMA_PRIORITY 2
#define STM32_ADC_IRQ_PRIORITY 6
#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 6
#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 6
#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 6
/*
* CAN driver system settings.
*/
#define STM32_CAN_USE_CAN1 FALSE
#define STM32_CAN_USE_CAN2 FALSE
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
#define STM32_CAN_CAN2_IRQ_PRIORITY 11
/*
* EXT driver system settings.
*/
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
#define STM32_EXT_EXTI17_IRQ_PRIORITY 15
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
#define STM32_EXT_EXTI20_IRQ_PRIORITY 6
#define STM32_EXT_EXTI21_IRQ_PRIORITY 15
#define STM32_EXT_EXTI22_IRQ_PRIORITY 15
/*
* GPT driver system settings.
*/
#define STM32_GPT_USE_TIM1 FALSE
#define STM32_GPT_USE_TIM2 FALSE
#define STM32_GPT_USE_TIM3 FALSE
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM5 FALSE
#define STM32_GPT_USE_TIM8 FALSE
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
#define STM32_GPT_TIM5_IRQ_PRIORITY 7
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
/*
* I2C driver system settings.
*/
#define STM32_I2C_USE_I2C1 FALSE
#define STM32_I2C_USE_I2C2 FALSE
#define STM32_I2C_USE_I2C3 FALSE
#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
#define STM32_I2C_I2C2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
#define STM32_I2C_I2C3_IRQ_PRIORITY 5
#define STM32_I2C_I2C1_DMA_PRIORITY 3
#define STM32_I2C_I2C2_DMA_PRIORITY 3
#define STM32_I2C_I2C3_DMA_PRIORITY 3
#define STM32_I2C_I2C1_DMA_ERROR_HOOK() chSysHalt()
#define STM32_I2C_I2C2_DMA_ERROR_HOOK() chSysHalt()
#define STM32_I2C_I2C3_DMA_ERROR_HOOK() chSysHalt()
/*
* ICU driver system settings.
*/
#define STM32_ICU_USE_TIM1 FALSE
#define STM32_ICU_USE_TIM2 FALSE
#define STM32_ICU_USE_TIM3 FALSE
#define STM32_ICU_USE_TIM4 FALSE
#define STM32_ICU_USE_TIM5 FALSE
#define STM32_ICU_USE_TIM8 FALSE
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
#define STM32_ICU_TIM5_IRQ_PRIORITY 7
#define STM32_ICU_TIM8_IRQ_PRIORITY 7
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
#define STM32_PWM_USE_TIM1 FALSE
#define STM32_PWM_USE_TIM2 FALSE
#define STM32_PWM_USE_TIM3 FALSE
#define STM32_PWM_USE_TIM4 FALSE
#define STM32_PWM_USE_TIM5 FALSE
#define STM32_PWM_USE_TIM8 FALSE
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
/*
* SERIAL driver system settings.
*/
#define STM32_SERIAL_USE_USART1 FALSE
#define STM32_SERIAL_USE_USART2 FALSE
#define STM32_SERIAL_USE_USART3 FALSE
#define STM32_SERIAL_USE_UART4 FALSE
#define STM32_SERIAL_USE_UART5 FALSE
#define STM32_SERIAL_USE_USART6 FALSE
#define STM32_SERIAL_USART1_PRIORITY 12
#define STM32_SERIAL_USART2_PRIORITY 12
#define STM32_SERIAL_USART3_PRIORITY 12
#define STM32_SERIAL_UART4_PRIORITY 12
#define STM32_SERIAL_UART5_PRIORITY 12
#define STM32_SERIAL_USART6_PRIORITY 12
/*
* SPI driver system settings.
*/
#define STM32_SPI_USE_SPI1 FALSE
#define STM32_SPI_USE_SPI2 FALSE
#define STM32_SPI_USE_SPI3 FALSE
#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 0)
#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
#define STM32_SPI_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_SPI_SPI3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_SPI_SPI3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
#define STM32_SPI_DMA_ERROR_HOOK(spip) chSysHalt()
/*
* UART driver system settings.
*/
#define STM32_UART_USE_USART1 FALSE
#define STM32_UART_USE_USART2 FALSE
#define STM32_UART_USE_USART3 FALSE
#define STM32_UART_USE_USART6 FALSE
#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7)
#define STM32_UART_USART2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
#define STM32_UART_USART2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 6)
#define STM32_UART_USART1_IRQ_PRIORITY 12
#define STM32_UART_USART2_IRQ_PRIORITY 12
#define STM32_UART_USART3_IRQ_PRIORITY 12
#define STM32_UART_USART6_IRQ_PRIORITY 12
#define STM32_UART_USART1_DMA_PRIORITY 1
#define STM32_UART_USART2_DMA_PRIORITY 0
#define STM32_UART_USART3_DMA_PRIORITY 0
#define STM32_UART_USART6_DMA_PRIORITY 0
#define STM32_UART_DMA_ERROR_HOOK(uartp) chSysHalt()
/*
* USB driver system settings.
*/
#define STM32_USB_USE_OTG1 FALSE // FS, DFU_BOOT
#define STM32_USB_USE_OTG2 FALSE // HS
#define STM32_USB_OTG1_IRQ_PRIORITY 14
#define STM32_USB_OTG2_IRQ_PRIORITY 14
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
#define STM32_USB_OTG2_RX_FIFO_SIZE 512
#define STM32_USB_OTG_THREAD_PRIO LOWPRIO
#define STM32_USB_OTG_THREAD_STACK_SIZE 128
#define STM32_USB_OTGFIFO_FILL_BASEPRI 0
/*
* SDC SDIO driver system settings.
*/
#define STM32_SDC_SDIO_DMA_STREAM STM32_DMA_STREAM_ID(2, 3)
#define STM32_SDC_SDIO_DMA_PRIORITY 3
#define STM32_SDC_SDIO_IRQ_PRIORITY 9
#define STM32_SDC_SDIO_UNALIGNED_SUPPORT FALSE
#define SDC_READ_TIMEOUT_MS 15
/*
* OPENCM3 INTEGRATION
*/
#define DECLARE_IRQS [NVIC_NVIC_WWDG_IRQ] = NVIC_NVIC_WWDG_IRQ_VEC_OPENCM3, \
[NVIC_PVD_IRQ] = NVIC_PVD_IRQ_VEC_OPENCM3, \
[NVIC_TAMP_STAMP_IRQ] = NVIC_TAMP_STAMP_IRQ_VEC_OPENCM3, \
[NVIC_RTC_WKUP_IRQ] = NVIC_RTC_WKUP_IRQ_VEC_CHIBIOS, \
[NVIC_FLASH_IRQ] = NVIC_FLASH_IRQ_VEC_OPENCM3, \
[NVIC_RCC_IRQ] = NVIC_RCC_IRQ_VEC_OPENCM3, \
[NVIC_EXTI0_IRQ] = NVIC_EXTI0_IRQ_VEC_OPENCM3, \
[NVIC_EXTI1_IRQ] = NVIC_EXTI1_IRQ_VEC_OPENCM3, \
[NVIC_EXTI2_IRQ] = NVIC_EXTI2_IRQ_VEC_OPENCM3, \
[NVIC_EXTI3_IRQ] = NVIC_EXTI3_IRQ_VEC_OPENCM3, \
[NVIC_EXTI4_IRQ] = NVIC_EXTI4_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM0_IRQ] = NVIC_DMA1_STREAM0_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM1_IRQ] = NVIC_DMA1_STREAM1_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM2_IRQ] = NVIC_DMA1_STREAM2_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM3_IRQ] = NVIC_DMA1_STREAM3_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM4_IRQ] = NVIC_DMA1_STREAM4_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM5_IRQ] = NVIC_DMA1_STREAM5_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM6_IRQ] = NVIC_DMA1_STREAM6_IRQ_VEC_OPENCM3, \
[NVIC_ADC_IRQ] = NVIC_ADC_IRQ_VEC_OPENCM3, \
[NVIC_CAN1_TX_IRQ] = NVIC_CAN1_TX_IRQ_VEC_OPENCM3, \
[NVIC_CAN1_RX0_IRQ] = NVIC_CAN1_RX0_IRQ_VEC_OPENCM3, \
[NVIC_CAN1_RX1_IRQ] = NVIC_CAN1_RX1_IRQ_VEC_OPENCM3, \
[NVIC_CAN1_SCE_IRQ] = NVIC_CAN1_SCE_IRQ_VEC_OPENCM3, \
[NVIC_EXTI9_5_IRQ] = NVIC_EXTI9_5_IRQ_VEC_OPENCM3, \
[NVIC_TIM1_BRK_TIM9_IRQ] = NVIC_TIM1_BRK_TIM9_IRQ_VEC_OPENCM3, \
[NVIC_TIM1_UP_TIM10_IRQ] = NVIC_TIM1_UP_TIM10_IRQ_VEC_OPENCM3, \
[NVIC_TIM1_TRG_COM_TIM11_IRQ] = NVIC_TIM1_TRG_COM_TIM11_IRQ_VEC_OPENCM3, \
[NVIC_TIM1_CC_IRQ] = NVIC_TIM1_CC_IRQ_VEC_OPENCM3, \
[NVIC_TIM2_IRQ] = NVIC_TIM2_IRQ_VEC_OPENCM3, \
[NVIC_TIM3_IRQ] = NVIC_TIM3_IRQ_VEC_OPENCM3, \
[NVIC_TIM4_IRQ] = NVIC_TIM4_IRQ_VEC_OPENCM3, \
[NVIC_I2C1_EV_IRQ] = NVIC_I2C1_EV_IRQ_VEC_OPENCM3, \
[NVIC_I2C1_ER_IRQ] = NVIC_I2C1_ER_IRQ_VEC_OPENCM3, \
[NVIC_I2C2_EV_IRQ] = NVIC_I2C2_EV_IRQ_VEC_OPENCM3, \
[NVIC_I2C2_ER_IRQ] = NVIC_I2C2_ER_IRQ_VEC_OPENCM3, \
[NVIC_SPI1_IRQ] = NVIC_SPI1_IRQ_VEC_OPENCM3, \
[NVIC_SPI2_IRQ] = NVIC_SPI2_IRQ_VEC_OPENCM3, \
[NVIC_USART1_IRQ] = NVIC_USART1_IRQ_VEC_OPENCM3, \
[NVIC_USART2_IRQ] = NVIC_USART2_IRQ_VEC_OPENCM3, \
[NVIC_USART3_IRQ] = NVIC_USART3_IRQ_VEC_OPENCM3, \
[NVIC_EXTI15_10_IRQ] = NVIC_EXTI15_10_IRQ_VEC_OPENCM3, \
[NVIC_RTC_ALARM_IRQ] = NVIC_RTC_ALARM_IRQ_VEC_CHIBIOS, \
[NVIC_USB_FS_WKUP_IRQ] = NVIC_USB_FS_WKUP_IRQ_VEC_OPENCM3, \
[NVIC_TIM8_BRK_TIM12_IRQ] = NVIC_TIM8_BRK_TIM12_IRQ_VEC_OPENCM3, \
[NVIC_TIM8_UP_TIM13_IRQ] = NVIC_TIM8_UP_TIM13_IRQ_VEC_OPENCM3, \
[NVIC_TIM8_TRG_COM_TIM14_IRQ] = NVIC_TIM8_TRG_COM_TIM14_IRQ_VEC_OPENCM3, \
[NVIC_TIM8_CC_IRQ] = NVIC_TIM8_CC_IRQ_VEC_OPENCM3, \
[NVIC_DMA1_STREAM7_IRQ] = NVIC_DMA1_STREAM7_IRQ_VEC_OPENCM3, \
[NVIC_FSMC_IRQ] = NVIC_FSMC_IRQ_VEC_OPENCM3, \
[NVIC_SDIO_IRQ] = NVIC_SDIO_IRQ_VEC_CHIBIOS, \
[NVIC_TIM5_IRQ] = NVIC_TIM5_IRQ_VEC_OPENCM3, \
[NVIC_SPI3_IRQ] = NVIC_SPI3_IRQ_VEC_OPENCM3, \
[NVIC_UART4_IRQ] = NVIC_UART4_IRQ_VEC_OPENCM3, \
[NVIC_UART5_IRQ] = NVIC_UART5_IRQ_VEC_OPENCM3, \
[NVIC_TIM6_DAC_IRQ] = NVIC_TIM6_DAC_IRQ_VEC_OPENCM3, \
[NVIC_TIM7_IRQ] = NVIC_TIM7_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM0_IRQ] = NVIC_DMA2_STREAM0_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM1_IRQ] = NVIC_DMA2_STREAM1_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM2_IRQ] = NVIC_DMA2_STREAM2_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM3_IRQ] = NVIC_DMA2_STREAM3_IRQ_VEC_CHIBIOS, \
[NVIC_DMA2_STREAM4_IRQ] = NVIC_DMA2_STREAM4_IRQ_VEC_OPENCM3, \
[NVIC_ETH_IRQ] = NVIC_ETH_IRQ_VEC_OPENCM3, \
[NVIC_ETH_WKUP_IRQ] = NVIC_ETH_WKUP_IRQ_VEC_OPENCM3, \
[NVIC_CAN2_TX_IRQ] = NVIC_CAN2_TX_IRQ_VEC_OPENCM3, \
[NVIC_CAN2_RX0_IRQ] = NVIC_CAN2_RX0_IRQ_VEC_OPENCM3, \
[NVIC_CAN2_RX1_IRQ] = NVIC_CAN2_RX1_IRQ_VEC_OPENCM3, \
[NVIC_CAN2_SCE_IRQ] = NVIC_CAN2_SCE_IRQ_VEC_OPENCM3, \
[NVIC_OTG_FS_IRQ] = NVIC_OTG_FS_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM5_IRQ] = NVIC_DMA2_STREAM5_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM6_IRQ] = NVIC_DMA2_STREAM6_IRQ_VEC_OPENCM3, \
[NVIC_DMA2_STREAM7_IRQ] = NVIC_DMA2_STREAM7_IRQ_VEC_OPENCM3, \
[NVIC_USART6_IRQ] = NVIC_USART6_IRQ_VEC_OPENCM3, \
[NVIC_I2C3_EV_IRQ] = NVIC_I2C3_EV_IRQ_VEC_OPENCM3, \
[NVIC_I2C3_ER_IRQ] = NVIC_I2C3_ER_IRQ_VEC_OPENCM3, \
[NVIC_OTG_HS_EP1_OUT_IRQ] = NVIC_OTG_HS_EP1_OUT_IRQ_VEC_OPENCM3, \
[NVIC_OTG_HS_EP1_IN_IRQ] = NVIC_OTG_HS_EP1_IN_IRQ_VEC_OPENCM3, \
[NVIC_OTG_HS_WKUP_IRQ] = NVIC_OTG_HS_WKUP_IRQ_VEC_OPENCM3, \
[NVIC_OTG_HS_IRQ] = NVIC_OTG_HS_IRQ_VEC_OPENCM3, \
[NVIC_DCMI_IRQ] = NVIC_DCMI_IRQ_VEC_OPENCM3, \
[NVIC_CRYP_IRQ] = NVIC_CRYP_IRQ_VEC_OPENCM3, \
[NVIC_HASH_RNG_IRQ] = NVIC_HASH_RNG_IRQ_VEC_OPENCM3, \
[81] = Vector184

View File

@@ -367,4 +367,18 @@
#define SPEKTRUM_UART2_ISR usart2_isr
#define SPEKTRUM_UART2_DEV USART2
/*
* IRQ Priorities
*/
#define RTOS_PRIO 2
#define NVIC_TIM_IRQ_PRIO (RTOS_PRIO+1)
#define NVIC_I2C_IRQ_PRIO (RTOS_PRIO+2)
#define NVIC_SPI_IRQ_PRIO (RTOS_PRIO+3)
#define NVIC_UART_IRQ_PRIO (RTOS_PRIO+4)
#define NVIC_USART_IRQ_PRIO (RTOS_PRIO+4)
#define NVIC_ADC_IRQ_PRIO (RTOS_PRIO+5)
#define NVIC_TIM6_DAC_IRQ_PRIO (RTOS_PRIO+6)
#endif /* CONFIG_APOGEE_1_00_H */

View File

@@ -0,0 +1,142 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/*
* @file firmwares/fixedwing/chibios-libopencm3/chibios_init.c
*
*/
#include <ch.h>
#include <hal.h>
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "sdLog.h"
#include "pprz_stub.h"
#include "rtcAccess.h"
#ifndef SYS_TIME_FREQUENCY
#error SYS_TIME_FREQUENCY should be defined in Makefile.chibios or airframe.xml and be equal to CH_FREQUENCY
#elif SYS_TIME_FREQUENCY != CH_FREQUENCY
#error SYS_TIME_FREQUENCY should be equal to CH_FREQUENCY
#elif CH_FREQUENCY < (2 * PERIODIC_FREQUENCY)
#error CH_FREQUENCY and SYS_TIME_FREQUENCY should be >= 2 x PERIODIC_FREQUENCY
#endif
static __attribute__((noreturn)) msg_t thd_heartbeat(void *arg);
#define MAX(x , y) (((x) > (y)) ? (x) : (y))
#define ARRAY_LEN(a) (sizeof(a)/sizeof(a[0]))
static WORKING_AREA(wa_thd_heartbeat, 2048);
void chibios_launch_heartbeat (void);
bool_t sdOk = FALSE;
#if LOG_PROCESS_STATE
static int32_t get_stack_free (Thread *tp);
#endif
/*
* Init ChibiOS HAL and Sys
*/
bool_t chibios_init(void) {
halInit();
chSysInit();
PWR->CSR &= ~PWR_CSR_BRE;
DBGMCU->APB1FZ |= DBGMCU_APB1_FZ_DBG_IWDG_STOP;
chThdSleepMilliseconds (100);
sdOk = chibios_logInit(true);
chThdCreateStatic(wa_thd_heartbeat, sizeof(wa_thd_heartbeat),
NORMALPRIO, thd_heartbeat, NULL);
return sdOk;
}
static WORKING_AREA(pprzThd, 4096);
void launch_pprz_thd (int32_t (*thd) (void *arg))
{
chThdCreateStatic(pprzThd, sizeof(pprzThd), NORMALPRIO+1, thd, NULL);
}
/*
* Heartbeat thread
*/
static __attribute__((noreturn)) msg_t thd_heartbeat(void *arg)
{
(void) arg;
chRegSetThreadName("pprz heartbeat");
while (TRUE) {
palTogglePad (GPIOC, GPIOC_LED3);
chThdSleepMilliseconds (sdOk == TRUE ? 1000 : 200);
static uint32_t timestamp = 0;
#if LOG_PROCESS_STATE
sdLogWriteLog (&processLogFile, " addr stack frestk prio refs state time name\r\n");
#endif
// chSysDisable ();
Thread *tp = chRegFirstThread();
do {
#if LOG_PROCESS_STATE
sdLogWriteLog (&processLogFile, "%.8lx %.8lx %6lu %4lu %4lu [S:%d] %5lu %s\r\n",
(uint32_t)tp, (uint32_t)tp->p_ctx.r13,
get_stack_free (tp),
(uint32_t)tp->p_prio, (uint32_t)(tp->p_refs - 1),
tp->p_state, (uint32_t)tp->p_time,
chRegGetThreadName(tp));
#endif
tp = chRegNextThread(tp);
} while (tp != NULL);
// chSysEnable ();
// we sync gps time to rtc every 5 seconds
if (chTimeNow() - timestamp > 5000) {
timestamp = chTimeNow();
if (getGpsTimeOfWeek() != 0) {
setRtcFromGps (getGpsWeek(), getGpsTimeOfWeek());
}
}
}
}
#if LOG_PROCESS_STATE
static int32_t get_stack_free (Thread *tp)
{
int32_t index = 0;
const uint8_t *maxRamAddr = (uint8_t*) (0x20000000 + (128*1024));
const int32_t internalStructSize = 80;
unsigned long long *stkAdr = (unsigned long long *) ((uint8_t *) tp + internalStructSize);
//unsigned long long *stkAdr = (unsigned long long *) tp;
while ((stkAdr[index] == 0x5555555555555555) && ( ((uint8_t *) &(stkAdr[index])) < maxRamAddr))
index++;
const int32_t freeBytes = index * sizeof(long long);
return MAX(0, freeBytes - internalStructSize);
}
#endif

View File

@@ -0,0 +1,35 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/*
* @file firmwares/fixedwing/chibios-libopencm3/chibios_init.h
*
*/
#ifndef CHIBIOS_INIT_H
#define CHIBIOS_INIT_H
#include "std.h"
extern bool_t chibios_init(void);
extern void launch_pprz_thd (int32_t (*thd) (void *arg));
#endif

View File

@@ -0,0 +1,96 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/**
* @file firmwares/fixedwing/main_chibios.c
*/
#include "firmwares/fixedwing/chibios-libopencm3/chibios_init.h"
#include "mcu_periph/sys_time.h"
#include "chibios_stub.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "sdLog.h"
#ifdef FBW
#include "firmwares/fixedwing/main_fbw.h"
#define Fbw(f) f ## _fbw()
#else
#define Fbw(f)
#endif
#ifdef AP
#include "firmwares/fixedwing/main_ap.h"
#define Ap(f) f ## _ap()
#else
#define Ap(f)
#endif
#include "led.h"
static int32_t pprz_thd (void *arg);
static bool_t sdlogOk ;
bool_t pprzReady = FALSE;
int main( void )
{
// Init
sys_time_init();
// Init ChibiOS
sdlogOk = chibios_init();
// Init PPRZ
Fbw(init);
Ap(init);
chibios_chThdSleepMilliseconds(100);
launch_pprz_thd (&pprz_thd);
pprzReady = TRUE;
// Call PPRZ periodic and event functions
while (TRUE) {
chibios_chThdSleepMilliseconds(1000);
}
return 0;
}
static int32_t pprz_thd (void *arg)
{
/*
To be compatible with rtos architecture, each of this 4 workers should
be implemented in differents threads, each of them waiting for job to be done:
periodic task should sleep, and event task should wait for event
*/
(void) arg;
chibios_chRegSetThreadName ("pprz big loop");
while (TRUE) {
Fbw(handle_periodic_tasks);
Ap(handle_periodic_tasks);
Fbw(event_task);
Ap(event_task);
chibios_chThdSleepMilliseconds(1);
}
return 0;
}

View File

@@ -38,6 +38,6 @@ volatile bool_t inter_mcu_received_ap = FALSE;
#ifdef FBW
/** Variables for monitoring AP communication status */
uint8_t ap_ok;
bool_t ap_ok;
uint8_t time_since_last_ap;
#endif

View File

@@ -0,0 +1,144 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/*
* @file subsystems/chibios-libopencm3/chibios_sdlog.c
* @brief sdlog process with battery monitoring
*
*/
#include <ch.h>
#include <hal.h>
#include "subsystems/chibios-libopencm3/sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "mcu_periph/adc.h"
#define DefaultAdcOfVoltage(voltage) ((uint32_t) (voltage/(DefaultVoltageOfAdc(1))))
static const uint16_t V_ALERT = DefaultAdcOfVoltage(5.0f);
static const char PPRZ_LOG_NAME[] = "pprzlog_";
static const char PPRZ_LOG_DIR[] = "PPRZ";
static msg_t batterySurveyThd(void *arg);
static void launchBatterySurveyThread (void);
static void powerOutageIsr (void);
EventSource powerOutageSource;
EventListener powerOutageListener;
FIL pprzLogFile = {0};
#if LOG_PROCESS_STATE
static const char PROCESS_LOG_NAME[] = "processLog_";
FIL processLogFile = {0};
#endif
static WORKING_AREA(waThdBatterySurvey, 4096);
static void launchBatterySurveyThread (void)
{
chThdCreateStatic (waThdBatterySurvey, sizeof(waThdBatterySurvey),
NORMALPRIO+2, batterySurveyThd, NULL);
}
bool_t chibios_logInit(const bool_t binaryFile)
{
nvicSetSystemHandlerPriority(HANDLER_PENDSV,
CORTEX_PRIORITY_MASK(15));
if (sdLogInit (NULL) != SDLOG_OK)
goto error;
if (sdLogOpenLog (&pprzLogFile, PPRZ_LOG_DIR, PPRZ_LOG_NAME) != SDLOG_OK)
goto error;
#if LOG_PROCESS_STATE
if (sdLogOpenLog (&processLogFile, PROCESS_LOG_NAME) != SDLOG_OK)
goto error;
#endif
if (sdLoglaunchThread (binaryFile) != SDLOG_OK)
goto error;
chEvtInit (&powerOutageSource);
launchBatterySurveyThread ();
return TRUE;
error:
return FALSE;
}
void chibios_logFinish(void)
{
sdLogStopThread ();
sdLogCloseLog (&pprzLogFile);
#if LOG_PROCESS_STATE
sdLogCloseLog (&processLogFile);
#endif
sdLogFinish ();
}
static msg_t batterySurveyThd(void *arg)
{
(void)arg;
chRegSetThreadName ("battery survey");
chEvtRegister(&powerOutageSource, &powerOutageListener, 1);
chThdSleepMilliseconds (2000);
register_adc_watchdog((uint32_t) ADC1, 4,
V_ALERT, 0xfff, &powerOutageIsr);
chEvtWaitOne(EVENT_MASK(1));
chibios_logFinish ();
chThdExit(0);
return 0;
}
/*
powerOutageIsr is called from an isr not managed by chibios, so it is not possible
to directly call chibios api from this isr.
We have to use a 2 stage system and trigger a pendSV isr that is directly managed
by chibios
° if in the future we have more than one pprz(ocm3) isr which have to call
chibios api, we will need to route the pendSV isr to the right isr routine
° all theses problems will vanish when we will use a chibios hal
*/
static void powerOutageIsr (void)
{
// trigger PendSVVector isr
SCB_ICSR = ICSR_PENDSVSET;
}
CH_IRQ_HANDLER(PendSVVector) {
CH_IRQ_PROLOGUE();
chSysLockFromIsr();
chEvtBroadcastI(&powerOutageSource);
chSysUnlockFromIsr();
CH_IRQ_EPILOGUE();
}

View File

@@ -0,0 +1,50 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/*
* @file subsystems/chibios-libopencm3/chibios_sdlog.h
* @brief sdlog process with battery monitoring
*
*/
#ifndef CHIBIOS_SDLOG_H
#define CHIBIOS_SDLOG_H
#include "ff.h"
/*
what to be done :
* having an api to register new log
* keep internally a list of open file
* when power failure event occurs, close all logs
*/
extern FIL pprzLogFile;
#if LOG_PROCESS_STATE
// if activated, will log all process states
extern FIL processLogFile;
#endif
extern bool_t chibios_logInit(const bool_t binaryFile);
extern void chibios_logFinish(void);
#endif

View File

@@ -0,0 +1,77 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#include <ch.h>
#include <hal.h>
#include "chibios_stub.h"
void chibios_chSysLock (void)
{
chSysLock ();
}
void chibios_chSysUnlock (void)
{
chSysUnlock ();
}
void chibios_chSysLockFromIsr (void)
{
chSysLockFromIsr();
}
void chibios_chSysUnlockFromIsr (void)
{
chSysUnlockFromIsr();
}
void chibios_chSysDisable (void)
{
chSysDisable();
}
void chibios_chSysEnable (void)
{
chSysEnable();
}
void chibios_chRegSetThreadName (const char* thdName)
{
chRegSetThreadName (thdName);
}
void chibios_chThdSleepMilliseconds(uint32_t ms)
{
chThdSleepMilliseconds(ms);
}
void chibios_chThdSleepMicroseconds(uint32_t us)
{
chThdSleepMicroseconds(us);
}
uint32_t chibios_chTimeNow(void)
{
return chTimeNow();
}

View File

@@ -0,0 +1,38 @@
/*
* Copyright (C) 2013 Gautier Hattenberger, Alexandre Bustico
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#ifndef CHIBIOS_STUB_H
#define CHIBIOS_STUB_H
#include <stdint.h>
extern void chibios_chSysLock (void);
extern void chibios_chSysUnlock (void);
extern void chibios_chSysLockFromIsr (void);
extern void chibios_chSysUnlockFromIsr (void);
extern void chibios_chSysDisable (void);
extern void chibios_chSysEnable (void);
extern void chibios_chRegSetThreadName (const char* thdName);
extern void chibios_chThdSleepMilliseconds(uint32_t ms);
extern void chibios_chThdSleepMicroseconds(uint32_t us);
extern uint32_t chibios_chTimeNow(void);
#endif

View File

@@ -0,0 +1,193 @@
/* CHIBIOS FIX */
#include "ch.h"
/*---------------------------------------------------------------------------/
/ FatFs - FAT file system module configuration file R0.09 (C)ChaN, 2011
/----------------------------------------------------------------------------/
/
/ CAUTION! Do not forget to make clean the project after any changes to
/ the configuration options.
/
/----------------------------------------------------------------------------*/
#ifndef _FFCONF
#define _FFCONF 6502 /* Revision ID */
/*---------------------------------------------------------------------------/
/ Functions and Buffer Configurations
/----------------------------------------------------------------------------*/
#define _FS_TINY 0 /* 0:Normal or 1:Tiny */
/* When _FS_TINY is set to 1, FatFs uses the sector buffer in the file system
/ object instead of the sector buffer in the individual file object for file
/ data transfer. This reduces memory consumption 512 bytes each file object. */
#define _FS_READONLY 0 /* 0:Read/Write or 1:Read only */
/* Setting _FS_READONLY to 1 defines read only configuration. This removes
/ writing functions, f_write, f_sync, f_unlink, f_mkdir, f_chmod, f_rename,
/ f_truncate and useless f_getfree. */
#define _FS_MINIMIZE 0 /* 0 to 3 */
/* The _FS_MINIMIZE option defines minimization level to remove some functions.
/
/ 0: Full function.
/ 1: f_stat, f_getfree, f_unlink, f_mkdir, f_chmod, f_truncate and f_rename
/ are removed.
/ 2: f_opendir and f_readdir are removed in addition to 1.
/ 3: f_lseek is removed in addition to 2. */
#define _USE_STRFUNC 2 /* 0:Disable or 1-2:Enable */
/* To enable string functions, set _USE_STRFUNC to 1 or 2. */
#define _USE_MKFS 1 /* 0:Disable or 1:Enable */
/* To enable f_mkfs function, set _USE_MKFS to 1 and set _FS_READONLY to 0 */
#define _USE_FORWARD 0 /* 0:Disable or 1:Enable */
/* To enable f_forward function, set _USE_FORWARD to 1 and set _FS_TINY to 1. */
#define _USE_FASTSEEK 0 /* 0:Disable or 1:Enable */
/* To enable fast seek feature, set _USE_FASTSEEK to 1. */
/*---------------------------------------------------------------------------/
/ Locale and Namespace Configurations
/----------------------------------------------------------------------------*/
#define _CODE_PAGE 1250
/* The _CODE_PAGE specifies the OEM code page to be used on the target system.
/ Incorrect setting of the code page can cause a file open failure.
/
/ 932 - Japanese Shift-JIS (DBCS, OEM, Windows)
/ 936 - Simplified Chinese GBK (DBCS, OEM, Windows)
/ 949 - Korean (DBCS, OEM, Windows)
/ 950 - Traditional Chinese Big5 (DBCS, OEM, Windows)
/ 1250 - Central Europe (Windows)
/ 1251 - Cyrillic (Windows)
/ 1252 - Latin 1 (Windows)
/ 1253 - Greek (Windows)
/ 1254 - Turkish (Windows)
/ 1255 - Hebrew (Windows)
/ 1256 - Arabic (Windows)
/ 1257 - Baltic (Windows)
/ 1258 - Vietnam (OEM, Windows)
/ 437 - U.S. (OEM)
/ 720 - Arabic (OEM)
/ 737 - Greek (OEM)
/ 775 - Baltic (OEM)
/ 850 - Multilingual Latin 1 (OEM)
/ 858 - Multilingual Latin 1 + Euro (OEM)
/ 852 - Latin 2 (OEM)
/ 855 - Cyrillic (OEM)
/ 866 - Russian (OEM)
/ 857 - Turkish (OEM)
/ 862 - Hebrew (OEM)
/ 874 - Thai (OEM, Windows)
/ 1 - ASCII only (Valid for non LFN cfg.)
*/
#define _USE_LFN 2 /* 0 to 3 */
#define _MAX_LFN 255 /* Maximum LFN length to handle (12 to 255) */
/* The _USE_LFN option switches the LFN support.
/
/ 0: Disable LFN feature. _MAX_LFN and _LFN_UNICODE have no effect.
/ 1: Enable LFN with static working buffer on the BSS. Always NOT reentrant.
/ 2: Enable LFN with dynamic working buffer on the STACK.
/ 3: Enable LFN with dynamic working buffer on the HEAP.
/
/ The LFN working buffer occupies (_MAX_LFN + 1) * 2 bytes. To enable LFN,
/ Unicode handling functions ff_convert() and ff_wtoupper() must be added
/ to the project. When enable to use heap, memory control functions
/ ff_memalloc() and ff_memfree() must be added to the project. */
#define _LFN_UNICODE 0 /* 0:ANSI/OEM or 1:Unicode */
/* To switch the character code set on FatFs API to Unicode,
/ enable LFN feature and set _LFN_UNICODE to 1. */
#define _FS_RPATH 2 /* 0 to 2 */
/* The _FS_RPATH option configures relative path feature.
/
/ 0: Disable relative path feature and remove related functions.
/ 1: Enable relative path. f_chdrive() and f_chdir() are available.
/ 2: f_getcwd() is available in addition to 1.
/
/ Note that output of the f_readdir fnction is affected by this option. */
/*---------------------------------------------------------------------------/
/ Physical Drive Configurations
/----------------------------------------------------------------------------*/
#define _VOLUMES 1
/* Number of volumes (logical drives) to be used. */
#define _MAX_SS 512 /* 512, 1024, 2048 or 4096 */
/* Maximum sector size to be handled.
/ Always set 512 for memory card and hard disk but a larger value may be
/ required for on-board flash memory, floppy disk and optical disk.
/ When _MAX_SS is larger than 512, it configures FatFs to variable sector size
/ and GET_SECTOR_SIZE command must be implememted to the disk_ioctl function. */
#define _MULTI_PARTITION 0 /* 0:Single partition, 1/2:Enable multiple partition */
/* When set to 0, each volume is bound to the same physical drive number and
/ it can mount only first primaly partition. When it is set to 1, each volume
/ is tied to the partitions listed in VolToPart[]. */
#define _USE_ERASE 1 /* 0:Disable or 1:Enable */
/* To enable sector erase feature, set _USE_ERASE to 1. CTRL_ERASE_SECTOR command
/ should be added to the disk_ioctl functio. */
/*---------------------------------------------------------------------------/
/ System Configurations
/----------------------------------------------------------------------------*/
#define _WORD_ACCESS 1 /* 0 or 1 */
/* Set 0 first and it is always compatible with all platforms. The _WORD_ACCESS
/ option defines which access method is used to the word data on the FAT volume.
/
/ 0: Byte-by-byte access.
/ 1: Word access. Do not choose this unless following condition is met.
/
/ When the byte order on the memory is big-endian or address miss-aligned word
/ access results incorrect behavior, the _WORD_ACCESS must be set to 0.
/ If it is not the case, the value can also be set to 1 to improve the
/ performance and code size.
*/
/* A header file that defines sync object types on the O/S, such as
/ windows.h, ucos_ii.h and semphr.h, must be included prior to ff.h. */
#define _FS_REENTRANT 0 /* 0:Disable or 1:Enable */
#define _FS_TIMEOUT 1000 /* Timeout period in unit of time ticks */
#define _SYNC_t Semaphore * /* O/S dependent type of sync object. e.g. HANDLE, OS_EVENT*, ID and etc.. */
/* The _FS_REENTRANT option switches the reentrancy (thread safe) of the FatFs module.
/
/ 0: Disable reentrancy. _SYNC_t and _FS_TIMEOUT have no effect.
/ 1: Enable reentrancy. Also user provided synchronization handlers,
/ ff_req_grant, ff_rel_grant, ff_del_syncobj and ff_cre_syncobj
/ function must be added to the project. */
#define _FS_SHARE 0 /* 0:Disable or >=1:Enable */
/* To enable file shareing feature, set _FS_SHARE to 1 or greater. The value
defines how many files can be opened simultaneously. */
#endif /* _FFCONFIG */

View File

@@ -0,0 +1,12 @@
#include "pprz_stub.h"
#include "subsystems/gps.h"
uint16_t getGpsWeek (void)
{
return gps.week;
}
uint32_t getGpsTimeOfWeek (void)
{
return gps.tow;
}

View File

@@ -0,0 +1,6 @@
#pragma once
#include <stdint.h>
uint16_t getGpsWeek (void);
uint32_t getGpsTimeOfWeek (void);

View File

@@ -0,0 +1,468 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
Concepts and parts of this file have been contributed by Fabio Utzig.
*/
/**
* @file chprintf.c
* @brief Mini printf-like functionality.
*
* @addtogroup chprintf
* @{
*/
#include <stdarg.h>
#include "ch.h"
#include "printf.h"
#define MAX_FILLER 11
#define FLOAT_PRECISION 100000
static int intPow(int a, int b)
{
uint32_t c=a;
for (uint32_t n=b; n>1; n--) c*=a;
return c;
}
static bool_t writeBufferWithinSize (char **buffer, const char c, size_t *size)
{
if (*size) {
**buffer = c;
(*buffer)++;
return (--(*size) == 0);
} else {
return TRUE;
}
}
static char *long_to_string_with_divisor(char *p,
long num,
unsigned radix,
long divisor) {
int i;
char *q;
long l, ll;
l = num;
if (divisor == 0) {
ll = num;
} else {
ll = divisor;
}
q = p + MAX_FILLER;
do {
i = (int)(l % radix);
i += '0';
if (i > '9')
i += 'A' - '0' - 10;
*--q = i;
l /= radix;
} while ((ll /= radix) != 0);
i = (int)(p + MAX_FILLER - q);
do
*p++ = *q++;
while (--i);
return p;
}
static char *ltoa(char *p, long num, unsigned radix) {
return long_to_string_with_divisor(p, num, radix, 0);
}
#if CHPRINTF_USE_FLOAT
static char *ftoa(char *p, double num, uint32_t precision) {
long l;
// unsigned long precision = FLOAT_PRECISION;
l = num;
p = long_to_string_with_divisor(p, l, 10, 0);
*p++ = '.';
l = (num - l) * precision;
return long_to_string_with_divisor(p, l, 10, precision / 10);
}
#endif
/**
* @brief System formatted output function.
* @details This function implements a minimal @p printf() like functionality
* with output on a @p BaseSequentialStream.
* The general parameters format is: %[-][width|*][.precision|*][l|L]p.
* The following parameter types (p) are supported:
* - <b>x</b> hexadecimal integer.
* - <b>X</b> hexadecimal long.
* - <b>o</b> octal integer.
* - <b>O</b> octal long.
* - <b>d</b> decimal signed integer.
* - <b>D</b> decimal signed long.
* - <b>u</b> decimal unsigned integer.
* - <b>U</b> decimal unsigned long.
* - <b>c</b> character.
* - <b>s</b> string.
* .
*
* @param[in] chp pointer to a @p BaseSequentialStream implementing object
* @param[in] fmt formatting string
*/
void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
char *p, *s, c, filler;
int i, precision, width;
bool_t is_long, left_align;
long l;
#if CHPRINTF_USE_FLOAT
double d;
char tmpbuf[2*MAX_FILLER + 1];
int fprec=0;
#else
char tmpbuf[MAX_FILLER + 1];
#endif
while (TRUE) {
c = *fmt++;
if (c == 0) {
return;
}
if (c != '%') {
chSequentialStreamPut(chp, (uint8_t)c);
continue;
}
p = tmpbuf;
s = tmpbuf;
left_align = FALSE;
if (*fmt == '-') {
fmt++;
left_align = TRUE;
}
filler = ' ';
if (*fmt == '.') {
fmt++;
filler = '0';
#if CHPRINTF_USE_FLOAT
fprec = intPow (10, (*fmt)-'0');
#endif
}
width = 0;
while (TRUE) {
c = *fmt++;
if (c >= '0' && c <= '9')
c -= '0';
else if (c == '*')
c = va_arg(ap, int);
else
break;
width = width * 10 + c;
}
precision = 0;
if (c == '.') {
while (TRUE) {
c = *fmt++;
if (c >= '0' && c <= '9') {
c -= '0';
#if CHPRINTF_USE_FLOAT
fprec = intPow (10, c);
#endif
}
else if (c == '*')
c = va_arg(ap, int);
else
break;
precision *= 10;
precision += c;
}
}
/* Long modifier.*/
if (c == 'l' || c == 'L') {
is_long = TRUE;
if (*fmt)
c = *fmt++;
}
else
is_long = (c >= 'A') && (c <= 'Z');
/* Command decoding.*/
switch (c) {
case 'c':
filler = ' ';
*p++ = va_arg(ap, int);
break;
case 's':
filler = ' ';
if ((s = va_arg(ap, char *)) == 0)
s = "(null)";
if (precision == 0)
precision = 32767;
for (p = s; *p && (--precision >= 0); p++)
;
break;
case 'D':
case 'd':
if (is_long)
l = va_arg(ap, long);
else
l = va_arg(ap, int);
if (l < 0) {
*p++ = '-';
l = -l;
}
p = ltoa(p, l, 10);
break;
#if CHPRINTF_USE_FLOAT
case 'f':
d = (double) va_arg(ap, double);
if (d < 0) {
*p++ = '-';
d = -d;
}
p = ftoa(p, d, fprec);
break;
#endif
case 'X':
case 'x':
c = 16;
goto unsigned_common;
case 'U':
case 'u':
c = 10;
goto unsigned_common;
case 'O':
case 'o':
c = 8;
unsigned_common:
if (is_long)
l = va_arg(ap, long);
else
l = va_arg(ap, int);
p = ltoa(p, l, c);
break;
default:
*p++ = c;
break;
}
i = (int)(p - s);
if ((width -= i) < 0)
width = 0;
if (left_align == FALSE)
width = -width;
if (width < 0) {
if (*s == '-' && filler == '0') {
chSequentialStreamPut(chp, (uint8_t)*s++);
i--;
}
do
chSequentialStreamPut(chp, (uint8_t)filler);
while (++width != 0);
}
while (--i >= 0)
chSequentialStreamPut(chp, (uint8_t)*s++);
while (width) {
chSequentialStreamPut(chp, (uint8_t)filler);
width--;
}
}
}
void chvsnprintf(char *buffer, size_t size, const char *fmt, va_list ap) {
char *p, *s, c, filler;
int i, precision, width;
bool_t is_long, left_align;
long l;
#if CHPRINTF_USE_FLOAT
double d;
char tmpbuf[2*MAX_FILLER + 1];
int fprec=0;
#else
char tmpbuf[MAX_FILLER + 1];
#endif
while (TRUE) {
c = *fmt++;
if (c == 0) {
writeBufferWithinSize (&buffer, 0, &size);
return;
}
if (c != '%') {
if (writeBufferWithinSize (&buffer, c, &size)) return;
continue;
}
p = tmpbuf;
s = tmpbuf;
left_align = FALSE;
if (*fmt == '-') {
fmt++;
left_align = TRUE;
}
filler = ' ';
if (*fmt == '.') {
fmt++;
filler = '0';
#if CHPRINTF_USE_FLOAT
fprec = intPow (10, (*fmt)-'0');
#endif
}
width = 0;
while (TRUE) {
c = *fmt++;
if (c >= '0' && c <= '9')
c -= '0';
else if (c == '*')
c = va_arg(ap, int);
else
break;
width = width * 10 + c;
}
precision = 0;
if (c == '.') {
while (TRUE) {
c = *fmt++;
if (c >= '0' && c <= '9') {
c -= '0';
#if CHPRINTF_USE_FLOAT
fprec = intPow (10, c);
#endif
} else if (c == '*')
c = va_arg(ap, int);
else
break;
precision *= 10;
precision += c;
}
}
/* Long modifier.*/
if (c == 'l' || c == 'L') {
is_long = TRUE;
if (*fmt)
c = *fmt++;
}
else
is_long = (c >= 'A') && (c <= 'Z');
/* Command decoding.*/
switch (c) {
case 'c':
filler = ' ';
*p++ = va_arg(ap, int);
break;
case 's':
filler = ' ';
if ((s = va_arg(ap, char *)) == 0)
s = "(null)";
if (precision == 0)
precision = 32767;
for (p = s; *p && (--precision >= 0); p++)
;
break;
case 'D':
case 'd':
if (is_long)
l = va_arg(ap, long);
else
l = va_arg(ap, int);
if (l < 0) {
*p++ = '-';
l = -l;
}
p = ltoa(p, l, 10);
break;
#if CHPRINTF_USE_FLOAT
case 'f':
d = (double) va_arg(ap, double);
if (d < 0) {
*p++ = '-';
d = -d;
}
p = ftoa(p, d, fprec);
break;
#endif
case 'X':
case 'x':
c = 16;
goto unsigned_common;
case 'U':
case 'u':
c = 10;
goto unsigned_common;
case 'O':
case 'o':
c = 8;
unsigned_common:
if (is_long)
l = va_arg(ap, long);
else
l = va_arg(ap, int);
p = ltoa(p, l, c);
break;
default:
*p++ = c;
break;
}
i = (int)(p - s);
if ((width -= i) < 0)
width = 0;
if (left_align == FALSE)
width = -width;
if (width < 0) {
if (*s == '-' && filler == '0') {
if (writeBufferWithinSize (&buffer, (uint8_t)*s++, &size)) return;
i--;
}
do
if (writeBufferWithinSize (&buffer, (uint8_t)filler, &size)) return;
while (++width != 0);
}
while (--i >= 0)
if (writeBufferWithinSize (&buffer, (uint8_t)*s++, &size)) return;
while (width) {
if (writeBufferWithinSize (&buffer, (uint8_t)filler, &size)) return;
width--;
}
}
writeBufferWithinSize (&buffer, 0, &size) ;
}
void chsnprintf(char *buffer, size_t size, const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
chvsnprintf(buffer, size, fmt, ap);
va_end(ap);
}
void chprintf(BaseSequentialStream *chp, const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
chvprintf(chp, fmt, ap);
va_end(ap);
}
/** @} */

View File

@@ -0,0 +1,55 @@
/*
ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010,
2011,2012 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file printf.h
* @brief Mini printf-like functionality.
*
* @addtogroup chprintf
* @{
*/
#ifndef _PRINTF_H_
#define _PRINTF_H_
#include <stdarg.h>
/**
* @brief Float type support.
*/
#if !defined(CHPRINTF_USE_FLOAT) || defined(__DOXYGEN__)
#define CHPRINTF_USE_FLOAT FALSE
#endif
#ifdef __cplusplus
extern "C" {
#endif
void chprintf(BaseSequentialStream *chp, const char *fmt, ...);
void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap);
// __attribute__ ((format (printf, 2, 3)));
void chvsnprintf(char *buffer, size_t size, const char *fmt, va_list ap);
void chsnprintf(char *buffer, size_t size, const char *fmt, ...);
// __attribute__ ((format (printf, 3, 4)));
#ifdef __cplusplus
}
#endif
#endif /* _PRINTF_H_ */
/** @} */

View File

@@ -0,0 +1,144 @@
#include "ringBuffer.h"
#include <string.h>
/*
TODO:
* CircularBufferInit statique avec une macro pour eviter le malloc_m
* encapsuler dans une structure avec une mailbox chibios
* voir pb atomicité arithmetique sur les pointeurs entre
l'increment et le modulo
* peut-être réglé avec le & logique si on se restreint à des tailles modulo 2
* optimisation avec memcopy au lieu de copie octets par octets
*/
// RING_BUFFER_DECL (, toto, 10,);
// RING_BUFFER_DECL (static, toto, 10, __attribute__ ((section(".ccmram"), aligned(8))));
/**< Init Circular Buffer */
bool ringBufferIsFull(const CircularBuffer* que)
{
return ringBufferFreeSize(que) == 0;
}
bool ringBufferIsEmpty(const CircularBuffer* que)
{
return (que->readPointer == que->writePointer);
}
int32_t ringBufferFreeSize(const CircularBuffer* que)
{
if (que->writePointer < que->readPointer) {
return que->readPointer - que->writePointer -1;
} else {
return (que->size -1) - (que->writePointer - que->readPointer);
}
}
int32_t ringBufferUsedSize(const CircularBuffer* que)
{
return (que->size -1) - ringBufferFreeSize (que);
}
int32_t ringBufferEnqueBuffer(CircularBuffer* que, const uint8_t* pK, size_t len)
{
if (len > (size_t) ringBufferFreeSize (que)) {
return ERROR_CIRCULAR_BUFFER_FULL;
}
if (que->writePointer < que->readPointer) {
// write pointer is before read pointer
// only one memcpy (area don't overlap)
memcpy (&que->keys[que->writePointer], pK, len);
ringBufferWriteSeek (que, len);
} else {
// write pointer is equal or after read point
// depending on size to write, we will do one or two memcpy
if (len <= (size_t) (que->size - que->writePointer)) {
// size to write is less or equal to size from write pointer to end of buffer
// just one memcpy
memcpy (&que->keys[que->writePointer], pK, len);
ringBufferWriteSeek (que, len);
} else {
// size to write is less or equal more than size from write pointer to end of buffer
// two memcpy
const uint32_t firstCopyLen = que->size - que->writePointer;
const uint32_t secondCopyLen = len - firstCopyLen;
memcpy (&que->keys[que->writePointer], pK, firstCopyLen);
memcpy (&que->keys[0], &pK[firstCopyLen], secondCopyLen);
que->writePointer = secondCopyLen;
}
}
return len;
}
int32_t ringBufferDequeBuffer(CircularBuffer* que, uint8_t* pK, size_t len)
{
if (len > (size_t) ringBufferUsedSize (que)) {
return ERROR_CIRCULAR_BUFFER_FULL;
}
if (que->readPointer < que->writePointer) {
// read pointer is before write pointer
// only one memcpy (area don't overlap)
memcpy (pK, &que->keys[que->readPointer], len);
ringBufferReadSeek (que, len);
} else {
// read pointer is equal or after write pointer
// depending on size to read, we will do one or two memcpy
if (len <= (size_t) (que->size - que->readPointer)) {
// size to read is less or equal to size from read pointer to end of buffer
// just one memcpy
memcpy (pK, &que->keys[que->readPointer], len);
ringBufferReadSeek (que, len);
} else {
// size to read is less or equal more than size from read pointer to end of buffer
// two memcpy
const uint32_t firstCopyLen = que->size - que->readPointer;
const uint32_t secondCopyLen = len - firstCopyLen;
memcpy (pK, &que->keys[que->readPointer], firstCopyLen);
memcpy (&pK[firstCopyLen], &que->keys[0], secondCopyLen);
que->readPointer = secondCopyLen;
}
}
return len;
}
int32_t ringBufferCopyFromAddr(CircularBuffer* que, const uint16_t readFrom,
uint8_t* pK, size_t len)
{
if (readFrom < que->writePointer) {
// read pointer is before write pointer
// only one memcpy (area don't overlap)
memcpy (pK, &que->keys[readFrom], len);
} else {
// read pointer is equal or after write pointer
// depending on size to read, we will do one or two memcpy
if (len <= (size_t) (que->size - readFrom)) {
// size to read is less or equal to size from read pointer to end of buffer
// just one memcpy
memcpy (pK, &que->keys[readFrom], len);
} else {
// size to read is less or equal more than size from read pointer to end of buffer
// two memcpy
const uint32_t firstCopyLen = que->size - readFrom;
const uint32_t secondCopyLen = len - firstCopyLen;
memcpy (pK, &que->keys[readFrom], firstCopyLen);
memcpy (&pK[firstCopyLen], &que->keys[0], secondCopyLen);
}
}
return len;
}

View File

@@ -0,0 +1,104 @@
#ifndef __RING_BUFFER__
#define __RING_BUFFER__
/*
TODO:
*/
#ifdef DEBUG_ON_WORKSTATION
#include <stddef.h>
#include <stdlib.h>
#include <stdint.h>
#else
#include "std.h"
#endif
#define ERROR_CIRCULAR_BUFFER_FULL -1
#define ERROR_CIRCULAR_BUFFER_UNSYNC -2
#define _RINGBUFFER_DATA(name, _size) { \
.writePointer = 0, \
.readPointer = 0, \
.size = _size, \
.keys = __ ## name ## _ringBufferInternal \
}
#define _RINGBUFFER_BUFFER(name, size, attrib) \
static uint8_t __ ## name ## _ringBufferInternal[size] attrib = {0};
#define RINGBUFFER_DECL(scope, name, size, attrib) \
_RINGBUFFER_BUFFER(name, size, attrib); \
scope CircularBuffer name = _RINGBUFFER_DATA(name, size)
typedef struct
{
volatile uint16_t writePointer; /* write pointer */
volatile uint16_t readPointer; /* read pointer */
const uint16_t size; /* size of circular buffer */
uint8_t * const keys; /* pointer to Element of circular buffer */
} CircularBuffer;
bool ringBufferIsFull(const CircularBuffer* que);
bool ringBufferIsEmpty(const CircularBuffer* que);
int32_t ringBufferUsedSize(const CircularBuffer* que);
int32_t ringBufferFreeSize(const CircularBuffer* que);
int32_t ringBufferEnqueBuffer(CircularBuffer* que, const uint8_t* pK, size_t len);
int32_t ringBufferDequeBuffer(CircularBuffer* que, uint8_t* pK, size_t len);
int32_t ringBufferCopyFromAddr(CircularBuffer* que, const uint16_t readFrom,
uint8_t* pK, size_t len);
static inline uint16_t ringBufferGetSize(const CircularBuffer* que) {
return que->size;
}
static inline uint16_t ringBufferGetWritePointer(const CircularBuffer* que) {
return que->writePointer;
}
static inline void ringBufferSetWritePointer(CircularBuffer* que, uint16_t writePointer) {
que->writePointer = writePointer;
}
static inline uint16_t ringBufferGetReadPointer(const CircularBuffer* que) {
return que->readPointer;
}
static inline void ringBufferSetReadPointer(CircularBuffer* que, uint16_t readPointer) {
que->readPointer = readPointer;
}
static inline void ringBufferReadSeek(CircularBuffer* que, size_t len) {
que->readPointer = (que->readPointer+len) % que->size;
}
static inline void ringBufferWriteSeek(CircularBuffer* que, size_t len) {
que->writePointer = (que->writePointer+len) % que->size;
}
static inline int32_t ringBufferFreeSizeToEndOfCircular(const CircularBuffer* que)
{
return (que->size - que->writePointer);
}
static inline uint8_t *ringBufferGetAddrOfElem(const CircularBuffer* que, const uint16_t elem)
{
return (&que->keys[elem]);
}
static inline uint16_t ringBufferGetIndexOfElemAddr(const CircularBuffer* que, const uint8_t* elemAddr)
{
return (elemAddr - que->keys);
}
#endif

View File

@@ -0,0 +1,144 @@
#include "rtcAccess.h"
#include <ch.h>
#include <hal.h>
#include <chrtclib.h>
#include <time.h>
static struct tm utime;
static uint32_t weekDay (void);
void setHour (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_hour = val;
utime.tm_isdst = 0;
rtcSetTimeTm (&RTCD1, &utime);
}
void setMinute (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_min = val;
rtcSetTimeTm (&RTCD1, &utime);
}
void setSecond (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_sec = val;
rtcSetTimeTm (&RTCD1, &utime);
}
void setYear (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_year = val-1900;
rtcSetTimeTm (&RTCD1, &utime);
setWeekDay (weekDay());
}
void setMonth (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_mon = val-1;
rtcSetTimeTm (&RTCD1, &utime);
setWeekDay (weekDay());
}
void setMonthDay (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_mday = val;
rtcSetTimeTm (&RTCD1, &utime);
setWeekDay (weekDay());
}
void setWeekDay (uint32_t val)
{
rtcGetTimeTm (&RTCD1, &utime);
utime.tm_wday = val;
rtcSetTimeTm (&RTCD1, &utime);
}
uint32_t getHour (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_hour;
}
uint32_t getMinute (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_min;
}
uint32_t getSecond (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_sec;
}
uint32_t getYear (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_year+1900;
}
uint32_t getMonth (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_mon+1;
}
uint32_t getMonthDay (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_mday;
}
uint32_t getWeekDay (void)
{
rtcGetTimeTm (&RTCD1, &utime);
return utime.tm_wday;
}
const char *getWeekDayAscii (void)
{
static const char* weekDays[] = {
"Sunday",
"Monday",
"Tuesday",
"Wednesday",
"Thursday",
"Friday",
"Saturday"
};
return weekDays[(getWeekDay())];
}
void setRtcFromGps (int16_t week, uint32_t tow)
{
// Unix timestamp of the GPS epoch 1980-01-06 00:00:00 UTC
const uint32_t unixToGpsEpoch = 315964800;
struct tm time_tm;
time_t univTime = ((week * 7 * 24 * 3600) + (tow/1000)) + unixToGpsEpoch;
gmtime_r (&univTime, &time_tm);
rtcSetTimeTm (&RTCD1, &time_tm);
}
static uint32_t weekDay (void)
{
const uint32_t day = getMonthDay();
const uint32_t month = getMonth();
const uint32_t year = getYear();
return (day
+ ((153 * (month + 12 * ((14 - month) / 12) - 3) + 2) / 5)
+ (365 * (year + 4800 - ((14 - month) / 12)))
+ ((year + 4800 - ((14 - month) / 12)) / 4)
- ((year + 4800 - ((14 - month) / 12)) / 100)
+ ((year + 4800 - ((14 - month) / 12)) / 400)
- 32045) % 7;
}

View File

@@ -0,0 +1,24 @@
#ifndef __RTC_ACCESS_H__
#define __RTC_ACCESS_H__
#include <stdint.h>
void setHour (uint32_t val);
void setMinute (uint32_t val);
void setSecond (uint32_t val);
void setYear (uint32_t val);
void setMonth (uint32_t val);
void setMonthDay (uint32_t val);
void setWeekDay (uint32_t val);
void setRtcFromGps (int16_t week, uint32_t tow);
uint32_t getHour (void);
uint32_t getMinute (void);
uint32_t getSecond (void);
uint32_t getYear (void);
uint32_t getMonth (void);
uint32_t getMonthDay (void);
uint32_t getWeekDay (void);
const char* getWeekDayAscii (void);
#endif // __RTC_ACCESS_H__

View File

@@ -0,0 +1,386 @@
#include <string.h>
#include <stdlib.h>
#include "sdLog.h"
#include "ch.h"
#include "hal.h"
#include "ff.h"
#include "printf.h"
#include "sdio.h"
#include "rtcAccess.h"
#include "varLengthMsgQ.h"
#define MIN(x , y) (((x) < (y)) ? (x) : (y))
#define MAX(x , y) (((x) > (y)) ? (x) : (y))
VARLEN_MSGQUEUE_DECL(static, TRUE, messagesQueue, 16384, 512, __attribute__ ((section(".ccmram"), aligned(8))));
#define FATFS_PREBUF_SIZE 8192u
static uint8_t perfBuffer[FATFS_PREBUF_SIZE];
struct LogMessage {
FIL *fileObject;
char mess[0];
} ;
#define MAX_MESSAGE_LEN 252
#define LOG_MESSAGE_PREBUF_LEN (MAX_MESSAGE_LEN+sizeof(LogMessage))
//static LogMessage logMessages[QUEUE_LENGTH] __attribute__ ((section(".ccmram"), aligned(8))) ;
//static msg_t _bufferQueue[QUEUE_LENGTH];
//static MAILBOX_DECL(xQueue, _bufferQueue, QUEUE_LENGTH);
//static MEMORYPOOL_DECL(memPool, sizeof(LogMessage), NULL);
static FATFS fatfs; /* File system object */
static size_t logMessageLen (const LogMessage *lm);
static size_t logRawLen (const size_t len);
static SdioError getNextFileName(const char* prefix, const char* directoryName,
char* nextFileName, const size_t nameLength);
static uint32_t uiGetIndexOfLogFile (const char* prefix, const char* fileName) ;
static msg_t thdSdLog(void *arg) ;
static Thread *sdLogThd = NULL;
SdioError sdLogInit (uint32_t* freeSpaceInKo)
{
DWORD clusters=0;
FATFS *fsp=NULL;
varLenMsgDynamicInit (&messagesQueue);
if (!sdc_lld_is_card_inserted (NULL))
return SDLOG_NOCARD;
sdioConnect ();
chThdSleepMilliseconds (10);
sdioDisconnect ();
if (sdioConnect () == FALSE)
return SDLOG_NOCARD;
FRESULT rc = f_mount(0, &fatfs);
if (rc != FR_OK) {
return SDLOG_FATFS_ERROR;
}
if (freeSpaceInKo != NULL) {
f_getfree("/", &clusters, &fsp);
*freeSpaceInKo = clusters * (uint32_t)fatfs.csize / 2;
}
return SDLOG_OK ;
}
SdioError sdLogFinish (void)
{
FRESULT rc = f_mount(0, NULL);
if (rc != FR_OK) {
return SDLOG_FATFS_ERROR;
}
// if we mount, unmount, don't disconnect sdio
/* if (sdioDisconnect () == FALSE) */
/* return SDLOG_NOCARD; */
return SDLOG_OK ;
}
SdioError sdLogOpenLog (FIL *fileObject, const char* directoryName, const char* prefix)
{
FRESULT rc; /* fatfs result code */
SdioError sde; /* sdio result code */
//DIR dir; /* Directory object */
//FILINFO fno; /* File information object */
char fileName[32];
sde = getNextFileName(prefix, directoryName, fileName, sizeof (fileName));
if (sde != SDLOG_OK) {
// sd card is not inserted, so logging task can be deleted
return SDLOG_FATFS_ERROR;
}
rc = f_open(fileObject, fileName, FA_WRITE | FA_CREATE_ALWAYS);
if (rc) {
return SDLOG_FATFS_ERROR;
}
return SDLOG_OK;
}
SdioError sdLogCloseLog (FIL *fileObject)
{
FRESULT rc; /* Result code */
if (fileObject->fs == NULL)
return SDLOG_FATFS_ERROR;
rc = f_close(fileObject);
if (rc) {
return SDLOG_FATFS_ERROR;
}
return SDLOG_OK;
}
SdioError sdLogWriteLog (FIL *fileObject, const char* fmt, ...)
{
if (fileObject->fs == NULL)
return SDLOG_FATFS_ERROR;
va_list ap;
va_start(ap, fmt);
LogMessage *lm = alloca(LOG_MESSAGE_PREBUF_LEN);
lm->fileObject = fileObject;
chvsnprintf (lm->mess, MAX_MESSAGE_LEN-1, fmt, ap);
lm->mess[MAX_MESSAGE_LEN-1]=0;
va_end(ap);
if (varLenMsgQueuePush (&messagesQueue, lm, logMessageLen(lm), VarLenMsgQueue_REGULAR) < 0) {
return SDLOG_QUEUEFULL;
}
return SDLOG_OK;
}
SdioError sdLogWriteRaw (FIL *fileObject, const uint8_t * buffer, const size_t len)
{
if (fileObject->fs == NULL)
return SDLOG_FATFS_ERROR;
LogMessage *lm = alloca(LOG_MESSAGE_PREBUF_LEN);
lm->fileObject = fileObject;
memcpy (lm->mess, buffer, len);
if (varLenMsgQueuePush (&messagesQueue, lm, logRawLen(len), VarLenMsgQueue_REGULAR) < 0) {
return SDLOG_QUEUEFULL;
}
return SDLOG_OK;
}
SdioError sdLogWriteByte (FIL *fileObject, const uint8_t value)
{
if (fileObject->fs == NULL)
return SDLOG_FATFS_ERROR;
LogMessage *lm = alloca(sizeof(LogMessage)+1);
lm->fileObject = fileObject;
lm->mess[0] = value;
if (varLenMsgQueuePush (&messagesQueue, lm, sizeof(LogMessage)+1, VarLenMsgQueue_REGULAR) < 0) {
return SDLOG_QUEUEFULL;
}
return SDLOG_OK;
}
/* enregistrer les fichiers ouverts de manière à les fermer
si necessaire
*/
static WORKING_AREA(waThdSdLog, 2048);
SdioError sdLoglaunchThread (const bool_t binaryLog)
{
chThdSleepMilliseconds(100);
sdLogThd = chThdCreateStatic(waThdSdLog, sizeof(waThdSdLog),
NORMALPRIO, thdSdLog, (void *) binaryLog);
if (sdLogThd == NULL)
return SDLOG_INTERNAL_ERROR;
else
return SDLOG_OK;
}
SdioError sdLogStopThread (void)
{
SdioError retVal=SDLOG_OK;
if (sdLogThd == NULL)
return SDLOG_NOTHREAD;
static LogMessage lm;
lm.fileObject = NULL;
if (varLenMsgQueuePush (&messagesQueue, &lm, sizeof(LogMessage), VarLenMsgQueue_OUT_OF_BAND) < 0) {
retVal= SDLOG_QUEUEFULL;
}
chThdTerminate (sdLogThd);
chThdWait (sdLogThd);
sdLogThd = NULL;
return retVal;
}
/*
# _____ _ _
# | __ \ (_) | |
# | |__) | _ __ _ __ __ __ _ | |_ ___
# | ___/ | '__| | | \ \ / / / _` | | __| / _ \
# | | | | | | \ V / | (_| | \ |_ | __/
# |_| |_| |_| \_/ \__,_| \__| \___|
*/
static SdioError getNextFileName(const char* prefix, const char* directoryName,
char* nextFileName, const size_t nameLength)
{
DIR dir; /* Directory object */
FRESULT rc; /* Result code */
FILINFO fno; /* File information object */
uint32_t fileIndex ;
uint32_t maxCurrentIndex = 0;
char *fn; /* This function is assuming non-Unicode cfg. */
#if _USE_LFN
char lfn[_MAX_LFN + 1];
fno.lfname = lfn;
fno.lfsize = sizeof lfn;
#endif
const size_t directoryNameLen = strlen (directoryName);
char slashDirName[directoryNameLen+2];
strcpy (slashDirName, "/");
strcat (slashDirName, directoryName);
rc = f_opendir(&dir, directoryName);
if (rc != FR_OK) {
rc = f_mkdir(slashDirName);
if (rc != FR_OK) {
return SDLOG_FATFS_ERROR;
}
rc = f_opendir(&dir, directoryName);
if (rc != FR_OK) {
return SDLOG_FATFS_ERROR;
}
}
for (;;) {
rc = f_readdir(&dir, &fno); /* Read a directory item */
if (rc != FR_OK || fno.fname[0] == 0) break; /* Error or end of dir */
#if _USE_LFN
fn = *fno.lfname ? fno.lfname : fno.fname;
#else
fn = fno.fname;
#endif
if (fn[0] == '.') continue;
if (!(fno.fattrib & AM_DIR)) {
//vPrintMsg ("%8lu %s\n", fno.fsize, fn);
fileIndex = uiGetIndexOfLogFile (prefix, fn);
maxCurrentIndex = MAX (maxCurrentIndex, fileIndex);
}
}
if (rc) {
return SDLOG_FATFS_ERROR;
}
chsnprintf (nextFileName, nameLength, "%s\\%s%.03d.LOG",
directoryName, prefix, maxCurrentIndex+1);
return SDLOG_OK;
}
uint32_t uiGetIndexOfLogFile (const char* prefix, const char* fileName)
{
const size_t len = strlen(prefix);
// if filename does not began with prefix, return 0
if (strncmp (prefix, fileName, len))
return 0;
// we point on the first char after prefix
const char* suffix = &(fileName[len]);
return (uint32_t) atoi (suffix);
}
static msg_t thdSdLog(void *arg)
{
UINT bw;
uint32_t curBufFill=0;
FIL *foSaved = NULL;
const bool_t appendCloseLogMsg = (bool_t) arg;
/* LogMessage *lm = alloca(LOG_MESSAGE_PREBUF_LEN) */;
chRegSetThreadName("thdSdLog");
while (!chThdShouldTerminate()) {
// if ((retLen = varLenMsgQueuePop (&messagesQueue, lm, LOG_MESSAGE_PREBUF_LEN)) > 0) {
const ChunkBufferRO cbro = varLenMsgQueuePopChunk (&messagesQueue);
const int32_t retLen = cbro.blen;
if (retLen > 0) {
const LogMessage *lm = (LogMessage *) cbro.bptr;
if (lm->fileObject == NULL) {
if (foSaved) {
if (curBufFill) {
f_write(foSaved, perfBuffer, curBufFill, &bw);
}
if (appendCloseLogMsg) {
f_write(foSaved, "\r\nEND_OF_LOG\r\n", 14, &bw);
}
f_sync (foSaved);
}
chThdExit(SDLOG_OK);
continue; /* To exit from thread when asked : chThdTerminate
then send special message with fileObject NULL to unblock thread
*/
}
foSaved = lm->fileObject;
// put end of string at end of message
//lm->mess[retLen-sizeof(LogMessage)]=0;
const uint32_t messLen = retLen-sizeof(LogMessage);
if (messLen < (FATFS_PREBUF_SIZE-curBufFill)) {
// the buffer can accept this message
memcpy (&(perfBuffer[curBufFill]), lm->mess, messLen);
curBufFill += messLen;
} else {
// fill the buffer
const uint32_t stayLen = FATFS_PREBUF_SIZE-curBufFill;
memcpy (&(perfBuffer[curBufFill]), lm->mess, stayLen);
FRESULT rc = f_write(lm->fileObject, perfBuffer, FATFS_PREBUF_SIZE, &bw);
f_sync (lm->fileObject);
if (rc) {
return SDLOG_FATFS_ERROR;
} else if (bw != FATFS_PREBUF_SIZE) {
return SDLOG_FSFULL;
}
memcpy (perfBuffer, &(lm->mess[stayLen]), messLen-stayLen);
curBufFill=messLen-stayLen;
}
varLenMsgQueueFreeChunk (&messagesQueue, &cbro);
} else {
return SDLOG_INTERNAL_ERROR;
}
}
return SDLOG_OK;
}
static size_t logMessageLen (const LogMessage *lm)
{
return sizeof(LogMessage) + strnlen (lm->mess, MAX_MESSAGE_LEN);
}
static size_t logRawLen (const size_t len)
{
return sizeof(LogMessage) + len;
}

View File

@@ -0,0 +1,30 @@
#ifndef __SD_LOG_H__
#define __SD_LOG_H__
#include "ff.h"
#include <stdarg.h>
typedef struct LogMessage LogMessage;
typedef enum {
SDLOG_OK,
SDLOG_NOCARD,
SDLOG_FATFS_ERROR,
SDLOG_FSFULL,
SDLOG_QUEUEFULL,
SDLOG_NOTHREAD,
SDLOG_INTERNAL_ERROR
} SdioError;
SdioError sdLogInit (uint32_t* freeSpaceInKo);
SdioError sdLogFinish (void);
SdioError sdLogOpenLog (FIL *fileObject, const char* directoryName, const char* fileName);
SdioError sdLoglaunchThread (const bool_t binaryLog);
SdioError sdLogWriteLog (FIL *fileObject, const char* fmt, ...);
SdioError sdLogWriteRaw (FIL *fileObject, const uint8_t* buffer, const size_t len);
SdioError sdLogWriteByte (FIL *fileObject, const uint8_t value);
SdioError sdLogCloseLog (FIL *fileObject);
SdioError sdLogStopThread (void);
#endif // __SD_LOG_H__

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,6 @@
#pragma once
bool_t sdioConnect (void);
bool_t sdioDisconnect (void);
bool_t isCardInserted (void);
void cmd_sdiotest(void);

File diff suppressed because it is too large Load Diff

Some files were not shown because too many files have changed in this diff Show More