From 2a0dba402591bc58df894432dbeda4a958c3d12f Mon Sep 17 00:00:00 2001 From: Freek van Tienen Date: Wed, 18 May 2022 17:38:58 +0200 Subject: [PATCH] [chibios] Add STM32H7 (#2859) * [chibios] Add STM32H7 * [chibios] Update to latest version * [chibios] Cleanup board configuration * [chibios] Cleanup peripheral drivers * [chibios] Fix bootloader interrupt vector done inside ChibiOS * [sdlogger] Enable RTC by default * [chibios] Fix DMA buffers SPI/I2C * [formatting] Fix formatting/styling of files * [chibios] Change PWM configuration (small fixes i2c and makefile) * [chibios] Generic board files * [boards] Fix apogee board * [conf] Cleanup airframes and remove Navstik board --- .gitmodules | 4 +- .vscode/settings.json | 6 +- conf/Makefile.chibios | 9 +- conf/airframes/ENAC/conf_enac.xml | 8 +- conf/airframes/examples/cube_orange.xml | 365 ++++ conf/airframes/examples/quadrotor_navstik.xml | 216 --- conf/boards/apogee_1.0_chibios.makefile | 2 +- conf/boards/chimera_1.0.makefile | 3 +- conf/boards/crazyflie_2.1.makefile | 2 +- conf/boards/cube_orange.makefile | 88 + conf/boards/holybro_kakute_f7.makefile | 3 +- conf/boards/lisa_m_common_chibios.makefile | 2 +- conf/boards/lisa_mx_2.1_chibios.makefile | 2 +- conf/boards/matek_f765_wing.makefile | 3 +- conf/boards/navstik_1.0.makefile | 54 - conf/boards/nucleo144_f767zi.makefile | 3 +- conf/boards/px4fmu_2.4_chibios.makefile | 10 +- conf/boards/px4fmu_4.0_chibios.makefile | 13 +- conf/boards/px4fmu_5.0_chibios.makefile | 26 +- conf/boards/tawaki_common.makefile | 3 +- conf/conf_example.xml | 37 +- conf/conf_tests.xml | 65 +- conf/conf_tests_coverity.xml | 49 +- conf/firmwares/baro_board.makefile | 7 - conf/firmwares/test_progs.makefile | 3 - conf/flash_modes.xml | 4 +- conf/modules/baro_board.xml | 10 +- conf/modules/boards/cube_orange.xml | 17 + conf/modules/boards/navstik_1.0.xml | 14 - conf/modules/boards/px4fmu_5.0_chibios.xml | 4 +- conf/modules/imu_navstik.xml | 47 - conf/userconf/tudelft/conf.xml | 2 +- sw/airborne/arch/chibios/STM32H743xI.ld | 139 ++ .../kakute_f7 => arch/chibios}/board.c | 132 +- sw/airborne/arch/chibios/chconf.h | 111 +- .../px4fmu.h => arch/chibios/common_board.h} | 260 +-- sw/airborne/arch/chibios/ffconf.h | 129 +- sw/airborne/arch/chibios/halconf.h | 83 +- sw/airborne/arch/chibios/mcu_arch.c | 33 +- sw/airborne/arch/chibios/mcu_arch.h | 9 +- .../arch/chibios/mcu_periph/adc_arch.c | 171 +- .../arch/chibios/mcu_periph/adc_arch.h | 2 +- .../arch/chibios/mcu_periph/gpio_arch.c | 6 +- .../arch/chibios/mcu_periph/i2c_arch.c | 220 +-- .../arch/chibios/mcu_periph/ram_arch.h | 25 +- .../arch/chibios/mcu_periph/sdio_arch.c | 41 +- .../arch/chibios/mcu_periph/spi_arch.c | 301 +-- .../arch/chibios/mcu_periph/sys_time_arch.c | 16 +- .../arch/chibios/mcu_periph/uart_arch.c | 12 +- .../modules/actuators/actuators_pwm_arch.c | 249 ++- .../modules/actuators/actuators_pwm_arch.h | 36 - .../arch/chibios/modules/core/rtos_mon_arch.c | 92 +- .../arch/chibios/modules/core/shell_arch.c | 20 +- .../chibios/modules/tlsf/tlsf_malloc_arch.h | 6 +- .../arch/chibios/modules/uavcan/uavcan.c | 167 +- .../arch/chibios/modules/uavcan/uavcan.h | 1 + sw/airborne/autopilot.c | 6 +- .../boards/apogee/chibios/v1.0/board.c | 278 --- .../boards/apogee/chibios/v1.0/board.cfg | 333 ++-- .../boards/apogee/chibios/v1.0/board.h | 354 ++-- .../boards/apogee/chibios/v1.0/board.mk | 24 - .../boards/apogee/chibios/v1.0/mcuconf.h | 22 + .../boards/chimera/chibios/v1.0/board.c | 283 --- .../boards/chimera/chibios/v1.0/board.cfg | 137 +- .../boards/chimera/chibios/v1.0/board.h | 215 ++- .../boards/chimera/chibios/v1.0/board.mk | 24 - .../boards/chimera/chibios/v1.0/chimera.h | 190 +- .../boards/crazyflie/chibios/v2.1/board.c | 263 --- .../boards/crazyflie/chibios/v2.1/board.mk | 24 - .../boards/crazyflie/chibios/v2.1/crazyflie.h | 57 +- .../boards/crazyflie/chibios/v2.1/mcuconf.h | 22 + sw/airborne/boards/cube/orange/Makefile | 9 + sw/airborne/boards/cube/orange/board.cfg | 166 ++ sw/airborne/boards/cube/orange/board.h | 1691 +++++++++++++++++ sw/airborne/boards/cube/orange/mcuconf.h | 582 ++++++ sw/airborne/boards/holybro/kakute_f7/Makefile | 9 + .../{holybro_kakute_f7.cfg => board.cfg} | 3 + sw/airborne/boards/holybro/kakute_f7/board.h | 28 + sw/airborne/boards/holybro/kakute_f7/board.mk | 24 - .../holybro/kakute_f7/holybro_kakute_f7.h | 82 +- sw/airborne/boards/lia/chibios/v1.1/board.c | 269 --- sw/airborne/boards/lia/chibios/v1.1/board.h | 108 +- sw/airborne/boards/lia/chibios/v1.1/board.mk | 24 - .../boards/lisa_mx/chibios/v2.1/board.c | 264 --- .../boards/lisa_mx/chibios/v2.1/board.h | 104 +- .../boards/lisa_mx/chibios/v2.1/board.mk | 24 - .../boards/lisa_mx/chibios/v2.1/mcuconf.h | 22 + .../boards/mateksys/F765-WING/Makefile | 9 + sw/airborne/boards/mateksys/F765-WING/board.c | 278 --- sw/airborne/boards/mateksys/F765-WING/board.h | 36 + .../boards/mateksys/F765-WING/board.mk | 24 - .../mateksys/F765-WING/matekF765-WING.cfg | 3 + .../mateksys/F765-WING/matekF765-WING.h | 143 +- sw/airborne/boards/navstik/baro_board.c | 72 - sw/airborne/boards/navstik/baro_board.h | 37 - sw/airborne/boards/nucleo/144_f767zi/board.c | 262 --- sw/airborne/boards/nucleo/144_f767zi/board.mk | 24 - .../nucleo/144_f767zi/nucleo144_f767zi.h | 140 +- .../boards/px4fmu/chibios/v2.4/board.c | 266 --- .../boards/px4fmu/chibios/v2.4/board.h | 72 +- .../boards/px4fmu/chibios/v2.4/board.mk | 24 - .../boards/px4fmu/chibios/v2.4/mcuconf.h | 22 + .../boards/px4fmu/chibios/v4.0/board.c | 263 --- .../boards/px4fmu/chibios/v4.0/board.cfg | 163 +- .../boards/px4fmu/chibios/v4.0/board.h | 148 +- .../boards/px4fmu/chibios/v4.0/board.mk | 24 - .../boards/px4fmu/chibios/v4.0/mcuconf.h | 32 +- .../boards/px4fmu/chibios/v4.0/px4fmu.h | 190 +- .../boards/px4fmu/chibios/v5.0/board.c | 263 --- .../boards/px4fmu/chibios/v5.0/board.cfg | 130 +- .../boards/px4fmu/chibios/v5.0/board.h | 141 ++ .../boards/px4fmu/chibios/v5.0/board.mk | 24 - .../boards/px4fmu/chibios/v5.0/mcuconf.h | 4 +- .../boards/tawaki/chibios/common/board.c | 287 --- .../boards/tawaki/chibios/common/tawaki.h | 140 +- .../boards/tawaki/chibios/v1.0/board.h | 32 + .../boards/tawaki/chibios/v1.0/board.mk | 26 - .../boards/tawaki/chibios/v1.0/tawaki_1.0.cfg | 4 +- .../boards/tawaki/chibios/v1.1/Makefile | 2 +- .../boards/tawaki/chibios/v1.1/board.h | 32 + .../boards/tawaki/chibios/v1.1/board.mk | 26 - .../boards/tawaki/chibios/v1.1/tawaki_1.1.cfg | 4 +- sw/airborne/mcu.c | 8 +- sw/airborne/mcu_periph/spi.h | 3 + sw/airborne/mcu_periph/uart.h | 14 +- sw/airborne/modules/imu/imu_navstik.c | 131 -- sw/airborne/modules/imu/imu_navstik.h | 83 - sw/airborne/modules/loggers/sdlog_chibios.c | 11 +- .../modules/loggers/sdlog_chibios/sdLog.c | 3 - sw/ext/Makefile | 10 +- sw/ext/chibios | 2 +- sw/ext/fatfs | 2 +- sw/tools/flash_scripts/bmp_swd_flash.scr | 2 + .../flash_scripts/bmp_swd_nopwr_flash.scr | 2 + sw/tools/px4/cube_orange.prototype | 13 + sw/tools/px4/px4fmu_5.0.prototype | 13 + sw/tools/px4/set_target.py | 9 +- 137 files changed, 5955 insertions(+), 6681 deletions(-) create mode 100644 conf/airframes/examples/cube_orange.xml delete mode 100644 conf/airframes/examples/quadrotor_navstik.xml create mode 100644 conf/boards/cube_orange.makefile delete mode 100644 conf/boards/navstik_1.0.makefile create mode 100644 conf/modules/boards/cube_orange.xml delete mode 100644 conf/modules/boards/navstik_1.0.xml delete mode 100644 conf/modules/imu_navstik.xml create mode 100644 sw/airborne/arch/chibios/STM32H743xI.ld rename sw/airborne/{boards/holybro/kakute_f7 => arch/chibios}/board.c (71%) rename sw/airborne/{boards/px4fmu/chibios/v5.0/px4fmu.h => arch/chibios/common_board.h} (79%) delete mode 100644 sw/airborne/boards/apogee/chibios/v1.0/board.c delete mode 100644 sw/airborne/boards/apogee/chibios/v1.0/board.mk delete mode 100644 sw/airborne/boards/chimera/chibios/v1.0/board.c delete mode 100644 sw/airborne/boards/chimera/chibios/v1.0/board.mk delete mode 100644 sw/airborne/boards/crazyflie/chibios/v2.1/board.c delete mode 100644 sw/airborne/boards/crazyflie/chibios/v2.1/board.mk create mode 100644 sw/airborne/boards/cube/orange/Makefile create mode 100644 sw/airborne/boards/cube/orange/board.cfg create mode 100644 sw/airborne/boards/cube/orange/board.h create mode 100644 sw/airborne/boards/cube/orange/mcuconf.h create mode 100644 sw/airborne/boards/holybro/kakute_f7/Makefile rename sw/airborne/boards/holybro/kakute_f7/{holybro_kakute_f7.cfg => board.cfg} (98%) delete mode 100644 sw/airborne/boards/holybro/kakute_f7/board.mk delete mode 100644 sw/airborne/boards/lia/chibios/v1.1/board.c delete mode 100644 sw/airborne/boards/lia/chibios/v1.1/board.mk delete mode 100644 sw/airborne/boards/lisa_mx/chibios/v2.1/board.c delete mode 100644 sw/airborne/boards/lisa_mx/chibios/v2.1/board.mk create mode 100644 sw/airborne/boards/mateksys/F765-WING/Makefile delete mode 100644 sw/airborne/boards/mateksys/F765-WING/board.c delete mode 100644 sw/airborne/boards/mateksys/F765-WING/board.mk delete mode 100644 sw/airborne/boards/navstik/baro_board.c delete mode 100644 sw/airborne/boards/navstik/baro_board.h delete mode 100644 sw/airborne/boards/nucleo/144_f767zi/board.c delete mode 100644 sw/airborne/boards/nucleo/144_f767zi/board.mk delete mode 100644 sw/airborne/boards/px4fmu/chibios/v2.4/board.c delete mode 100644 sw/airborne/boards/px4fmu/chibios/v2.4/board.mk delete mode 100644 sw/airborne/boards/px4fmu/chibios/v4.0/board.c delete mode 100644 sw/airborne/boards/px4fmu/chibios/v4.0/board.mk delete mode 100644 sw/airborne/boards/px4fmu/chibios/v5.0/board.c delete mode 100644 sw/airborne/boards/px4fmu/chibios/v5.0/board.mk delete mode 100644 sw/airborne/boards/tawaki/chibios/common/board.c delete mode 100644 sw/airborne/boards/tawaki/chibios/v1.0/board.mk delete mode 100644 sw/airborne/boards/tawaki/chibios/v1.1/board.mk delete mode 100644 sw/airborne/modules/imu/imu_navstik.c delete mode 100644 sw/airborne/modules/imu/imu_navstik.h create mode 100644 sw/tools/px4/cube_orange.prototype create mode 100644 sw/tools/px4/px4fmu_5.0.prototype diff --git a/.gitmodules b/.gitmodules index 71b3af1e13..1729877be7 100644 --- a/.gitmodules +++ b/.gitmodules @@ -6,10 +6,10 @@ url = https://github.com/paparazzi/luftboot.git [submodule "sw/ext/fatfs"] path = sw/ext/fatfs - url = https://github.com/enacuavlab/fatfs.git + url = https://github.com/paparazzi/fatfs.git [submodule "sw/ext/chibios"] path = sw/ext/chibios - url = https://github.com/ChibiOS/ChibiOS.git + url = https://github.com/paparazzi/ChibiOS.git [submodule "sw/ext/libzbar"] path = sw/ext/libzbar url = https://github.com/paparazzi/libzbar diff --git a/.vscode/settings.json b/.vscode/settings.json index 7e8a23ab98..cb3a30ff32 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -9,9 +9,7 @@ "editor.tabSize": 4, }, "files.associations": { - "mateksys_3901_l0x.h": "c", - "stdlib.h": "c", - "iterator": "cpp", - "tensor": "cpp" + "Makefile.*": "makefile" }, + "C_Cpp.dimInactiveRegions": false, } \ No newline at end of file diff --git a/conf/Makefile.chibios b/conf/Makefile.chibios index b1664cb011..dbfff35494 100644 --- a/conf/Makefile.chibios +++ b/conf/Makefile.chibios @@ -26,7 +26,9 @@ CHIBIOS = $(PAPARAZZI_SRC)/sw/ext/chibios # directory with board defines for chibios platforms (board specific) +BOARD_COMMON ?= BOARD_DIR ?= $(BOARD)/chibios +CHIBIOS_BOARD_COMMON_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD_COMMON) CHIBIOS_BOARD_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD_DIR) # chibos linker scripts directory @@ -206,11 +208,10 @@ include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/$(CHIBIOS_BOARD_STA # HAL-OSAL files (optional). include $(CHIBIOS)/os/hal/hal.mk include $(CHIBIOS)/os/hal/ports/STM32/$(CHIBIOS_BOARD_PLATFORM) -include $(CHIBIOS_BOARD_DIR)/board.mk include $(CHIBIOS)/os/hal/osal/rt-nil/osal.mk # RTOS files (optional). include $(CHIBIOS)/os/rt/rt.mk -include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk +include $(CHIBIOS)/os/common/ports/ARMv7-M/compilers/GCC/mk/port.mk # Other files (optional). # ifeq ($(USE_FATFS), TRUE) @@ -224,7 +225,7 @@ LDSCRIPT= $(CHIBIOS_LINKER_DIR)/$(CHIBIOS_BOARD_LINKER) # setting. CSRC = $(ALLCSRC) \ $(CHIBIOS)/os/various/syscalls.c \ - $(CHIBIOS_BOARD_MAIN) + $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/board.c ECSRC = $(filter %.c, $($(TARGET).srcs)) ECPPSRC = $(filter %.cpp, $($(TARGET).srcs)) @@ -256,7 +257,7 @@ TCPPSRC = # List ASM source files here ASMXSRC = $(STARTUPASM) $(PORTASM) $(OSALASM) -INCDIR = $(CONFDIR) $(ALLINC) $(CHIBIOS_BOARD_DIR) +INCDIR = $(CONFDIR) $(ALLINC) $(CHIBIOS_BOARD_DIR) $(CHIBIOS_BOARD_COMMON_DIR) # Output directory and files BUILDDIR := $(AIRCRAFT_BUILD_DIR)/$(TARGET) diff --git a/conf/airframes/ENAC/conf_enac.xml b/conf/airframes/ENAC/conf_enac.xml index e706b1154f..5e69b098e0 100644 --- a/conf/airframes/ENAC/conf_enac.xml +++ b/conf/airframes/ENAC/conf_enac.xml @@ -18,7 +18,7 @@ telemetry="telemetry/default_rotorcraft.xml" flight_plan="flight_plans/rotorcraft_basic_safety.xml" settings="settings/rotorcraft_basic.xml" - settings_modules="modules/ins_extended.xml modules/ahrs_float_invariant.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml" + settings_modules="modules/ahrs_float_invariant.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml" gui_color="red" /> + + + + + Neddrone5 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + +
+ + + + + + + + + + + + + +
+ + + + + + + + + + + +
+ +
+ + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + +
+ +
+ + + + + + +
+ +
+ + + + + +
+ +
+ + + + +
+ +
+ + + + + +
+ +
diff --git a/conf/airframes/examples/quadrotor_navstik.xml b/conf/airframes/examples/quadrotor_navstik.xml deleted file mode 100644 index 7bf8ccb18f..0000000000 --- a/conf/airframes/examples/quadrotor_navstik.xml +++ /dev/null @@ -1,216 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - - - - - - - -
- - - - - - - - - -
- - - - - - - - - - - - - - - -
- -
- - - -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - -
- -
- - - - - - -
- -
- - - -
- -
- - - -
- -
- - - - -
- -
diff --git a/conf/boards/apogee_1.0_chibios.makefile b/conf/boards/apogee_1.0_chibios.makefile index 7c5e694171..5334bb092c 100644 --- a/conf/boards/apogee_1.0_chibios.makefile +++ b/conf/boards/apogee_1.0_chibios.makefile @@ -17,7 +17,7 @@ RTOS=chibios ## FPU on F4 USE_FPU=softfp -$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options diff --git a/conf/boards/chimera_1.0.makefile b/conf/boards/chimera_1.0.makefile index e64127e800..1a3ec32266 100644 --- a/conf/boards/chimera_1.0.makefile +++ b/conf/boards/chimera_1.0.makefile @@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16 USE_LTO ?= yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options @@ -33,7 +33,6 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk diff --git a/conf/boards/crazyflie_2.1.makefile b/conf/boards/crazyflie_2.1.makefile index b968de9ad5..39ed27b2d4 100644 --- a/conf/boards/crazyflie_2.1.makefile +++ b/conf/boards/crazyflie_2.1.makefile @@ -18,7 +18,7 @@ ARCH=chibios ## FPU on F4 USE_FPU=softfp -$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options diff --git a/conf/boards/cube_orange.makefile b/conf/boards/cube_orange.makefile new file mode 100644 index 0000000000..0b2602f285 --- /dev/null +++ b/conf/boards/cube_orange.makefile @@ -0,0 +1,88 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# cube_orange.makefile +# +# This is for the main MCU (STM32F767) on the PX4 board +# See https://pixhawk.org/modules/pixhawk for details +# + +BOARD=cube +BOARD_VERSION=orange +BOARD_DIR=$(BOARD)/$(BOARD_VERSION) +BOARD_CFG=\"arch/chibios/common_board.h\" + +ARCH=chibios +$(TARGET).ARCHDIR = $(ARCH) + +RTOS=chibios +MCU=cortex-m7 + +# FPU on F7 +USE_FPU=hard +USE_FPU_OPT= -mfpu=fpv5-d16 + +#USE_LTO=yes + +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD + +############################################################################## +# Architecture or project specific options +# +# Define project name here (target) +PROJECT = $(TARGET) + +# Project specific files and paths (see Makefile.chibios for details) +CHIBIOS_BOARD_PLATFORM = STM32H7xx/platform.mk +CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/ +CHIBIOS_BOARD_LINKER = STM32H743xI.ld +CHIBIOS_BOARD_STARTUP = startup_stm32h7xx.mk + +############################################################################## +# Compiler settings +# + +# default flash mode is the PX4 bootloader +# possibilities: DFU, SWD, PX4 bootloader +FLASH_MODE ?= PX4_BOOTLOADER +PX4_TARGET = "ap" +PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/cube_orange.prototype" +PX4_BL_PORT ?= "/dev/serial/by-id/usb-Hex_ProfiCNC_CubeOrange*-BL*" + +# +# default LED configuration +# +SDLOG_LED ?= none +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= none +GPS_LED ?= none +SYS_TIME_LED ?= 1 + +# +# default UART configuration (modem, gps, spektrum) +# The TELEM2 port +SBUS_PORT ?= UART3 +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART3 + +# The TELEM1 port (UART3 is TELEM2) +MODEM_PORT ?= UART2 +MODEM_BAUD ?= B57600 + +# The GPS1 port (UART8 is GPS2) +GPS_PORT ?= UART1 +GPS_BAUD ?= B57600 + +# InterMCU port connected to the IO processor +INTERMCU_PORT ?= UART6 +INTERMCU_BAUD ?= B230400 + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_pwm + diff --git a/conf/boards/holybro_kakute_f7.makefile b/conf/boards/holybro_kakute_f7.makefile index 420b4d0997..d33d717a0a 100644 --- a/conf/boards/holybro_kakute_f7.makefile +++ b/conf/boards/holybro_kakute_f7.makefile @@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-sp-d16 USE_LTO ?= yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U ############################################################################## # Architecture or project specific options @@ -33,7 +33,6 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk #CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_LINKER = STM32F746xG.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk diff --git a/conf/boards/lisa_m_common_chibios.makefile b/conf/boards/lisa_m_common_chibios.makefile index 7a929d98cb..acf0039a33 100644 --- a/conf/boards/lisa_m_common_chibios.makefile +++ b/conf/boards/lisa_m_common_chibios.makefile @@ -15,7 +15,7 @@ RTOS=chibios USE_FPU=no HARD_FLOAT=no -$(TARGET).CFLAGS += -DSTM32F1 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options diff --git a/conf/boards/lisa_mx_2.1_chibios.makefile b/conf/boards/lisa_mx_2.1_chibios.makefile index d13fa2bf3d..1d472237d8 100644 --- a/conf/boards/lisa_mx_2.1_chibios.makefile +++ b/conf/boards/lisa_mx_2.1_chibios.makefile @@ -20,7 +20,7 @@ USE_FPU=hard # See list of supported Tier 3 architectures at: https://forge.rust-lang.org/platform-support.html RUST_ARCH = thumbv7em-none-eabihf -$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options diff --git a/conf/boards/matek_f765_wing.makefile b/conf/boards/matek_f765_wing.makefile index b0f5b5994b..7653093014 100644 --- a/conf/boards/matek_f765_wing.makefile +++ b/conf/boards/matek_f765_wing.makefile @@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16 USE_LTO ?= yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U ############################################################################## # Architecture or project specific options @@ -33,7 +33,6 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk diff --git a/conf/boards/navstik_1.0.makefile b/conf/boards/navstik_1.0.makefile deleted file mode 100644 index 53aa9f458f..0000000000 --- a/conf/boards/navstik_1.0.makefile +++ /dev/null @@ -1,54 +0,0 @@ -# Hey Emacs, this is a -*- makefile -*- -# -# navstik_1.0.makefile -# -# http://wiki.paparazziuav.org/wiki/Navstik -# - -BOARD=navstik -BOARD_VERSION=1.0 -BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\" - -ARCH=stm32 -ARCH_L=f4 -HARD_FLOAT=yes -$(TARGET).ARCHDIR = $(ARCH) -$(TARGET).OOCD_INTERFACE=ftdi/ivygs -$(TARGET).OOCD_BOARD=navstik -$(TARGET).LDSCRIPT=$(SRC_ARCH)/navstik.ld - -# ----------------------------------------------------------------------- - -# default flash mode is via usb dfu bootloader -# other possibilities: DFU-UTIL, JTAG -FLASH_MODE ?= JTAG - -# -# default LED configuration -# -RADIO_CONTROL_LED ?= none -BARO_LED ?= none -AHRS_ALIGNER_LED ?= 2 -GPS_LED ?= none -SYS_TIME_LED ?= 1 - -# -# default uart configuration -# -RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART6 - -MODEM_PORT ?= UART5 -MODEM_BAUD ?= B57600 - -GPS_PORT ?= UART2 -GPS_BAUD ?= B57600 - -# -# default actuator configuration -# -# you can use different actuators by adding a configure option to your firmware section -# e.g. -# -ACTUATORS ?= actuators_pwm diff --git a/conf/boards/nucleo144_f767zi.makefile b/conf/boards/nucleo144_f767zi.makefile index 21acec3848..1e95e43456 100644 --- a/conf/boards/nucleo144_f767zi.makefile +++ b/conf/boards/nucleo144_f767zi.makefile @@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16 USE_LTO=yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options @@ -33,7 +33,6 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk diff --git a/conf/boards/px4fmu_2.4_chibios.makefile b/conf/boards/px4fmu_2.4_chibios.makefile index f18d48d02d..217b0799e0 100644 --- a/conf/boards/px4fmu_2.4_chibios.makefile +++ b/conf/boards/px4fmu_2.4_chibios.makefile @@ -19,7 +19,7 @@ RTOS=chibios # FPU on F4 USE_FPU=hard -$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options @@ -32,14 +32,6 @@ CHIBIOS_BOARD_PLATFORM = STM32F4xx/platform.mk CHIBIOS_BOARD_LINKER = STM32F407xG.ld CHIBIOS_BOARD_STARTUP = startup_stm32f4xx.mk -# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order -# to correctly initialize the interrupt vector we have to define that -# the board has LUFTBOOT -HAS_LUFTBOOT ?= 1 -ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE)) -$(TARGET).CFLAGS+=-DLUFTBOOT -endif - ############################################################################## # Compiler settings # diff --git a/conf/boards/px4fmu_4.0_chibios.makefile b/conf/boards/px4fmu_4.0_chibios.makefile index 04d2eb1166..72d372f67c 100644 --- a/conf/boards/px4fmu_4.0_chibios.makefile +++ b/conf/boards/px4fmu_4.0_chibios.makefile @@ -15,11 +15,12 @@ ARCH=chibios $(TARGET).ARCHDIR = $(ARCH) RTOS=chibios +MCU=cortex-m4 # FPU on F4 USE_FPU=hard -$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options @@ -29,21 +30,13 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F4xx/platform.mk +CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/ CHIBIOS_BOARD_LINKER = STM32F427xT.ld CHIBIOS_BOARD_STARTUP = startup_stm32f4xx.mk -# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order -# to correctly initialize the interrupt vector we have to define that -# the board has LUFTBOOT -HAS_LUFTBOOT ?= 1 -ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE)) -$(TARGET).CFLAGS+=-DLUFTBOOT -endif - ############################################################################## # Compiler settings # -MCU = cortex-m4 # default flash mode is the PX4 bootloader # possibilities: DFU, SWD, PX4 bootloader diff --git a/conf/boards/px4fmu_5.0_chibios.makefile b/conf/boards/px4fmu_5.0_chibios.makefile index 037679d938..28d55f41cf 100644 --- a/conf/boards/px4fmu_5.0_chibios.makefile +++ b/conf/boards/px4fmu_5.0_chibios.makefile @@ -9,7 +9,7 @@ BOARD=px4fmu BOARD_VERSION=5.0 BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION) -BOARD_CFG=\"boards/$(BOARD_DIR)/$(BOARD).h\" +BOARD_CFG=\"arch/chibios/common_board.h\" ARCH=chibios $(TARGET).ARCHDIR = $(ARCH) @@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16 #USE_LTO=yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD ############################################################################## # Architecture or project specific options @@ -33,30 +33,10 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk +CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/ CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk -# ITCM flash is a special flash that allow faster operations -# At the moment it is not possible to flash the code in this mode using dfu-util -# but it should work with the BlackMagicProbe or STLINK -# By default, normal flash is used -ifeq ($(USE_ITCM),1) -$(TARGET).CFLAGS += -DUSE_ITCM=1 -DFU_ADDR = 0x00200000 -else -$(TARGET).CFLAGS += -DUSE_ITCM=0 -DFU_ADDR = 0x08000000 -endif - -# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order -# to correctly initialize the interrupt vector we have to define that -# the board has LUFTBOOT -HAS_LUFTBOOT ?= 1 -ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE)) -$(TARGET).CFLAGS+=-DLUFTBOOT -endif - ############################################################################## # Compiler settings # diff --git a/conf/boards/tawaki_common.makefile b/conf/boards/tawaki_common.makefile index e0a6842c81..23df7d2ef9 100644 --- a/conf/boards/tawaki_common.makefile +++ b/conf/boards/tawaki_common.makefile @@ -22,7 +22,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16 USE_LTO ?= yes -$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U +$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U ############################################################################## # Architecture or project specific options @@ -32,7 +32,6 @@ PROJECT = $(TARGET) # Project specific files and paths (see Makefile.chibios for details) CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk -CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk CHIBIOS_BOARD_LINKER = STM32F76xxI.ld CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk diff --git a/conf/conf_example.xml b/conf/conf_example.xml index 29450fb7fd..e2349f169d 100644 --- a/conf/conf_example.xml +++ b/conf/conf_example.xml @@ -7,7 +7,7 @@ telemetry="telemetry/default_fixedwing_imu.xml" flight_plan="flight_plans/versatile.xml" settings="settings/fixedwing_basic.xml settings/nps.xml" - settings_modules="modules/nav_basic_fw.xml modules/gps.xml modules/ahrs_float_dcm.xml modules/imu_common.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml" + settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml" gui_color="blue" /> - diff --git a/conf/conf_tests.xml b/conf/conf_tests.xml index db706d5d80..e9aba727ad 100644 --- a/conf/conf_tests.xml +++ b/conf/conf_tests.xml @@ -1,4 +1,15 @@ + - - + + diff --git a/conf/conf_tests_coverity.xml b/conf/conf_tests_coverity.xml index c2282b2b8f..d26ff838ae 100644 --- a/conf/conf_tests_coverity.xml +++ b/conf/conf_tests_coverity.xml @@ -7,7 +7,7 @@ telemetry="telemetry/default_rotorcraft.xml" flight_plan="flight_plans/rotorcraft_basic_geofence.xml" settings="settings/rotorcraft_basic.xml settings/nps.xml" - settings_modules="modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml" + settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml" gui_color="#ffff954c0000" /> - diff --git a/conf/firmwares/baro_board.makefile b/conf/firmwares/baro_board.makefile index e5017b795c..08b1c9eb4c 100644 --- a/conf/firmwares/baro_board.makefile +++ b/conf/firmwares/baro_board.makefile @@ -14,13 +14,6 @@ ifeq ($(BOARD), lisa_l) BARO_BOARD_CFLAGS += -DUSE_I2C2 BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c -# Navstik baro -else ifeq ($(BOARD), navstik) - BARO_BOARD_CFLAGS += -DUSE_I2C3 - BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_BOARD_BMP085 - BARO_BOARD_SRCS += peripherals/bmp085.c - BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c - # Ardrone baro else ifeq ($(BOARD), ardrone) BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c diff --git a/conf/firmwares/test_progs.makefile b/conf/firmwares/test_progs.makefile index e2363d6df1..55ebd8ed54 100644 --- a/conf/firmwares/test_progs.makefile +++ b/conf/firmwares/test_progs.makefile @@ -124,9 +124,6 @@ ifeq ($(BOARD_VERSION), 2.0) LED_DEFINES = -DLED_BLUE=3 -DLED_RED=4 -DLED_GREEN=5 endif endif -ifeq ($(BOARD), navstik) -LED_DEFINES = -DLED_RED=1 -DLED_GREEN=2 -endif ifeq ($(BOARD), cc3d) LED_DEFINES = -DLED_BLUE=1 endif diff --git a/conf/flash_modes.xml b/conf/flash_modes.xml index 7d05bbee6a..9db203b84c 100644 --- a/conf/flash_modes.xml +++ b/conf/flash_modes.xml @@ -27,7 +27,6 @@ - @@ -77,6 +76,7 @@ + @@ -103,6 +103,7 @@ + @@ -110,7 +111,6 @@ - diff --git a/conf/modules/baro_board.xml b/conf/modules/baro_board.xml index 356e2e9282..725fb6c7fa 100644 --- a/conf/modules/baro_board.xml +++ b/conf/modules/baro_board.xml @@ -17,16 +17,8 @@ ifeq ($(USE_BARO_BOARD), TRUE) -# Navstik baro -ifeq ($(BOARD), navstik) - BARO_BOARD_CFLAGS += -DUSE_I2C3 - BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_BOARD_BMP085 - BARO_BOARD_SRCS += peripherals/bmp085.c - BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c - - # Lisa/M baro -else ifeq ($(BOARD), lisa_m) +ifeq ($(BOARD), lisa_m) ifeq ($(BOARD_VERSION), 1.0) # on lisa_m_1.0: defaults to i2c baro bmp085 on the board LISA_M_BARO ?= BARO_BOARD_BMP085 diff --git a/conf/modules/boards/cube_orange.xml b/conf/modules/boards/cube_orange.xml new file mode 100644 index 0000000000..8489231c2a --- /dev/null +++ b/conf/modules/boards/cube_orange.xml @@ -0,0 +1,17 @@ + + + + + + Specific configuration for Cube Orange with ChibiOS + + + + spi_master,baro_ms5611_spi + + + + + + + diff --git a/conf/modules/boards/navstik_1.0.xml b/conf/modules/boards/navstik_1.0.xml deleted file mode 100644 index ed4a8bd1a3..0000000000 --- a/conf/modules/boards/navstik_1.0.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - Specific configuration for Navstik 1.0 - - - - i2c,baro_board - - - - diff --git a/conf/modules/boards/px4fmu_5.0_chibios.xml b/conf/modules/boards/px4fmu_5.0_chibios.xml index ee94d958bc..aae15232d8 100644 --- a/conf/modules/boards/px4fmu_5.0_chibios.xml +++ b/conf/modules/boards/px4fmu_5.0_chibios.xml @@ -9,6 +9,8 @@ spi_master,baro_board - + + + diff --git a/conf/modules/imu_navstik.xml b/conf/modules/imu_navstik.xml deleted file mode 100644 index 4eac80f78d..0000000000 --- a/conf/modules/imu_navstik.xml +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - Navstik IMU: MPU60x0 and HMC5883 via I2C. - - - -
- - - - - - - -
-
- - i2c,imu_common - imu,mag - - - -
- -
- - - - - - - - - - - - - - - - - - -
diff --git a/conf/userconf/tudelft/conf.xml b/conf/userconf/tudelft/conf.xml index 509f9defb7..2657e4f9cd 100644 --- a/conf/userconf/tudelft/conf.xml +++ b/conf/userconf/tudelft/conf.xml @@ -300,7 +300,7 @@ NOCACHE_RAM + + /* Special section for Ethernet DMA non cache-able areas.*/ + .eth (NOLOAD) : ALIGN(4) + { + __eth_base__ = .; + *(.eth) + *(.eth.*) + *(.bss.__eth_*) + . = ALIGN(4); + __eth_end__ = .; + } > ETH_RAM +} + +/* Code rules inclusion.*/ +INCLUDE rules_code.ld + +/* Data rules inclusion.*/ +INCLUDE rules_data.ld + +/* Memory rules inclusion.*/ +INCLUDE rules_memory.ld + diff --git a/sw/airborne/boards/holybro/kakute_f7/board.c b/sw/airborne/arch/chibios/board.c similarity index 71% rename from sw/airborne/boards/holybro/kakute_f7/board.c rename to sw/airborne/arch/chibios/board.c index 1e9139007f..b2350b7eb7 100644 --- a/sw/airborne/boards/holybro/kakute_f7/board.c +++ b/sw/airborne/arch/chibios/board.c @@ -34,6 +34,21 @@ /* Driver local variables and types. */ /*===========================================================================*/ +#if defined(STM32F1XX) + +/** + * @brief STM32 GPIO static initialization data. + */ +const PALConfig pal_default_config = { + {VAL_GPIOA_ODR, VAL_GPIOA_CRL, VAL_GPIOA_CRH}, + {VAL_GPIOB_ODR, VAL_GPIOB_CRL, VAL_GPIOB_CRH}, + {VAL_GPIOC_ODR, VAL_GPIOC_CRL, VAL_GPIOC_CRH}, + {VAL_GPIOD_ODR, VAL_GPIOD_CRL, VAL_GPIOD_CRH}, + {VAL_GPIOE_ODR, VAL_GPIOE_CRL, VAL_GPIOE_CRH}, +}; + +#else /* STM32F1XX */ + /** * @brief Type of STM32 GPIO port setup. */ @@ -91,48 +106,70 @@ typedef struct { */ static const gpio_config_t gpio_default_config = { #if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, + { + VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, + VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH + }, #endif #if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, + { + VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, + VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH + }, #endif #if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, + { + VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, + VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH + }, #endif #if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, + { + VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, + VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH + }, #endif #if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, + { + VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, + VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH + }, #endif #if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, + { + VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, + VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH + }, #endif #if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, + { + VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, + VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH + }, #endif #if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, + { + VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, + VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH + }, #endif #if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, + { + VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, + VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH + }, #endif #if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, + { + VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, + VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH + }, #endif #if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} + { + VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, + VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH + } #endif }; @@ -140,7 +177,8 @@ static const gpio_config_t gpio_default_config = { /* Driver local functions. */ /*===========================================================================*/ -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { +static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) +{ gpiop->OTYPER = config->otyper; gpiop->OSPEEDR = config->ospeedr; @@ -151,12 +189,21 @@ static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { gpiop->MODER = config->moder; } -static void stm32_gpio_init(void) { +static void stm32_gpio_init(void) +{ /* Enabling GPIO-related clocks, the mask comes from the registry header file.*/ +#if defined(STM32H7XX) + rccResetAHB4(STM32_GPIO_EN_MASK); + rccEnableAHB4(STM32_GPIO_EN_MASK, true); +#elif defined(STM32F3XX) + rccResetAHB(STM32_GPIO_EN_MASK); + rccEnableAHB(STM32_GPIO_EN_MASK, true); +#else rccResetAHB1(STM32_GPIO_EN_MASK); rccEnableAHB1(STM32_GPIO_EN_MASK, true); +#endif /* Initializing all the defined GPIO ports.*/ #if STM32_HAS_GPIOA @@ -194,6 +241,8 @@ static void stm32_gpio_init(void) { #endif } +#endif /* not STM32F1XX */ + /*===========================================================================*/ /* Driver interrupt handlers. */ /*===========================================================================*/ @@ -207,8 +256,8 @@ static void stm32_gpio_init(void) { * @details GPIO ports and system clocks are initialized before everything * else. */ -void __early_init(void) { - +void __early_init(void) +{ stm32_gpio_init(); stm32_clock_init(); } @@ -217,18 +266,17 @@ void __early_init(void) { /** * @brief SDC card detection. */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { +bool sdc_lld_is_card_inserted(SDCDriver *sdcp) +{ (void)sdcp; - /* assume card is inserted as there is no SD_DETECT pin - * actual detection will be done by the software - */ return true; } /** * @brief SDC card write protection detection. */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { +bool sdc_lld_is_write_protected(SDCDriver *sdcp) +{ (void)sdcp; return false; @@ -239,7 +287,8 @@ bool sdc_lld_is_write_protected(SDCDriver *sdcp) { /** * @brief MMC_SPI card detection. */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { +bool mmc_lld_is_card_inserted(MMCDriver *mmcp) +{ (void)mmcp; /* TODO: Fill the implementation.*/ @@ -249,7 +298,8 @@ bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { /** * @brief MMC_SPI card write protection detection. */ -bool mmc_lld_is_write_protected(MMCDriver *mmcp) { +bool mmc_lld_is_write_protected(MMCDriver *mmcp) +{ (void)mmcp; /* TODO: Fill the implementation.*/ @@ -261,17 +311,9 @@ bool mmc_lld_is_write_protected(MMCDriver *mmcp) { * @brief Board-specific initialization code. * @todo Add your board-specific code, if any. */ -void boardInit(void) { - -} - -/** Energy saving procedure for SD log closing - */ -void mcu_periph_energy_save(void) +void boardInit(void) { - palSetLineMode(LINE_LED1, PAL_MODE_INPUT); - palSetLineMode(LINE_OSD_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_IMU_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_SDCARD_CS, PAL_MODE_INPUT); +#if defined(AFIO_MAPR_VAL) + AFIO->MAPR |= AFIO_MAPR_VAL; +#endif } - diff --git a/sw/airborne/arch/chibios/chconf.h b/sw/airborne/arch/chibios/chconf.h index 6f2403f8e7..d115fd8382 100644 --- a/sw/airborne/arch/chibios/chconf.h +++ b/sw/airborne/arch/chibios/chconf.h @@ -1,5 +1,5 @@ /* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio + ChibiOS - Copyright (C) 2006..2020 Giovanni Di Sirio Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. @@ -29,7 +29,27 @@ #define CHCONF_H #define _CHIBIOS_RT_CONF_ -#define _CHIBIOS_RT_CONF_VER_6_1_ +#define _CHIBIOS_RT_CONF_VER_7_0_ + +/*===========================================================================*/ +/** + * @name System settings + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Handling of instances. + * @note If enabled then threads assigned to various instances can + * interact each other using the same synchronization objects. + * If disabled then each OS instance is a separate world, no + * direct interactions are handled by the OS. + */ +#if !defined(CH_CFG_SMP_MODE) +#define CH_CFG_SMP_MODE FALSE +#endif + +/** @} */ /*===========================================================================*/ /** @@ -119,6 +139,19 @@ #define CH_CFG_NO_IDLE_THREAD FALSE #endif +/** + * @brief Kernel hardening level. + * @details This option is the level of functional-safety checks enabled + * in the kerkel. The meaning is: + * - 0: No checks, maximum performance. + * - 1: Reasonable checks. + * - 2: All checks. + * . + */ +#if !defined(CH_CFG_HARDENING_LEVEL) +#define CH_CFG_HARDENING_LEVEL 0 +#endif + /** @} */ /*===========================================================================*/ @@ -160,6 +193,16 @@ #define CH_CFG_USE_TM TRUE #endif +/** + * @brief Time Stamps APIs. + * @details If enabled then the time stamps APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_CFG_USE_TIMESTAMP) +#define CH_CFG_USE_TIMESTAMP TRUE +#endif + /** * @brief Threads registry APIs. * @details If enabled then the registry APIs are included in the kernel. @@ -330,6 +373,16 @@ #define CH_CFG_USE_MAILBOXES TRUE #endif +/** + * @brief Memory checks APIs. + * @details If enabled then the memory checks APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_CFG_USE_MEMCHECKS) +#define CH_CFG_USE_MEMCHECKS TRUE +#endif + /** * @brief Core Memory Manager APIs. * @details If enabled then the core memory manager APIs are included @@ -631,7 +684,7 @@ * @details User fields added to the end of the @p ch_system_t structure. */ #define CH_CFG_SYSTEM_EXTRA_FIELDS \ - /* Add threads custom fields here.*/ + /* Add system custom fields here.*/ /** * @brief System initialization hook. @@ -639,7 +692,23 @@ * just before interrupts are enabled globally. */ #define CH_CFG_SYSTEM_INIT_HOOK() { \ - /* Add threads initialization code here.*/ \ + /* Add system initialization code here.*/ \ +} + +/** + * @brief OS instance structure extension. + * @details User fields added to the end of the @p os_instance_t structure. + */ +#define CH_CFG_OS_INSTANCE_EXTRA_FIELDS \ + /* Add OS instance custom fields here.*/ + +/** + * @brief OS instance initialization hook. + * + * @param[in] oip pointer to the @p os_instance_t structure + */ +#define CH_CFG_OS_INSTANCE_INIT_HOOK(oip) { \ + /* Add OS instance initialization code here.*/ \ } /** @@ -655,6 +724,8 @@ * * @note It is invoked from within @p _thread_init() and implicitly from all * the threads creation APIs. + * + * @param[in] tp pointer to the @p thread_t structure */ #define CH_CFG_THREAD_INIT_HOOK(tp) { \ /* Add threads initialization code here.*/ \ @@ -663,6 +734,8 @@ /** * @brief Threads finalization hook. * @details User finalization code added to the @p chThdExit() API. + * + * @param[in] tp pointer to the @p thread_t structure */ #define CH_CFG_THREAD_EXIT_HOOK(tp) { \ /* Add threads finalization code here.*/ \ @@ -671,6 +744,9 @@ /** * @brief Context switch hook. * @details This hook is invoked just before switching between threads. + * + * @param[in] ntp thread being switched in + * @param[in] otp thread being switched out */ #define CH_CFG_CONTEXT_SWITCH_HOOK(ntp, otp) { \ /* Context switch code here.*/ \ @@ -745,31 +821,20 @@ /* Trace code here.*/ \ } -/** @} */ +/** + * @brief Runtime Faults Collection Unit hook. + * @details This hook is invoked each time new faults are collected and stored. + */ +#define CH_CFG_RUNTIME_FAULTS_HOOK(mask) { \ + /* Faults handling code here.*/ \ +} +/** @} */ /*===========================================================================*/ /* Port-specific settings (override port settings defaulted in chcore.h). */ /*===========================================================================*/ - - -#ifndef CORTEX_VTOR_INIT // try to find the correct init address if not defined - -#if LUFTBOOT // using LUFTBOOT bootloader - -#if defined(STM32F4) -#define CORTEX_VTOR_INIT 0x00004000U -#elif defined(STM32F7) -#define CORTEX_VTOR_INIT 0x08008000U -#else -#define CORTEX_VTOR_INIT 0x00002000U -#endif - -#endif // LUFTBOOT - -#endif // CORTEX_VTOR_INIT - // allow float for the ChibiOS print function (used with logger) #define CHPRINTF_USE_FLOAT 1 diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/px4fmu.h b/sw/airborne/arch/chibios/common_board.h similarity index 79% rename from sw/airborne/boards/px4fmu/chibios/v5.0/px4fmu.h rename to sw/airborne/arch/chibios/common_board.h index 7debb963f8..4e74e20606 100644 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/px4fmu.h +++ b/sw/airborne/arch/chibios/common_board.h @@ -1,21 +1,41 @@ -#ifndef CONFIG_PX4FMU_5_00_H -#define CONFIG_PX4FMU_5_00_H - -#define BOARD_PX4FMU +/* + * Copyright (C) 2022 Freek van Tienen + * + * 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. + * + */ /** - * ChibiOS board file + * @file arch/chibios/common_board.h + * @brief Generic board file */ -#include "boards/px4fmu/chibios/v5.0/board.h" - +#ifndef ARCH_COMMON_BOARD_H +#define ARCH_COMMON_BOARD_H /** - * PPRZ definitions + * ChibiOS board file generated by the cfg file */ +#include "board.h" /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* * LEDs @@ -28,7 +48,6 @@ #define LED_1_GPIO_PIN PAL_PAD(LINE_LED1) #define LED_1_GPIO_ON gpio_clear #define LED_1_GPIO_OFF gpio_set -#define LED_1_AFIO_REMAP ((void)0) #endif #if defined(LINE_LED2) @@ -39,7 +58,6 @@ #define LED_2_GPIO_PIN PAL_PAD(LINE_LED2) #define LED_2_GPIO_ON gpio_clear #define LED_2_GPIO_OFF gpio_set -#define LED_2_AFIO_REMAP ((void)0) #endif #if defined(LINE_LED3) @@ -50,7 +68,6 @@ #define LED_3_GPIO_PIN PAL_PAD(LINE_LED3) #define LED_3_GPIO_ON gpio_clear #define LED_3_GPIO_OFF gpio_set -#define LED_3_AFIO_REMAP ((void)0) #endif #if defined(LINE_LED4) @@ -61,7 +78,6 @@ #define LED_4_GPIO_PIN PAL_PAD(LINE_LED4) #define LED_4_GPIO_ON gpio_clear #define LED_4_GPIO_OFF gpio_set -#define LED_4_AFIO_REMAP ((void)0) #endif /* @@ -72,7 +88,11 @@ #define USE_ADC_1 1 #endif #if USE_ADC_1 -#define AD1_1_CHANNEL ADC_CHANNEL_IN0 +#if defined(ADC1_ADC_IN) +#define AD1_1_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC1_ADC_IN) +#elif defined(ADC1_ADC_INP) +#define AD1_1_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC1_ADC_INP) +#endif #define ADC_1 AD1_1 #define ADC_1_GPIO_PORT PAL_PORT(LINE_ADC1) #define ADC_1_GPIO_PIN PAL_PAD(LINE_ADC1) @@ -84,7 +104,11 @@ #define USE_ADC_2 1 #endif #if USE_ADC_2 -#define AD1_2_CHANNEL ADC_CHANNEL_IN1 +#if defined(ADC2_ADC_IN) +#define AD1_2_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC2_ADC_IN) +#elif defined(ADC2_ADC_INP) +#define AD1_2_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC2_ADC_INP) +#endif #define ADC_2 AD1_2 #define ADC_2_GPIO_PORT PAL_PORT(LINE_ADC2) #define ADC_2_GPIO_PIN PAL_PAD(LINE_ADC2) @@ -96,7 +120,11 @@ #define USE_ADC_3 1 #endif #if USE_ADC_3 -#define AD1_3_CHANNEL ADC_CHANNEL_IN2 +#if defined(ADC3_ADC_IN) +#define AD1_3_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC3_ADC_IN) +#elif defined(ADC3_ADC_INP) +#define AD1_3_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC3_ADC_INP) +#endif #define ADC_3 AD1_3 #define ADC_3_GPIO_PORT PAL_PORT(LINE_ADC3) #define ADC_3_GPIO_PIN PAL_PAD(LINE_ADC3) @@ -108,7 +136,11 @@ #define USE_ADC_4 1 #endif #if USE_ADC_4 -#define AD1_4_CHANNEL ADC_CHANNEL_IN3 +#if defined(ADC4_ADC_IN) +#define AD1_4_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC4_ADC_IN) +#elif defined(ADC4_ADC_INP) +#define AD1_4_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC4_ADC_INP) +#endif #define ADC_4 AD1_4 #define ADC_4_GPIO_PORT PAL_PORT(LINE_ADC4) #define ADC_4_GPIO_PIN PAL_PAD(LINE_ADC4) @@ -116,8 +148,15 @@ #endif #if defined(LINE_ADC5) +#ifndef USE_ADC_5 +#define USE_ADC_5 1 +#endif #if USE_ADC_5 -#define AD1_5_CHANNEL ADC_CHANNEL_IN4 +#if defined(ADC5_ADC_IN) +#define AD1_5_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC5_ADC_IN) +#elif defined(ADC5_ADC_INP) +#define AD1_5_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC5_ADC_INP) +#endif #define ADC_5 AD1_5 #define ADC_5_GPIO_PORT PAL_PORT(LINE_ADC5) #define ADC_5_GPIO_PIN PAL_PAD(LINE_ADC5) @@ -126,29 +165,19 @@ #if defined(LINE_ADC6) #if USE_ADC_6 -#define AD1_6_CHANNEL ADC_CHANNEL_IN14 +#if defined(ADC6_ADC_IN) +#define AD1_6_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC6_ADC_IN) +#elif defined(ADC6_ADC_INP) +#define AD1_6_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC6_ADC_INP) +#endif #define ADC_6 AD1_6 #define ADC_6_GPIO_PORT PAL_PORT(LINE_ADC6) #define ADC_6_GPIO_PIN PAL_PAD(LINE_ADC6) #endif #endif -/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ -#ifndef ADC_CHANNEL_VSUPPLY -#define ADC_CHANNEL_VSUPPLY ADC_1 -#endif - -/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/ -#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE -#define ADC_CHANNEL_CURRENT ADC_2 -#endif - -/* Default powerbrick values */ -#define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 10.3208191126f * adc) -#define MilliAmpereOfAdc(adc) ((3.3f/4096.0f) * 24000.0f * adc) - /* - * PWM defines (TODO DRIVER and CHANNEL) + * PWM defines */ #if defined(LINE_SERVO1) #ifndef USE_PWM1 @@ -159,11 +188,9 @@ #define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1) #define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1) #define PWM_SERVO_1_AF AF_LINE_SERVO1 -#define PWM_SERVO_1_DRIVER PWMD1 -#define PWM_SERVO_1_CHANNEL 4-1 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM) +#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1) +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM) #endif #endif @@ -176,11 +203,9 @@ #define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2) #define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2) #define PWM_SERVO_2_AF AF_LINE_SERVO2 -#define PWM_SERVO_2_DRIVER PWMD1 -#define PWM_SERVO_2_CHANNEL 3-1 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM) +#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1) +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM) #endif #endif @@ -193,11 +218,9 @@ #define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3) #define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3) #define PWM_SERVO_3_AF AF_LINE_SERVO3 -#define PWM_SERVO_3_DRIVER PWMD1 -#define PWM_SERVO_3_CHANNEL 2-1 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM) +#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1) +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM) #endif #endif @@ -210,11 +233,9 @@ #define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4) #define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4) #define PWM_SERVO_4_AF AF_LINE_SERVO4 -#define PWM_SERVO_4_DRIVER PWMD1 -#define PWM_SERVO_4_CHANNEL 1-1 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM) +#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1) +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM) #endif #endif @@ -227,11 +248,9 @@ #define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5) #define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5) #define PWM_SERVO_5_AF AF_LINE_SERVO5 -#define PWM_SERVO_5_DRIVER PWMD4 -#define PWM_SERVO_5_CHANNEL 2-1 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM) +#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1) +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM) #endif #endif @@ -244,11 +263,9 @@ #define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6) #define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6) #define PWM_SERVO_6_AF AF_LINE_SERVO6 -#define PWM_SERVO_6_DRIVER PWMD4 -#define PWM_SERVO_6_CHANNEL 3-1 -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM) +#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1) +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM) #endif #endif @@ -261,11 +278,9 @@ #define PWM_SERVO_7_GPIO PAL_PORT(LINE_SERVO7) #define PWM_SERVO_7_PIN PAL_PAD(LINE_SERVO7) #define PWM_SERVO_7_AF AF_LINE_SERVO7 -#define PWM_SERVO_7_DRIVER PWMD12 -#define PWM_SERVO_7_CHANNEL 1-1 -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO7_TIM) +#define PWM_SERVO_7_CHANNEL (SERVO7_TIM_CH-1) +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO7_TIM) #endif #endif @@ -278,80 +293,12 @@ #define PWM_SERVO_8_GPIO PAL_PORT(LINE_SERVO8) #define PWM_SERVO_8_PIN PAL_PAD(LINE_SERVO8) #define PWM_SERVO_8_AF AF_LINE_SERVO8 -#define PWM_SERVO_8_DRIVER PWMD12 -#define PWM_SERVO_8_CHANNEL 2-1 -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO8_TIM) +#define PWM_SERVO_8_CHANNEL (SERVO8_TIM_CH-1) +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO8_TIM) #endif #endif - -#ifdef STM32_PWM_USE_TIM1 -#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1 -#else -#define PWM_CONF_TIM1 1 -#endif -#define PWM_CONF1_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM1_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 -#endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM12 -#define PWM_CONF_TIM12 STM32_PWM_USE_TIM12 -#else -#define PWM_CONF_TIM12 1 -#endif -#define PWM_CONF12_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM12_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_7_ACTIVE, NULL }, \ - { PWM_SERVO_8_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -/** - * PPM radio defines - */ -#define RC_PPM_TICKS_PER_USEC 2 -#define PPM_TIMER_FREQUENCY 2000000 -#define PPM_CHANNEL ICU_CHANNEL_1 -#define PPM_TIMER ICUD8 - /** * UART defines */ @@ -483,9 +430,6 @@ #define UART8_GPIO_AF ((void)0) #endif -/** - * I2C defines - */ /** * I2C defines */ @@ -700,14 +644,14 @@ #define SPI_SELECT_SLAVE6_PIN PAL_PAD(LINE_SPI_SLAVE6) #endif -/** - * Baro - * - * Apparently needed for backwards compatibility - * with the ancient onboard baro boards - */ -#ifndef USE_BARO_BOARD -#define USE_BARO_BOARD 1 +#if defined(LINE_SPI_SLAVE7) +#define SPI_SELECT_SLAVE7_PORT PAL_PORT(LINE_SPI_SLAVE7) +#define SPI_SELECT_SLAVE7_PIN PAL_PAD(LINE_SPI_SLAVE7) +#endif + +#if defined(LINE_SPI_SLAVE8) +#define SPI_SELECT_SLAVE8_PORT PAL_PORT(LINE_SPI_SLAVE8) +#define SPI_SELECT_SLAVE8_PIN PAL_PAD(LINE_SPI_SLAVE8) #endif /** @@ -737,16 +681,9 @@ #if defined(LINE_USB_VBUS) #define SDLOG_USB_VBUS_PORT PAL_PORT(LINE_USB_VBUS) #define SDLOG_USB_VBUS_PIN PAL_PAD(LINE_USB_VBUS) -#define SDLOG_USB_VBUS_BOOT true +#define SDLOG_USB_VBUS_BOOT false #endif -// bat monitoring for file closing -#define SDLOG_BAT_ADC ADCD1 -#define SDLOG_BAT_CHAN AD1_1_CHANNEL -// usb led status -#define SDLOG_USB_LED 3 - - /* * Actuators for fixedwing */ @@ -756,5 +693,4 @@ #define ActuatorsDefaultInit() ActuatorsPwmInit() #define ActuatorsDefaultCommit() ActuatorsPwmCommit() -#endif /* CONFIG_PX4FMU_4_00_H */ - +#endif /* ARCH_COMMON_BOARD_H */ diff --git a/sw/airborne/arch/chibios/ffconf.h b/sw/airborne/arch/chibios/ffconf.h index e5664c5c2b..fa9e633932 100644 --- a/sw/airborne/arch/chibios/ffconf.h +++ b/sw/airborne/arch/chibios/ffconf.h @@ -1,11 +1,12 @@ /* CHIBIOS FIX */ #include "ch.h" +#define FATFS_CHIBIOS_EXTENSIONS /*---------------------------------------------------------------------------/ -/ FatFs - FAT file system module configuration file +/ FatFs Functional Configurations /---------------------------------------------------------------------------*/ -#define FFCONF_DEF 86606 /* Revision ID */ +#define FFCONF_DEF 86631 /* Revision ID */ /*---------------------------------------------------------------------------/ / Function Configurations @@ -28,55 +29,69 @@ / 3: f_lseek() function is removed in addition to 2. */ -#define FF_USE_STRFUNC 0 -/* This option switches string functions, f_gets(), f_putc(), f_puts() and -/ f_printf(). -/ -/ 0: Disable string functions. -/ 1: Enable without LF-CRLF conversion. -/ 2: Enable with LF-CRLF conversion. */ - - -#define FF_USE_FIND 1 +#define FF_USE_FIND 1 /* This option switches filtered directory read functions, f_findfirst() and / f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */ -#define FF_USE_MKFS 1 +#define FF_USE_MKFS 1 /* This option switches f_mkfs() function. (0:Disable or 1:Enable) */ -#define FF_USE_FASTSEEK 1 +#define FF_USE_FASTSEEK 1 /* This option switches fast seek function. (0:Disable or 1:Enable) */ -#define FF_USE_EXPAND 1 +#define FF_USE_EXPAND 1 /* This option switches f_expand function. (0:Disable or 1:Enable) */ -#define FF_USE_CHMOD 1 +#define FF_USE_CHMOD 1 /* This option switches attribute manipulation functions, f_chmod() and f_utime(). / (0:Disable or 1:Enable) Also FF_FS_READONLY needs to be 0 to enable this option. */ -#define FF_USE_LABEL 1 +#define FF_USE_LABEL 1 /* This option switches volume label functions, f_getlabel() and f_setlabel(). / (0:Disable or 1:Enable) */ -#define FF_USE_FORWARD 1 +#define FF_USE_FORWARD 1 /* This option switches f_forward() function. (0:Disable or 1:Enable) */ +#define FF_USE_STRFUNC 0 +#define FF_PRINT_LLI 0 +#define FF_PRINT_FLOAT 0 +#define FF_STRF_ENCODE 0 +/* FF_USE_STRFUNC switches string functions, f_gets(), f_putc(), f_puts() and +/ f_printf(). +/ +/ 0: Disable. FF_PRINT_LLI, FF_PRINT_FLOAT and FF_STRF_ENCODE have no effect. +/ 1: Enable without LF-CRLF conversion. +/ 2: Enable with LF-CRLF conversion. +/ +/ FF_PRINT_LLI = 1 makes f_printf() support long long argument and FF_PRINT_FLOAT = 1/2 + makes f_printf() support floating point argument. These features want C99 or later. +/ When FF_LFN_UNICODE >= 1 with LFN enabled, string functions convert the character +/ encoding in it. FF_STRF_ENCODE selects assumption of character encoding ON THE FILE +/ to be read/written via those functions. +/ +/ 0: ANSI/OEM in current CP +/ 1: Unicode in UTF-16LE +/ 2: Unicode in UTF-16BE +/ 3: Unicode in UTF-8 +*/ + + /*---------------------------------------------------------------------------/ / Locale and Namespace Configurations /---------------------------------------------------------------------------*/ -#define FF_CODE_PAGE 850 +#define FF_CODE_PAGE 850 /* This option specifies the OEM code page to be used on the target system. -/ Incorrect setting of the code page can cause a file open failure. +/ Incorrect code page setting can cause a file open failure. / -/ 1 - ASCII (No extended character. Non-LFN cfg. only) / 437 - U.S. / 720 - Arabic / 737 - Greek @@ -98,31 +113,40 @@ / 936 - Simplified Chinese (DBCS) / 949 - Korean (DBCS) / 950 - Traditional Chinese (DBCS) +/ 0 - Include all code pages above and configured by f_setcp() */ -#define FF_USE_LFN 2 -#define FF_MAX_LFN 255 -/* The FF_USE_LFN switches the support of long file name (LFN). +#define FF_USE_LFN 2 +#define FF_MAX_LFN 255 +/* The FF_USE_LFN switches the support for LFN (long file name). / -/ 0: Disable support of LFN. _MAX_LFN has no effect. -/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe. +/ 0: Disable LFN. FF_MAX_LFN has no effect. +/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe. / 2: Enable LFN with dynamic working buffer on the STACK. / 3: Enable LFN with dynamic working buffer on the HEAP. / -/ To enable the LFN, Unicode handling functions (option/unicode.c) must be added -/ to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and -/ additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255. -/ It should be set 255 to support full featured LFN operations. +/ To enable the LFN, ffunicode.c needs to be added to the project. The LFN function +/ requiers certain internal working buffer occupies (FF_MAX_LFN + 1) * 2 bytes and +/ additional (FF_MAX_LFN + 44) / 15 * 32 bytes when exFAT is enabled. +/ The FF_MAX_LFN defines size of the working buffer in UTF-16 code unit and it can +/ be in range of 12 to 255. It is recommended to be set it 255 to fully support LFN +/ specification. / When use stack for the working buffer, take care on stack overflow. When use heap / memory for the working buffer, memory management functions, ff_memalloc() and -/ ff_memfree(), must be added to the project. */ +/ ff_memfree() exemplified in ffsystem.c, need to be added to the project. */ -#define FF_LFN_UNICODE 0 -/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16) -/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1. -/ This option also affects behavior of string I/O functions. */ +#define FF_LFN_UNICODE 0 +/* This option switches the character encoding on the API when LFN is enabled. +/ +/ 0: ANSI/OEM in current CP (TCHAR = char) +/ 1: Unicode in UTF-16 (TCHAR = WCHAR) +/ 2: Unicode in UTF-8 (TCHAR = char) +/ 3: Unicode in UTF-32 (TCHAR = DWORD) +/ +/ Also behavior of string I/O functions will be affected by this option. +/ When LFN is not enabled, this option has no effect. */ #define FF_LFN_BUF 255 @@ -133,22 +157,8 @@ / on character encoding. When LFN is not enabled, these options have no effect. */ -#define FF_STRF_ENCODE 3 -/* When FF_LFN_UNICODE >= 1 with LFN enabled, string I/O functions, f_gets(), -/ f_putc(), f_puts and f_printf() convert the character encoding in it. -/ This option selects assumption of character encoding ON THE FILE to be -/ read/written via those functions. -/ -/ 0: ANSI/OEM -/ 1: UTF-16LE -/ 2: UTF-16BE -/ 3: UTF-8 -/ -/ This option has no effect when _LFN_UNICODE == 0. */ - - -#define FF_FS_RPATH 1 -/* This option configures support of relative path. +#define FF_FS_RPATH 1 +/* This option configures support for relative path. / / 0: Disable relative path and remove related functions. / 1: Enable relative path. f_chdir() and f_chdrive() are available. @@ -160,8 +170,8 @@ / Drive/Volume Configurations /---------------------------------------------------------------------------*/ -#define FF_VOLUMES 1 -/* Number of volumes (logical drives) to be used. */ +#define FF_VOLUMES 1 +/* Number of volumes (logical drives) to be used. (1-10) */ #define FF_STR_VOLUME_ID 0 @@ -191,7 +201,7 @@ #define FF_MAX_SS 512 /* This set of options configures the range of sector size to be supported. (512, / 1024, 2048 or 4096) Always set both 512 for most systems, generic memory card and -/ harddisk. But a larger value may be required for on-board flash memory and some +/ harddisk, but a larger value may be required for on-board flash memory and some / type of optical media. When FF_MAX_SS is larger than FF_MIN_SS, FatFs is configured / for variable sector size mode and disk_ioctl() function needs to implement / GET_SECTOR_SIZE command. */ @@ -203,7 +213,7 @@ #define FF_MIN_GPT 0x100000000 -/* Minimum number of sectors to switch GPT format to create partition in f_mkfs and +/* Minimum number of sectors to switch GPT as partitioning format in f_mkfs and / f_fdisk function. 0x100000000 max. This option has no effect when FF_LBA64 == 0. */ @@ -234,7 +244,7 @@ #define FF_FS_NORTC 0 #define FF_NORTC_MON 1 #define FF_NORTC_MDAY 1 -#define FF_NORTC_YEAR 2019 +#define FF_NORTC_YEAR 2020 /* The option FF_FS_NORTC switches timestamp functiton. If the system does not have / any RTC function or valid timestamp is not needed, set FF_FS_NORTC = 1 to disable / the timestamp function. Every object modified by FatFs will have a fixed timestamp @@ -278,18 +288,17 @@ / and f_fdisk() function, are always not re-entrant. Only file/directory access / to the same volume is under control of this function. / -/ 0: Disable re-entrancy. FF_FS_TIMEOUT and _SYNC_t have no effect. +/ 0: Disable re-entrancy. FF_FS_TIMEOUT and FF_SYNC_t have no effect. / 1: Enable re-entrancy. 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. Samples are available in / option/syscall.c. / / The FF_FS_TIMEOUT defines timeout period in unit of time tick. -/ The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*, -/ SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be +/ The FF_SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*, +/ SemaphoreHandle_t and etc. A header file for O/S definitions needs to be / included somewhere in the scope of ff.h. */ -/* #include // O/S definitions */ /*--- End of configuration options ---*/ diff --git a/sw/airborne/arch/chibios/halconf.h b/sw/airborne/arch/chibios/halconf.h index bf566b7cb6..55e01e790e 100644 --- a/sw/airborne/arch/chibios/halconf.h +++ b/sw/airborne/arch/chibios/halconf.h @@ -1,13 +1,5 @@ /* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications - Utah State University, http://aggieair.usu.edu/ - - Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu) - Calvin Coopmans (c.r.coopmans@ieee.org) - - modified by Gautier Hattenberger for STM32F7 support + ChibiOS - Copyright (C) 2006..2020 Giovanni Di Sirio Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. @@ -37,7 +29,7 @@ #define HALCONF_H #define _CHIBIOS_HAL_CONF_ -#define _CHIBIOS_HAL_CONF_VER_7_1_ +#define _CHIBIOS_HAL_CONF_VER_8_0_ #include "mcuconf.h" @@ -45,7 +37,7 @@ * @brief Enables the PAL subsystem. */ #if !defined(HAL_USE_PAL) || defined(__DOXYGEN__) -#define HAL_USE_PAL TRUE +#define HAL_USE_PAL TRUE #endif /** @@ -53,9 +45,9 @@ */ #if !defined(HAL_USE_ADC) || defined(__DOXYGEN__) #if USE_ADC -#define HAL_USE_ADC TRUE +#define HAL_USE_ADC TRUE #else -#define HAL_USE_ADC FALSE +#define HAL_USE_ADC FALSE #endif #endif @@ -64,9 +56,9 @@ */ #if !defined(HAL_USE_CAN) || defined(__DOXYGEN__) #if USE_CAN1 || USE_CAN2 -#define HAL_USE_CAN TRUE +#define HAL_USE_CAN TRUE #else -#define HAL_USE_CAN FALSE +#define HAL_USE_CAN FALSE #endif #endif @@ -82,9 +74,9 @@ */ #if !defined(HAL_USE_DAC) || defined(__DOXYGEN__) #if USE_DAC1 || USE_DAC2 -#define HAL_USE_DAC TRUE +#define HAL_USE_DAC TRUE #else -#define HAL_USE_DAC FALSE +#define HAL_USE_DAC FALSE #endif #endif @@ -107,9 +99,9 @@ */ #if !defined(HAL_USE_I2C) || defined(__DOXYGEN__) #if USE_I2C1 || USE_I2C2 || USE_I2C3 || USE_I2C4 -#define HAL_USE_I2C TRUE +#define HAL_USE_I2C TRUE #else -#define HAL_USE_I2C FALSE +#define HAL_USE_I2C FALSE #endif #endif @@ -122,16 +114,12 @@ /** * @brief Enables the ICU subsystem. - * NOTE: ICU is needed form PPM and Spektrum radio - * Maybe also for Superbit. Leave default TRUE for now - * Might have to be changed to - * ifdef RADIO_CONTROL_TYPE_PPM then TRUE, otherwise FALSE */ #if !defined(HAL_USE_ICU) || defined(__DOXYGEN__) -#if RADIO_CONTROL_TYPE_PPM || USE_PWM_INPUT || defined USE_PWM_INPUT1 || defined USE_PWM_INPUT2 -#define HAL_USE_ICU TRUE +#if RADIO_CONTROL_TYPE_PPM || USE_PWM_INPUT || defined(USE_PWM_INPUT1) || defined(USE_PWM_INPUT2) +#define HAL_USE_ICU TRUE #else -#define HAL_USE_ICU FALSE +#define HAL_USE_ICU FALSE #endif #endif @@ -175,9 +163,9 @@ */ #if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__) #if USE_UART1 || USE_UART2 || USE_UART3 || USE_UART4 || USE_UART5 || USE_UART6 || USE_UART7 || USE_UART8 -#define HAL_USE_SERIAL TRUE +#define HAL_USE_SERIAL TRUE #else -#define HAL_USE_SERIAL FALSE +#define HAL_USE_SERIAL FALSE #endif #endif @@ -186,9 +174,9 @@ */ #if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__) #if USE_USB_SERIAL -#define HAL_USE_SERIAL_USB TRUE +#define HAL_USE_SERIAL_USB TRUE #else -#define HAL_USE_SERIAL_USB FALSE +#define HAL_USE_SERIAL_USB FALSE #endif #endif @@ -204,9 +192,9 @@ */ #if !defined(HAL_USE_SPI) || defined(__DOXYGEN__) #if USE_SPI -#define HAL_USE_SPI TRUE +#define HAL_USE_SPI TRUE #else -#define HAL_USE_SPI FALSE +#define HAL_USE_SPI FALSE #endif #endif @@ -229,9 +217,9 @@ */ #if !defined(HAL_USE_USB) || defined(__DOXYGEN__) #if USE_USB_SERIAL -#define HAL_USE_USB TRUE +#define HAL_USE_USB TRUE #else -#define HAL_USE_USB FALSE +#define HAL_USE_USB FALSE #endif #endif @@ -463,6 +451,26 @@ #define SERIAL_BUFFERS_SIZE 1024 #endif +/*===========================================================================*/ +/* SIO driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Default bit rate. + * @details Configuration parameter, this is the baud rate selected for the + * default configuration. + */ +#if !defined(SIO_DEFAULT_BITRATE) || defined(__DOXYGEN__) +#define SIO_DEFAULT_BITRATE 38400 +#endif + +/** + * @brief Support for thread synchronization API. + */ +#if !defined(SIO_USE_SYNCHRONIZATION) || defined(__DOXYGEN__) +#define SIO_USE_SYNCHRONIZATION TRUE +#endif + /*===========================================================================*/ /* SERIAL_USB driver related setting. */ /*===========================================================================*/ @@ -499,11 +507,10 @@ #endif /** - * @brief Enables circular transfers APIs. - * @note Disabling this option saves both code and data space. + * @brief Inserts an assertion on function errors before returning. */ -#if !defined(SPI_USE_CIRCULAR) || defined(__DOXYGEN__) -#define SPI_USE_CIRCULAR FALSE +#if !defined(SPI_USE_ASSERT_ON_ERROR) || defined(__DOXYGEN__) +#define SPI_USE_ASSERT_ON_ERROR TRUE #endif /** diff --git a/sw/airborne/arch/chibios/mcu_arch.c b/sw/airborne/arch/chibios/mcu_arch.c index 9e152ab53d..7a6395de23 100644 --- a/sw/airborne/arch/chibios/mcu_arch.c +++ b/sw/airborne/arch/chibios/mcu_arch.c @@ -41,7 +41,7 @@ #if USE_HARD_FAULT_RECOVERY -#if defined STM32F4 || defined STM32F7 +#if defined(STM32F4XX) || defined (STM32F7XX) #define BCKP_SECTION ".ram5" #define IN_BCKP_SECTION(var) var __attribute__ ((section(BCKP_SECTION), aligned(8))) #else @@ -87,11 +87,11 @@ CH_IRQ_HANDLER(UsageFault_Handler) bool recovering_from_hard_fault; // select correct register -#if defined STM32F4 +#if defined(STM32F4XX) #define __PWR_CSR PWR->CSR #define __PWR_CSR_BRE PWR_CSR_BRE #define __PWR_CSR_BRR PWR_CSR_BRR -#elif defined STM32F7 +#elif defined(STM32F7XX) #define __PWR_CSR PWR->CSR1 #define __PWR_CSR_BRE PWR_CSR1_BRE #define __PWR_CSR_BRR PWR_CSR1_BRR @@ -108,11 +108,6 @@ bool recovering_from_hard_fault; */ void mcu_arch_init(void) { -#if LUFTBOOT - PRINT_CONFIG_MSG("We are running luftboot, the interrupt vector is being relocated.") - SCB->VTOR = CORTEX_VTOR_INIT; -#endif - /* * System initializations. * - HAL initialization, this also initializes the configured device drivers @@ -125,11 +120,11 @@ void mcu_arch_init(void) #if USE_HARD_FAULT_RECOVERY /* Backup domain SRAM enable, and with it, the regulator */ -#if defined STM32F4 || defined STM32F7 +#if defined(STM32F4XX) || defined(STM32F7XX) RCC->AHB1ENR |= RCC_AHB1ENR_BKPSRAMEN; __PWR_CSR |= __PWR_CSR_BRE; while ((__PWR_CSR & __PWR_CSR_BRR) == 0) ; /* Waits until the regulator is stable */ -#endif /* STM32F4 | STM32F7*/ +#endif /* STM32F4 | STM32F7 */ // test if last reset was a 'real' hard fault recovering_from_hard_fault = false; @@ -151,9 +146,21 @@ void mcu_arch_init(void) } -void WEAK mcu_periph_energy_save(void) +/** + * @brief Save energy for performing operations on shutdown + * Used for example to shutdown SD-card logging + */ +void mcu_periph_energy_save(void) { - // Default empty implementation - // see board.c file +#if defined(ENERGY_SAVE_INPUTS) + BOARD_GROUP_DECLFOREACH(input_line, ENERGY_SAVE_INPUTS) { + palSetLineMode(input_line, PAL_MODE_INPUT); + } +#endif +#if defined(ENERGY_SAVE_LOWS) + BOARD_GROUP_DECLFOREACH(input_low, ENERGY_SAVE_LOWS) { + palClearLine(input_low); + } +#endif } diff --git a/sw/airborne/arch/chibios/mcu_arch.h b/sw/airborne/arch/chibios/mcu_arch.h index 6cee6b18aa..b71ae408cd 100644 --- a/sw/airborne/arch/chibios/mcu_arch.h +++ b/sw/airborne/arch/chibios/mcu_arch.h @@ -51,16 +51,21 @@ extern bool recovering_from_hard_fault; */ static inline void mcu_deep_sleep(void) { -#if defined STM32F4 +#if defined(STM32F4XX) /* clear PDDS and LPDS bits */ PWR->CR &= ~(PWR_CR_PDDS | PWR_CR_LPDS); /* set LPDS and clear */ PWR->CR |= (PWR_CR_LPDS | PWR_CR_CSBF | PWR_CR_CWUF); -#elif defined STM32F7 +#elif defined(STM32F7XX) /* clear PDDS and LPDS bits */ PWR->CR1 &= ~(PWR_CR1_PDDS | PWR_CR1_LPDS); /* set LPDS and clear */ PWR->CR1 |= (PWR_CR1_LPDS | PWR_CR1_CSBF); +#elif defined(STM32H7XX) + /* clear LPDS */ + PWR->CR1 &= ~PWR_CR1_LPDS; + /* set LPDS */ + PWR->CR1 |= PWR_CR1_LPDS; #endif /* Setup the deepsleep mask */ diff --git a/sw/airborne/arch/chibios/mcu_periph/adc_arch.c b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c index c608e6da58..06c9bc0592 100644 --- a/sw/airborne/arch/chibios/mcu_periph/adc_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c @@ -48,7 +48,7 @@ * Then only every second channel is really read. Might be fixed in next version * of ChibiOS * - * V_ref is 3.3V, ADC has 12bit resolution. + * V_ref is 3.3V, ADC has 12bit or 16bit resolution. */ #include "mcu_periph/adc.h" #include "mcu_periph/gpio.h" @@ -66,22 +66,16 @@ ///#endif -// architecture dependent settings -#if defined(__STM32F10x_H) || defined(__STM32F105xC_H) || defined (__STM32F107xC_H) -// STM32F1xx -#define ADC_SAMPLE_RATE ADC_SAMPLE_41P5 -#define ADC_CR2_CFG ADC_CR2_TSVREFE -#elif defined(__STM32F4xx_H) || defined(__STM32F7xx_H) -// STM32F4xx | STM32F7xx -#define ADC_SAMPLE_RATE ADC_SAMPLE_480 -#define ADC_CR2_CFG ADC_CR2_SWSTART -#elif defined(__STM32F373xC_H) -#define ADC_SAMPLE_RATE ADC_SAMPLE_239P5 -#define ADC_CR2_CFG ADC_CR2_SWSTART -#elif defined(__STM32F3xx_H) +/* Set the default sample rate */ +#if !defined(ADC_SAMPLE_RATE) +#if defined(STM32H7XX) +#define ADC_SAMPLE_RATE ADC_SMPR_SMP_384P5 +#elif defined(STM32F3XX) #define ADC_SAMPLE_RATE ADC_SMPR_SMP_601P5 +#else +#define ADC_SAMPLE_RATE ADC_SAMPLE_480 +#endif #endif - // Create channel map static const uint8_t adc_channel_map[ADC_NUM_CHANNELS] = { @@ -143,9 +137,10 @@ ADCDriver *adcp_err = NULL; #ifndef ADC_BUF_DEPTH #define ADC_BUF_DEPTH (MAX_AV_NB_SAMPLE/2) #endif -static IN_DMA_SECTION(adcsample_t adc_samples[ADC_NUM_CHANNELS * ADC_BUF_DEPTH]); +static IN_DMA_SECTION(adcsample_t adc_samples[ADC_NUM_CHANNELS * MAX_AV_NB_SAMPLE]); #if USE_AD1 +static ADCConversionGroup adc1_group; static struct adc_buf *adc1_buffers[ADC_NUM_CHANNELS]; static uint32_t adc1_sum_tmp[ADC_NUM_CHANNELS]; static uint8_t adc1_samples_tmp[ADC_NUM_CHANNELS]; @@ -167,46 +162,70 @@ static struct { } adc_watchdog; #endif -// From libopencm3 -static void adc_regular_sequence(uint32_t *sqr1, uint32_t *sqr2, uint32_t *sqr3, uint8_t length, const uint8_t channel[]) +/** + * @brief Configure the ADC conversion group depending on the architecture + * + * @param cfg The configuration to be set + * @param num_channels The number of channels in the ADC + * @param channels The channel mapping to real channels + * @param sample_rate The sample rate for all channels + * @param end_cb The callback function at the end of conversion + * @param error_cb The callback function whenever an error occurs + */ +static void adc_configure(ADCConversionGroup *cfg, uint8_t num_channels, const uint8_t channels[], uint32_t sample_rate, + adccallback_t end_cb, adcerrorcallback_t error_cb) { - uint32_t first6 = 0; - uint32_t second6 = 0; - uint32_t third6 = ADC_SQR1_NUM_CH(length); - uint8_t i = 0; + // Set the general configuration + cfg->circular = true; + cfg->num_channels = num_channels; + cfg->end_cb = end_cb; + cfg->error_cb = error_cb; - for (i = 1; i <= length; i++) { - if (i <= 6) { - first6 |= (channel[i - 1] << ((i - 1) * 5)); + // Set to 16bits by default else try 12bit +#if defined(ADC_CFGR_RES_16BITS) + cfg->cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS; +#elif defined(ADC_CFGR_RES_12BITS) + cfg->cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS; +#else + cfg->sqr1 = ADC_SQR1_NUM_CH(num_channels); + cfg->cr2 = ADC_CR2_SWSTART; + +#if defined(ADC_CR2_TSVREFE) + cfg->cr2 |= ADC_CR2_TSVREFE; +#endif +#endif + + // Go through all the channels + for (uint8_t i = 0; i < num_channels; i++) { + uint8_t chan = channels[i]; + +#if defined(STM32H7XX) || defined(STM32F3XX) || defined(STM32G4XX) || defined(STM32L4XX) + cfg->pcsel |= (1 << chan); + cfg->smpr[chan / 10] |= sample_rate << (3 << (chan % 10)); + + if (i < 4) { + cfg->sqr[0] |= chan << (6 * (i + 1)); + } else if (i < 9) { + cfg->sqr[1] |= chan << (6 * (i - 4)); + } else { + cfg->sqr[2] |= chan << (6 * (i - 9)); } - if ((i > 6) && (i <= 12)) { - second6 |= (channel[i - 1] << ((i - 6 - 1) * 5)); +#else + if (chan < 10) { + cfg->smpr2 |= sample_rate << (3 * chan); + } else { + cfg->smpr1 |= sample_rate << (3 * (chan - 10)); } - if ((i > 12) && (i <= 18)) { - third6 |= (channel[i - 1] << ((i - 12 - 1) * 5)); + + if (i < 6) { + cfg->sqr3 |= chan << (5 * i); + } else if (i < 12) { + cfg->sqr2 |= chan << (5 * (i - 6)); + } else { + cfg->sqr3 |= chan << (5 * (i - 12)); } +#endif } - *sqr3 = first6; - *sqr2 = second6; - *sqr1 = third6; -} - -// From libopencm3 -static void adc_sample_time_on_all_channels(uint32_t *smpr1, uint32_t *smpr2, uint8_t time) -{ - uint8_t i; - uint32_t reg32 = 0; - - for (i = 0; i <= 9; i++) { - reg32 |= (time << (i * 3)); - } - *smpr2 = reg32; - - reg32 = 0; - for (i = 10; i <= 17; i++) { - reg32 |= (time << ((i - 10) * 3)); - } - *smpr1 = reg32; } /** @@ -231,7 +250,8 @@ void adc1callback(ADCDriver *adcp) // half buffer start in the middle of buffer, else, is start at // beginiing of buffer const adcsample_t *buffer = adc_samples + (adcIsBufferComplete(adcp) ? - n * ADC_NUM_CHANNELS : 0U); + n *ADC_NUM_CHANNELS : 0U); + cacheBufferInvalidate(adc_samples, sizeof(adc_samples)); for (int channel = 0; channel < ADC_NUM_CHANNELS; channel++) { if (adc1_buffers[channel] != NULL) { @@ -304,12 +324,6 @@ void adc_buf_channel(uint8_t adc_channel, struct adc_buf *s, uint8_t av_nb_sampl } } -/** - * Configuration structure - * must be global - */ -static ADCConversionGroup adcgrpcfg; - /** * Adc init * @@ -356,13 +370,6 @@ void adc_init(void) gpio_setup_pin_analog(ADC_9_GPIO_PORT, ADC_9_GPIO_PIN); #endif - // Configuration register - uint32_t sqr1, sqr2, sqr3; - adc_regular_sequence(&sqr1, &sqr2, &sqr3, ADC_NUM_CHANNELS, adc_channel_map); - - uint32_t smpr1, smpr2; - adc_sample_time_on_all_channels(&smpr1, &smpr2, ADC_SAMPLE_RATE); - #if USE_ADC_WATCHDOG adc_watchdog.adc = NULL; adc_watchdog.cb = NULL; @@ -370,42 +377,12 @@ void adc_init(void) adc_watchdog.vmin = (1 << 12) - 1; // max adc #endif - adcgrpcfg.circular = TRUE; - adcgrpcfg.num_channels = ADC_NUM_CHANNELS; - adcgrpcfg.end_cb = adc1callback; - adcgrpcfg.error_cb = adcerrorcallback; -#if defined(__STM32F373xC_H) - adcgrpcfg.u.adc.smpr[0] = smpr1; - adcgrpcfg.u.adc.smpr[1] = smpr2; - adcgrpcfg.u.adc.sqr[0] = sqr1; - adcgrpcfg.u.adc.sqr[1] = sqr2; - adcgrpcfg.u.adc.sqr[2] = sqr3; - adcgrpcfg.u.adc.cr1 = 0; - adcgrpcfg.u.adc.cr2 = ADC_CR2_CFG; -#elif defined(__STM32F3xx_H) - //TODO: check if something needs to be done with the other regs (can be found in ~/paparazzi/sw/ext/chibios/os/hal/ports/STM32/LLD/ADCv3) -#warning ADCs not tested with stm32f30 - // cfgr - // tr1 - - adcgrpcfg.smpr[0] = smpr1; // is this even correct? - adcgrpcfg.smpr[1] = smpr2; - adcgrpcfg.sqr[0] = sqr1; - adcgrpcfg.sqr[1] = sqr2; - adcgrpcfg.sqr[2] = sqr3; -#else - adcgrpcfg.cr2 = ADC_CR2_CFG; - adcgrpcfg.cr1 = 0; - adcgrpcfg.smpr1 = smpr1; - adcgrpcfg.smpr2 = smpr2; - adcgrpcfg.sqr1 = sqr1; - adcgrpcfg.sqr2 = sqr2; - adcgrpcfg.sqr3 = sqr3; -#endif + // Configure the ADC structure + adc_configure(&adc1_group, ADC_NUM_CHANNELS, adc_channel_map, ADC_SAMPLE_RATE, adc1callback, adcerrorcallback); // Start ADC in continious conversion mode adcStart(&ADCD1, NULL); - adcStartConversion(&ADCD1, &adcgrpcfg, adc_samples, ADC_BUF_DEPTH); + adcStartConversion(&ADCD1, &adc1_group, adc_samples, ADC_BUF_DEPTH); } #if USE_ADC_WATCHDOG diff --git a/sw/airborne/arch/chibios/mcu_periph/adc_arch.h b/sw/airborne/arch/chibios/mcu_periph/adc_arch.h index 168b651bc5..6b00568983 100644 --- a/sw/airborne/arch/chibios/mcu_periph/adc_arch.h +++ b/sw/airborne/arch/chibios/mcu_periph/adc_arch.h @@ -110,7 +110,7 @@ typedef void (*adc_watchdog_callback)(void); * @param cb callback function call within ISR locked zone */ extern void register_adc_watchdog(ADCDriver *adc, adc_channels_num_t channel, adcsample_t vmin, - adc_watchdog_callback cb); + adc_watchdog_callback cb); #endif diff --git a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c index 1c2f0a1ec4..7614c21dd7 100644 --- a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c @@ -62,14 +62,14 @@ void gpio_setup_pin_af(ioportid_t port, uint16_t pin, uint8_t af, bool is_output { chSysLock(); // architecture dependent settings -#if defined(STM32F1) +#if defined(STM32F1XX) // FIXME: STM32F1xx doesn't support several alternate modes, is it needed for drivers? (void)port; (void)pin; (void)af; (void)is_output; -#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F7) -// STM32F4xx, STM32F3xx and STM32F7xx +#else +// STM32F4xx, STM32F3xx, STM32F7xx and STM32H7xx if (af) { palSetPadMode(port, pin, PAL_MODE_ALTERNATE(af)); } else { diff --git a/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c b/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c index 13dcaec3fe..36eca2ce06 100644 --- a/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c @@ -56,11 +56,13 @@ static void i2c_chibios_setbitrate(struct i2c_periph *p, int bitrate) __attribut // private I2C init structure struct i2c_init { - semaphore_t *sem; - I2CConfig *cfg; -#ifdef STM32F7 - uint8_t *dma_buf; +#if defined(STM32F7XX) || defined(STM32H7XX) + uint8_t dma_buf[I2C_BUF_LEN]; #endif + char *name; + semaphore_t sem; + I2CConfig cfg; + struct i2c_errors errors; }; @@ -79,7 +81,7 @@ static void handle_i2c_thd(struct i2c_periph *p) struct i2c_init *i = (struct i2c_init *) p->init_struct; // wait for a transaction to be pushed in the queue - chSemWait(i->sem); + chSemWait(&i->sem); if (p->trans_insert_idx == p->trans_extract_idx) { p->status = I2CIdle; @@ -94,15 +96,17 @@ static void handle_i2c_thd(struct i2c_periph *p) msg_t status; // submit i2c transaction (R/W or R only depending of len_w) if (t->len_w > 0) { -#if defined STM32F7 +#if defined(STM32F7XX) || defined(STM32H7XX) // we do stupid mem copy because F7 needs a special RAM for DMA operation memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w)); + cacheBufferFlush(i->dma_buf, t->len_w); status = i2cMasterTransmitTimeout( (I2CDriver *)p->reg_addr, (i2caddr_t)((t->slave_addr) >> 1), (uint8_t *)i->dma_buf, (size_t)(t->len_w), (uint8_t *)i->dma_buf, (size_t)(t->len_r), tmo); + cacheBufferInvalidate(i->dma_buf, t->len_r); memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r)); #else status = i2cMasterTransmitTimeout( @@ -113,7 +117,7 @@ static void handle_i2c_thd(struct i2c_periph *p) tmo); #endif } else { -#if defined STM32F7 +#if defined(STM32F7XX) || defined(STM32H7XX) // we do stupid mem copy because F7 needs a special RAM for DMA operation memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w)); status = i2cMasterReceiveTimeout( @@ -150,7 +154,7 @@ static void handle_i2c_thd(struct i2c_periph *p) //if a timeout occurred before operation end // mark as failed and restart t->status = I2CTransFailed; - i2cStart((I2CDriver *)p->reg_addr, i->cfg); + i2cStart((I2CDriver *)p->reg_addr, &i->cfg); break; case MSG_RESET: //if one or more I2C errors occurred, the errors can @@ -183,31 +187,32 @@ static void handle_i2c_thd(struct i2c_periph *p) break; } } + +/** + * @brief I2C thead + * + * @param arg The i2c peripheral (i2c_periph) + */ +static void thd_i2c(void *arg) +{ + struct i2c_periph *i2cp = (struct i2c_periph *)arg; + struct i2c_init *init_s = (struct i2c_init *)i2cp->init_struct; + chRegSetThreadName(init_s->name); + + while (TRUE) { + handle_i2c_thd(i2cp); + } +} #endif /* USE_I2C1 || USE_I2C2 || USE_I2C3 || USE_I2C4 */ #if USE_I2C1 -// I2C1 config PRINT_CONFIG_VAR(I2C1_CLOCK_SPEED) -static SEMAPHORE_DECL(i2c1_sem, 0); -static I2CConfig i2cfg1 = I2C1_CFG_DEF; -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t i2c1_dma_buf[I2C_BUF_LEN]); -static struct i2c_init i2c1_init_s = { - .sem = &i2c1_sem, - .cfg = &i2cfg1, - .dma_buf = i2c1_dma_buf +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct i2c_init i2c1_init_s) = { + .name = "i2c1", + .sem = __SEMAPHORE_DATA(i2c1_init_s.sem, 0), + .cfg = I2C1_CFG_DEF }; -#else -static struct i2c_init i2c1_init_s = { - .sem = &i2c1_sem, - .cfg = &i2cfg1 -}; -#endif -// Errors -struct i2c_errors i2c1_errors; -// Thread -static __attribute__((noreturn)) void thd_i2c1(void *arg); static THD_WORKING_AREA(wa_thd_i2c1, I2C_THREAD_STACK_SIZE); /* @@ -219,53 +224,24 @@ void i2c1_hw_init(void) i2c1.submit = i2c_chibios_submit; i2c1.setbitrate = i2c_chibios_setbitrate; - i2cStart(&I2CD1, &i2cfg1); + i2cStart(&I2CD1, &i2c1_init_s.cfg); i2c1.reg_addr = &I2CD1; - i2c1.errors = &i2c1_errors; + i2c1.errors = &i2c1_init_s.errors; i2c1.init_struct = &i2c1_init_s; // Create thread chThdCreateStatic(wa_thd_i2c1, sizeof(wa_thd_i2c1), - NORMALPRIO + 1, thd_i2c1, NULL); -} - -/* - * I2C1 thread - * - */ -static void thd_i2c1(void *arg) -{ - (void) arg; - chRegSetThreadName("i2c1"); - - while (TRUE) { - handle_i2c_thd(&i2c1); - } + NORMALPRIO + 1, thd_i2c, (void *)&i2c1); } #endif /* USE_I2C1 */ #if USE_I2C2 -// I2C2 config PRINT_CONFIG_VAR(I2C2_CLOCK_SPEED) -static SEMAPHORE_DECL(i2c2_sem, 0); -static I2CConfig i2cfg2 = I2C2_CFG_DEF; -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t i2c2_dma_buf[I2C_BUF_LEN]); -static struct i2c_init i2c2_init_s = { - .sem = &i2c2_sem, - .cfg = &i2cfg2, - .dma_buf = i2c2_dma_buf +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct i2c_init i2c2_init_s) = { + .name = "i2c2", + .sem = __SEMAPHORE_DATA(i2c2_init_s.sem, 0), + .cfg = I2C2_CFG_DEF }; -#else -static struct i2c_init i2c2_init_s = { - .sem = &i2c2_sem, - .cfg = &i2cfg2 -}; -#endif -// Errors -struct i2c_errors i2c2_errors; -// Thread -static __attribute__((noreturn)) void thd_i2c2(void *arg); static THD_WORKING_AREA(wa_thd_i2c2, I2C_THREAD_STACK_SIZE); /* @@ -277,53 +253,24 @@ void i2c2_hw_init(void) i2c2.submit = i2c_chibios_submit; i2c2.setbitrate = i2c_chibios_setbitrate; - i2cStart(&I2CD2, &i2cfg2); + i2cStart(&I2CD2, &i2c2_init_s.cfg); i2c2.reg_addr = &I2CD2; - i2c2.errors = &i2c2_errors; + i2c2.errors = &i2c2_init_s.errors; i2c2.init_struct = &i2c2_init_s; // Create thread chThdCreateStatic(wa_thd_i2c2, sizeof(wa_thd_i2c2), - NORMALPRIO + 1, thd_i2c2, NULL); -} - -/* - * I2C2 thread - * - */ -static void thd_i2c2(void *arg) -{ - (void) arg; - chRegSetThreadName("i2c2"); - - while (TRUE) { - handle_i2c_thd(&i2c2); - } + NORMALPRIO + 1, thd_i2c, (void *)&i2c2); } #endif /* USE_I2C2 */ #if USE_I2C3 -// I2C3 config PRINT_CONFIG_VAR(I2C3_CLOCK_SPEED) -static SEMAPHORE_DECL(i2c3_sem, 0); -static I2CConfig i2cfg3 = I2C3_CFG_DEF; -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t i2c3_dma_buf[I2C_BUF_LEN]); -static struct i2c_init i2c3_init_s = { - .sem = &i2c3_sem, - .cfg = &i2cfg3, - .dma_buf = i2c3_dma_buf +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct i2c_init i2c3_init_s) = { + .name = "i2c3", + .sem = __SEMAPHORE_DATA(i2c3_init_s.sem, 0), + .cfg = I2C3_CFG_DEF }; -#else -static struct i2c_init i2c3_init_s = { - .sem = &i2c3_sem, - .cfg = &i2cfg3 -}; -#endif -// Errors -struct i2c_errors i2c3_errors; -// Thread -static __attribute__((noreturn)) void thd_i2c3(void *arg); static THD_WORKING_AREA(wa_thd_i2c3, I2C_THREAD_STACK_SIZE); /* @@ -335,54 +282,24 @@ void i2c3_hw_init(void) i2c3.submit = i2c_chibios_submit; i2c3.setbitrate = i2c_chibios_setbitrate; - i2cStart(&I2CD3, &i2cfg3); + i2cStart(&I2CD3, &i2c3_init_s.cfg); i2c3.reg_addr = &I2CD3; - i2c3.init_struct = NULL; - i2c3.errors = &i2c3_errors; + i2c3.errors = &i2c3_init_s.errors; i2c3.init_struct = &i2c3_init_s; // Create thread chThdCreateStatic(wa_thd_i2c3, sizeof(wa_thd_i2c3), - NORMALPRIO + 1, thd_i2c3, NULL); -} - -/* - * I2C3 thread - * - */ -static void thd_i2c3(void *arg) -{ - (void) arg; - chRegSetThreadName("i2c3"); - - while (TRUE) { - handle_i2c_thd(&i2c3); - } + NORMALPRIO + 1, thd_i2c, (void *)&i2c3); } #endif /* USE_I2C3 */ #if USE_I2C4 -// I2C4 config PRINT_CONFIG_VAR(I2C4_CLOCK_SPEED) -static SEMAPHORE_DECL(i2c4_sem, 0); -static I2CConfig i2cfg4 = I2C4_CFG_DEF; -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t i2c4_dma_buf[I2C_BUF_LEN]); -static struct i2c_init i2c4_init_s = { - .sem = &i2c4_sem, - .cfg = &i2cfg4, - .dma_buf = i2c4_dma_buf +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct i2c_init i2c4_init_s) = { + .name = "i2c4", + .sem = __SEMAPHORE_DATA(i2c4_init_s.sem, 0), + .cfg = I2C4_CFG_DEF }; -#else -static struct i2c_init i2c4_init_s = { - .sem = &i2c4_sem, - .cfg = &i2cfg4 -}; -#endif -// Errors -struct i2c_errors i2c4_errors; -// Thread -static __attribute__((noreturn)) void thd_i2c4(void *arg); static THD_WORKING_AREA(wa_thd_i2c4, I2C_THREAD_STACK_SIZE); /* @@ -394,28 +311,13 @@ void i2c4_hw_init(void) i2c4.submit = i2c_chibios_submit; i2c4.setbitrate = i2c_chibios_setbitrate; - i2cStart(&I2CD4, &i2cfg4); + i2cStart(&I2CD4, &i2c4_init_s.cfg); i2c4.reg_addr = &I2CD4; - i2c4.init_struct = NULL; - i2c4.errors = &i2c4_errors; + i2c4.errors = &i2c4_init_s.errors; i2c4.init_struct = &i2c4_init_s; // Create thread chThdCreateStatic(wa_thd_i2c4, sizeof(wa_thd_i2c4), - NORMALPRIO + 1, thd_i2c4, NULL); -} - -/* - * I2C4 thread - * - */ -static void thd_i2c4(void *arg) -{ - (void) arg; - chRegSetThreadName("i2c4"); - - while (TRUE) { - handle_i2c_thd(&i2c4); - } + NORMALPRIO + 1, thd_i2c, (void *)&i2c4); } #endif /* USE_I2C4 */ @@ -475,7 +377,7 @@ static bool i2c_chibios_submit(struct i2c_periph *p, struct i2c_transaction *t) p->trans_insert_idx = temp; chSysUnlock(); - chSemSignal(((struct i2c_init *)p->init_struct)->sem); + chSemSignal(&((struct i2c_init *)p->init_struct)->sem); // transaction submitted return TRUE; #else diff --git a/sw/airborne/arch/chibios/mcu_periph/ram_arch.h b/sw/airborne/arch/chibios/mcu_periph/ram_arch.h index 14bce33ae9..049e45fd59 100644 --- a/sw/airborne/arch/chibios/mcu_periph/ram_arch.h +++ b/sw/airborne/arch/chibios/mcu_periph/ram_arch.h @@ -43,24 +43,33 @@ #ifndef RAM_ARCH_H #define RAM_ARCH_H -#if defined STM32F1 +#if defined(STM32F1XX) #define STD_SECTION ".ram0" #define FAST_SECTION ".ram0" #define DMA_SECTION ".ram0" -#elif defined STM32F3 +#define DMA_ALIGN 8 +#elif defined(STM32F3XX) #define STD_SECTION ".ram0" #define FAST_SECTION ".ram4" #define DMA_SECTION ".ram0" -#elif defined STM32F4 +#define DMA_ALIGN 8 +#elif defined(STM32F4XX) #define STD_SECTION ".ram0" #define FAST_SECTION ".ram4" #define DMA_SECTION ".ram0" -#elif defined STM32F7 +#define DMA_ALIGN 8 +#elif defined(STM32F7XX) #define STD_SECTION ".ram0" #define FAST_SECTION ".ram0" #define DMA_SECTION ".ram3" +#define DMA_ALIGN 8 +#elif defined(STM32H7XX) +#define STD_SECTION ".ram1" +#define FAST_SECTION ".ram5" +#define DMA_SECTION ".ram0" +#define DMA_ALIGN 32 #else -#error "section defined only for STM32F1, STM32F4 and STM32F7" +#error "section defined only for STM32F1, STM32F3, STM32F4, STM32F7 and STM32H7" #endif #define IN_STD_SECTION_NOINIT(var) var __attribute__ ((section(STD_SECTION), aligned(8))) @@ -71,9 +80,9 @@ #define IN_FAST_SECTION_CLEAR(var) var __attribute__ ((section(FAST_SECTION "_clear"), aligned(8))) #define IN_FAST_SECTION(var) var __attribute__ ((section(FAST_SECTION "_init"), aligned(8))) -#define IN_DMA_SECTION_NOINIT(var) var __attribute__ ((section(DMA_SECTION), aligned(8))) -#define IN_DMA_SECTION_CLEAR(var) var __attribute__ ((section(DMA_SECTION "_clear"), aligned(8))) -#define IN_DMA_SECTION(var) var __attribute__ ((section(DMA_SECTION "_init"), aligned(8))) +#define IN_DMA_SECTION_NOINIT(var) var __attribute__ ((section(DMA_SECTION), aligned(DMA_ALIGN))) +#define IN_DMA_SECTION_CLEAR(var) var __attribute__ ((section(DMA_SECTION "_clear"), aligned(DMA_ALIGN))) +#define IN_DMA_SECTION(var) var __attribute__ ((section(DMA_SECTION "_init"), aligned(DMA_ALIGN))) #endif diff --git a/sw/airborne/arch/chibios/mcu_periph/sdio_arch.c b/sw/airborne/arch/chibios/mcu_periph/sdio_arch.c index 46de50207f..28aae38467 100644 --- a/sw/airborne/arch/chibios/mcu_periph/sdio_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/sdio_arch.c @@ -47,7 +47,7 @@ static enum {STOP, CONNECT} cnxState = STOP; bool sdio_connect(void) { - if (!sdc_lld_is_card_inserted (NULL)) { + if (!sdc_lld_is_card_inserted(NULL)) { return FALSE; } @@ -55,49 +55,36 @@ bool sdio_connect(void) return TRUE; } - /* - * Initializes the SDIO drivers. - * - * FIXME This could be hardcoded in board file ? - */ - const uint32_t mode = PAL_MODE_ALTERNATE(SDIO_AF) | PAL_STM32_OTYPE_PUSHPULL | - PAL_STM32_OSPEED_HIGHEST | PAL_STM32_PUPDR_FLOATING | PAL_STM32_MODE_ALTERNATE; - - palSetPadMode (SDIO_D0_PORT, SDIO_D0_PIN, mode | PAL_STM32_PUPDR_PULLUP); - palSetPadMode (SDIO_D1_PORT, SDIO_D1_PIN, mode | PAL_STM32_PUPDR_PULLUP); - palSetPadMode (SDIO_D2_PORT, SDIO_D2_PIN, mode | PAL_STM32_PUPDR_PULLUP); - palSetPadMode (SDIO_D3_PORT, SDIO_D3_PIN, mode | PAL_STM32_PUPDR_PULLUP); - palSetPadMode (SDIO_CK_PORT, SDIO_CK_PIN, mode); - palSetPadMode (SDIO_CMD_PORT, SDIO_CMD_PIN, mode | PAL_STM32_PUPDR_PULLUP); - // palSetPadMode (GPIOD, GPIOD_SDIO_CMD, mode); - - chThdSleepMilliseconds(100); - - - sdcStart(&SDCD1, NULL); - while (sdcConnect(&SDCD1) != HAL_SUCCESS) { + // Try only 3 times to prevent hanging + for (uint8_t i = 0; i < 3; i++) { + sdcStart(&SDCD1, NULL); + if (sdcConnect(&SDCD1) == HAL_SUCCESS) { + cnxState = CONNECT; + return TRUE; + } + sdcStop(&SDCD1); chThdSleepMilliseconds(100); } - cnxState = CONNECT; - return TRUE; + return FALSE; } bool sdio_disconnect(void) { - if (cnxState == STOP) + if (cnxState == STOP) { return TRUE; + } if (sdcDisconnect(&SDCD1)) { return FALSE; } - sdcStop (&SDCD1); + sdcStop(&SDCD1); cnxState = STOP; return TRUE; } bool is_card_inserted(void) { - return sdc_lld_is_card_inserted (NULL); + return sdc_lld_is_card_inserted(NULL); } diff --git a/sw/airborne/arch/chibios/mcu_periph/spi_arch.c b/sw/airborne/arch/chibios/mcu_periph/spi_arch.c index e6bc11e33f..34be645da6 100644 --- a/sw/airborne/arch/chibios/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/spi_arch.c @@ -35,8 +35,9 @@ #include #include "mcu_periph/ram_arch.h" + #if SPI_SLAVE -#error "ChibiOS operates only in SPI_MASTER mode" +#error "ChibiOS operates only in SPI_MASTER mode (Slave is TODO)" #endif #if USE_SPI0 @@ -48,15 +49,20 @@ #define SPI_THREAD_STACK_SIZE 512 #endif +// Default spi DMA buffer length for F7/H7 +#ifndef SPI_DMA_BUF_LEN +#define SPI_DMA_BUF_LEN 512 // it has to be big enough +#endif + // private SPI init structure struct spi_init { - semaphore_t *sem; -#ifdef STM32F7 - uint8_t *dma_buf_out; - uint8_t *dma_buf_in; +#if defined(STM32F7XX) || defined(STM32H7XX) + uint8_t dma_buf_out[SPI_DMA_BUF_LEN]; + uint8_t dma_buf_in[SPI_DMA_BUF_LEN]; #endif + char *name; + semaphore_t sem; }; -#define SPI_DMA_BUF_LEN 512 // it has to be big enough /** * Resolve slave port @@ -99,6 +105,21 @@ static inline ioportid_t spi_resolve_slave_port(uint8_t slave) return SPI_SELECT_SLAVE5_PORT; break; #endif //USE_SPI_SLAVE5 +#if USE_SPI_SLAVE6 + case 6: + return SPI_SELECT_SLAVE6_PORT; + break; +#endif //USE_SPI_SLAVE6 +#if USE_SPI_SLAVE7 + case 7: + return SPI_SELECT_SLAVE7_PORT; + break; +#endif //USE_SPI_SLAVE7 +#if USE_SPI_SLAVE8 + case 8: + return SPI_SELECT_SLAVE8_PORT; + break; +#endif //USE_SPI_SLAVE8 default: return 0; break; @@ -146,6 +167,21 @@ static inline uint16_t spi_resolve_slave_pin(uint8_t slave) return SPI_SELECT_SLAVE5_PIN; break; #endif //USE_SPI_SLAVE5 +#if USE_SPI_SLAVE6 + case 6: + return SPI_SELECT_SLAVE6_PIN; + break; +#endif //USE_SPI_SLAVE6 +#if USE_SPI_SLAVE7 + case 7: + return SPI_SELECT_SLAVE7_PIN; + break; +#endif //USE_SPI_SLAVE7 +#if USE_SPI_SLAVE8 + case 8: + return SPI_SELECT_SLAVE8_PIN; + break; +#endif //USE_SPI_SLAVE8 default: return 0; break; @@ -153,26 +189,26 @@ static inline uint16_t spi_resolve_slave_pin(uint8_t slave) } /** - * Resolve CR1 + * Resolve CR1 (or CFG1) * * Given the transaction settings, returns the right configuration of * SPIx_CR1 register. * * This function is currently architecture dependent (for STM32F1xx - * STM32F4xx and STM32F7xx only) + * STM32F4xx, STM32F7xx and STM32H7xx only) * TODO: extend for other architectures too * * @param[in] t pointer to a @p spi_transaction struct */ -static inline uint16_t spi_resolve_CR1(struct spi_transaction *t __attribute__((unused))) +static inline uint32_t spi_resolve_CR1(struct spi_transaction *t __attribute__((unused))) { - uint16_t CR1 = 0; -#if defined(STM32F1) || defined(STM32F4) + uint32_t CR1 = 0; +#if defined(STM32F1XX) || defined(STM32F4XX) if (t->dss == SPIDss16bit) { - CR1 |= SPI_CR1_DFF; // FIXME for F7 + CR1 |= SPI_CR1_DFF; } #endif -#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) +#if defined(STM32F1XX) || defined(STM32F4XX) || defined(STM32F7XX) if (t->bitorder == SPILSBFirst) { CR1 |= SPI_CR1_LSBFIRST; } @@ -210,32 +246,51 @@ static inline uint16_t spi_resolve_CR1(struct spi_transaction *t __attribute__(( default: break; } -#endif /* STM32F1 || STM32F4 || STM32F7 */ +#endif /* STM32F1XX || STM32F4XX || STM32F7XX */ +#if defined(STM32H7XX) + if (t->dss == SPIDss16bit) { + CR1 |= SPI_CFG1_DSIZE_VALUE(15); // 16 bit transfer + } else { + CR1 |= SPI_CFG1_DSIZE_VALUE(7); // 8 bit transfer + } + CR1 |= SPI_CFG1_MBR_VALUE(t->cdiv); +#endif /* STM32H7XX */ return CR1; } /** - * Resolve CR2 + * Resolve CR2 (or CFG2) * * Given the transaction settings, returns the right configuration of * SPIx_CR2 register. * * This function is currently architecture dependent (for STM32F1xx - * STM32F4xx and STM32F7xx only) + * STM32F4xx, STM32F7xx and STM32H7xx only) * TODO: extend for other architectures too * * @param[in] t pointer to a @p spi_transaction struct */ -static inline uint16_t spi_resolve_CR2(struct spi_transaction *t __attribute__((unused))) +static inline uint32_t spi_resolve_CR2(struct spi_transaction *t __attribute__((unused))) { - uint16_t CR2 = 0; -#if defined(STM32F7) + uint32_t CR2 = 0; +#if defined(STM32F7XX) if (t->dss == SPIDss16bit) { CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2 | SPI_CR2_DS_3; } else { CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2; } -#endif /* STM32F7 */ +#endif /* STM32F7XX */ +#if defined(STM32H7XX) + if (t->bitorder == SPILSBFirst) { + CR2 |= SPI_CFG2_LSBFRST; + } + if (t->cpha == SPICphaEdge2) { + CR2 |= SPI_CFG2_CPHA; + } + if (t->cpol == SPICpolIdleHigh) { + CR2 |= SPI_CFG2_CPOL; + } +#endif /* STM32H7XX */ return CR2; } @@ -249,7 +304,7 @@ static void handle_spi_thd(struct spi_periph *p) struct spi_init *i = (struct spi_init *) p->init_struct; // wait for a transaction to be pushed in the queue - chSemWait(i->sem); + chSemWait(&i->sem); if ((p->trans_insert_idx == p->trans_extract_idx) || p->suspend) { p->status = SPIIdle; @@ -264,11 +319,15 @@ static void handle_spi_thd(struct spi_periph *p) SPIConfig spi_cfg = { false, // no circular buffer +#if defined(HAL_LLD_SELECT_SPI_V2) + false, // no slave mode + NULL, // no callback +#endif NULL, // no callback spi_resolve_slave_port(t->slave_idx), spi_resolve_slave_pin(t->slave_idx), spi_resolve_CR1(t), - spi_resolve_CR2(t) + spi_resolve_CR2(t), }; // find max transaction length @@ -293,10 +352,12 @@ static void handle_spi_thd(struct spi_periph *p) } // Start synchronous data transfer -#if defined STM32F7 - // we do stupid mem copy because F7 needs a special RAM for DMA operation +#if defined(STM32F7XX) || defined(STM32H7XX) + // we do stupid mem copy because F7/H7 needs a special RAM for DMA operation memcpy(i->dma_buf_out, (void *)t->output_buf, (size_t)t->output_length); + cacheBufferFlush(i->dma_buf_out, t->output_length); spiExchange((SPIDriver *)p->reg_addr, t_length, i->dma_buf_out, i->dma_buf_in); + cacheBufferInvalidate(i->dma_buf_in, t->input_length); memcpy((void *)t->input_buf, i->dma_buf_in, (size_t)t->input_length); #else spiExchange((SPIDriver *)p->reg_addr, t_length, (uint8_t *)t->output_buf, (uint8_t *)t->input_buf); @@ -330,163 +391,99 @@ static void handle_spi_thd(struct spi_periph *p) } +/** + * @brief Default spi thread + * + * @param arg The SPI perpheral (struct spi_periph) + */ +static __attribute__((noreturn)) void thd_spi(void *arg) +{ + struct spi_periph *spip = (struct spi_periph *)arg; + struct spi_init *init_s = (struct spi_init *)spip->init_struct; + chRegSetThreadName(init_s->name); + + while (TRUE) { + handle_spi_thd(spip); + } +} + /** * Configure SPI peripherals */ #if USE_SPI1 -static SEMAPHORE_DECL(spi1_sem, 0); -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t spi1_dma_buf_out[SPI_DMA_BUF_LEN]); -static IN_DMA_SECTION(uint8_t spi1_dma_buf_in[SPI_DMA_BUF_LEN]); -static struct spi_init spi1_init_s = { - .sem = &spi1_sem, - .dma_buf_out = spi1_dma_buf_out, - .dma_buf_in = spi1_dma_buf_in +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct spi_init spi1_init_s) = { + .name = "spi1", + .sem = __SEMAPHORE_DATA(spi1_init_s.sem, 0), }; -#else -static struct spi_init spi1_init_s = { - .sem = &spi1_sem, -}; -#endif - -static __attribute__((noreturn)) void thd_spi1(void *arg) -{ - (void) arg; - chRegSetThreadName("spi1"); - - while (TRUE) { - handle_spi_thd(&spi1); - } -} - static THD_WORKING_AREA(wa_thd_spi1, SPI_THREAD_STACK_SIZE); +// Initialize the interface void spi1_arch_init(void) { spi1.reg_addr = &SPID1; spi1.init_struct = &spi1_init_s; // Create thread chThdCreateStatic(wa_thd_spi1, sizeof(wa_thd_spi1), - NORMALPRIO + 1, thd_spi1, NULL); + NORMALPRIO + 1, thd_spi, (void *)&spi1); } #endif #if USE_SPI2 -static SEMAPHORE_DECL(spi2_sem, 0); -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t spi2_dma_buf_out[SPI_DMA_BUF_LEN]); -static IN_DMA_SECTION(uint8_t spi2_dma_buf_in[SPI_DMA_BUF_LEN]); -static struct spi_init spi2_init_s = { - .sem = &spi2_sem, - .dma_buf_out = spi2_dma_buf_out, - .dma_buf_in = spi2_dma_buf_in +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct spi_init spi2_init_s) = { + .name = "spi2", + .sem = __SEMAPHORE_DATA(spi2_init_s.sem, 0), }; -#else -static struct spi_init spi2_init_s = { - .sem = &spi2_sem, -}; -#endif - -static __attribute__((noreturn)) void thd_spi2(void *arg) -{ - (void) arg; - chRegSetThreadName("spi2"); - - while (TRUE) { - handle_spi_thd(&spi2); - } -} - static THD_WORKING_AREA(wa_thd_spi2, SPI_THREAD_STACK_SIZE); +// Initialize the interface void spi2_arch_init(void) { spi2.reg_addr = &SPID2; spi2.init_struct = &spi2_init_s; // Create thread chThdCreateStatic(wa_thd_spi2, sizeof(wa_thd_spi2), - NORMALPRIO + 1, thd_spi2, NULL); + NORMALPRIO + 1, thd_spi, (void *)&spi2); } #endif #if USE_SPI3 -static SEMAPHORE_DECL(spi3_sem, 0); -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t spi3_dma_buf_out[SPI_DMA_BUF_LEN]); -static IN_DMA_SECTION(uint8_t spi3_dma_buf_in[SPI_DMA_BUF_LEN]); -static struct spi_init spi3_init_s = { - .sem = &spi3_sem, - .dma_buf_out = spi3_dma_buf_out, - .dma_buf_in = spi3_dma_buf_in +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct spi_init spi3_init_s) = { + .name = "spi3", + .sem = __SEMAPHORE_DATA(spi3_init_s.sem, 0), }; -#else -static struct spi_init spi3_init_s = { - .sem = &spi3_sem, -}; -#endif - -static __attribute__((noreturn)) void thd_spi3(void *arg) -{ - (void) arg; - chRegSetThreadName("spi3"); - - while (TRUE) { - handle_spi_thd(&spi3); - } -} - static THD_WORKING_AREA(wa_thd_spi3, SPI_THREAD_STACK_SIZE); +// Initialize the interface void spi3_arch_init(void) { spi3.reg_addr = &SPID3; spi3.init_struct = &spi3_init_s; // Create thread chThdCreateStatic(wa_thd_spi3, sizeof(wa_thd_spi3), - NORMALPRIO + 1, thd_spi3, NULL); + NORMALPRIO + 1, thd_spi, (void *)&spi3); } #endif #if USE_SPI4 -static SEMAPHORE_DECL(spi4_sem, 0); -#if defined STM32F7 -// We need a special buffer for DMA operations -static IN_DMA_SECTION(uint8_t spi4_dma_buf_out[SPI_DMA_BUF_LEN]); -static IN_DMA_SECTION(uint8_t spi4_dma_buf_in[SPI_DMA_BUF_LEN]); -static struct spi_init spi4_init_s = { - .sem = &spi4_sem, - .dma_buf_out = spi4_dma_buf_out, - .dma_buf_in = spi4_dma_buf_in +// Local variables (in DMA safe memory) +static IN_DMA_SECTION(struct spi_init spi4_init_s) = { + .name = "spi4", + .sem = __SEMAPHORE_DATA(spi4_init_s.sem, 0), }; -#else -static struct spi_init spi4_init_s = { - .sem = &spi4_sem, -}; -#endif - -static __attribute__((noreturn)) void thd_spi4(void *arg) -{ - (void) arg; - chRegSetThreadName("spi4"); - - while (TRUE) { - handle_spi_thd(&spi4); - } -} - static THD_WORKING_AREA(wa_thd_spi4, SPI_THREAD_STACK_SIZE); +// Initialize the interface void spi4_arch_init(void) { spi4.reg_addr = &SPID4; spi4.init_struct = &spi4_init_s; // Create thread chThdCreateStatic(wa_thd_spi4, sizeof(wa_thd_spi4), - NORMALPRIO + 1, thd_spi4, NULL); + NORMALPRIO + 1, thd_spi, (void *)&spi4); } #endif @@ -530,7 +527,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) p->trans_insert_idx = idx; chSysUnlock(); - chSemSignal(((struct spi_init *)p->init_struct)->sem); + chSemSignal(&((struct spi_init *)p->init_struct)->sem); // transaction submitted return TRUE; } @@ -574,6 +571,21 @@ void spi_slave_select(uint8_t slave) gpio_clear(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN); break; #endif //USE_SPI_SLAVE5 +#if USE_SPI_SLAVE6 + case 6: + gpio_clear(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN); + break; +#endif //USE_SPI_SLAVE6 +#if USE_SPI_SLAVE7 + case 7: + gpio_clear(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN); + break; +#endif //USE_SPI_SLAVE7 +#if USE_SPI_SLAVE8 + case 8: + gpio_clear(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN); + break; +#endif //USE_SPI_SLAVE8 default: break; } @@ -616,6 +628,21 @@ void spi_slave_unselect(uint8_t slave) gpio_set(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN); break; #endif //USE_SPI_SLAVE5 +#if USE_SPI_SLAVE6 + case 6: + gpio_set(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN); + break; +#endif //USE_SPI_SLAVE6 +#if USE_SPI_SLAVE7 + case 7: + gpio_set(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN); + break; +#endif //USE_SPI_SLAVE7 +#if USE_SPI_SLAVE8 + case 8: + gpio_set(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN); + break; +#endif //USE_SPI_SLAVE8 default: break; } @@ -685,5 +712,19 @@ void spi_init_slaves(void) gpio_setup_output(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN); spi_slave_unselect(5); #endif -} +#if USE_SPI_SLAVE6 + gpio_setup_output(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN); + spi_slave_unselect(6); +#endif + +#if USE_SPI_SLAVE7 + gpio_setup_output(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN); + spi_slave_unselect(7); +#endif + +#if USE_SPI_SLAVE8 + gpio_setup_output(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN); + spi_slave_unselect(8); +#endif +} diff --git a/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c index 0dec789634..f4f21cf009 100644 --- a/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/sys_time_arch.c @@ -39,6 +39,10 @@ static MUTEX_DECL(sys_time_mtx); +#ifndef STM32_SYSCLK +#define STM32_SYSCLK STM32_SYS_CK +#endif + /* * Sys_tick handler thread */ @@ -59,7 +63,7 @@ void sys_time_arch_init(void) // Create thread (PRIO should be higher than AP threads chThdCreateStatic(wa_thd_sys_tick, sizeof(wa_thd_sys_tick), - NORMALPRIO+2, thd_sys_tick, NULL); + NORMALPRIO + 2, thd_sys_tick, NULL); } @@ -73,8 +77,8 @@ uint32_t get_sys_time_usec(void) chMtxLock(&sys_time_mtx); uint32_t current = chSysGetRealtimeCounterX(); uint32_t t = sys_time.nb_sec * 1000000 + - TIME_I2US(sys_time.nb_sec_rem) + - RTC2US(STM32_SYSCLK, current - cpu_counter); + TIME_I2US(sys_time.nb_sec_rem) + + RTC2US(STM32_SYSCLK, current - cpu_counter); chMtxUnlock(&sys_time_mtx); return t; } @@ -84,8 +88,8 @@ uint32_t get_sys_time_msec(void) chMtxLock(&sys_time_mtx); uint32_t current = chSysGetRealtimeCounterX(); uint32_t t = sys_time.nb_sec * 1000 + - TIME_I2MS(sys_time.nb_sec_rem) + - RTC2MS(STM32_SYSCLK, current - cpu_counter); + TIME_I2MS(sys_time.nb_sec_rem) + + RTC2MS(STM32_SYSCLK, current - cpu_counter); chMtxUnlock(&sys_time_mtx); return t; } @@ -131,7 +135,7 @@ static __attribute__((noreturn)) void thd_sys_tick(void *arg) while (TRUE) { systime_t t = chVTGetSystemTime(); sys_tick_handler(); - chThdSleepUntilWindowed(t, t + TIME_US2I(USEC_OF_SEC(1.f/(SYS_TIME_FREQUENCY)))); + chThdSleepUntilWindowed(t, t + TIME_US2I(USEC_OF_SEC(1.f / (SYS_TIME_FREQUENCY)))); } } diff --git a/sw/airborne/arch/chibios/mcu_periph/uart_arch.c b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c index 6c70ce35d7..081a8f2a85 100644 --- a/sw/airborne/arch/chibios/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c @@ -998,13 +998,14 @@ void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud) */ void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx_enabled __attribute__((unused)), bool rx_enabled __attribute__((unused)), bool hw_flow_control __attribute__((unused))) {} - -#if defined STM32F7 +#if defined(STM32H7XX) +#define __USART_CR1_M USART_CR1_M0 +#elif defined(STM32F7XX) #define __USART_CR1_M USART_CR1_M_0 -#elif defined STM32F1 || defined STM32F4 || defined STM32F3 +#elif defined(STM32F1XX) || defined (STM32F3XX) || defined(STM32F4XX) #define __USART_CR1_M USART_CR1_M #else -#error unsupported board +#error Unsupported board #endif /** @@ -1049,7 +1050,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p, sdStart((SerialDriver *)(p->reg_addr), conf); } -#ifdef STM32F7 +#if defined(STM32F7XX) || defined(STM32H7XX) /** * Invert data logic */ @@ -1159,4 +1160,3 @@ void uart_send_message(struct uart_periph *p, long fd) // send signal to start transmission chSemSignal(init_struct->tx_sem); } - diff --git a/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.c b/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.c index 2144e0648d..b3077df01d 100644 --- a/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.c +++ b/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.c @@ -34,6 +34,48 @@ #include "modules/actuators/actuators_pwm.h" #include "mcu_periph/gpio.h" +/* Default timer base frequency is 1MHz */ +#ifndef PWM_FREQUENCY +#define PWM_FREQUENCY 1000000 +#endif + +/* Default servo update rate in Hz */ +#ifndef SERVO_HZ +#define SERVO_HZ 40 +#endif + +/* For each timer the period van be configured differently */ +#ifndef TIM1_SERVO_HZ +#define TIM1_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM2_SERVO_HZ +#define TIM2_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM3_SERVO_HZ +#define TIM3_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM4_SERVO_HZ +#define TIM4_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM5_SERVO_HZ +#define TIM5_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM8_SERVO_HZ +#define TIM8_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM9_SERVO_HZ +#define TIM9_SERVO_HZ SERVO_HZ +#endif +#ifndef TIM12_SERVO_HZ +#define TIM12_SERVO_HZ SERVO_HZ +#endif + +/** + * Print the configuration variables from the header + */ +PRINT_CONFIG_VAR(ACTUATORS_PWM_NB) +PRINT_CONFIG_VAR(PWM_FREQUENCY) +PRINT_CONFIG_VAR(SERVO_HZ) /** * CMD_TO_US() is depending on architecture @@ -60,35 +102,165 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; */ __attribute__((unused)) static void pwmpcb(PWMDriver *pwmp __attribute__((unused))) {} -#if PWM_CONF_TIM1 -static PWMConfig pwmcfg1 = PWM_CONF1_DEF; +#if STM32_PWM_USE_TIM1 +static PWMConfig pwmcfg1 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM1_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM2 -static PWMConfig pwmcfg2 = PWM_CONF2_DEF; +#if STM32_PWM_USE_TIM2 +static PWMConfig pwmcfg2 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM2_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM3 -static PWMConfig pwmcfg3 = PWM_CONF3_DEF; +#if STM32_PWM_USE_TIM3 +static PWMConfig pwmcfg3 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM3_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM4 -static PWMConfig pwmcfg4 = PWM_CONF4_DEF; +#if STM32_PWM_USE_TIM4 +static PWMConfig pwmcfg4 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM4_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM5 -static PWMConfig pwmcfg5 = PWM_CONF5_DEF; +#if STM32_PWM_USE_TIM5 +static PWMConfig pwmcfg5 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM5_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM8 -static PWMConfig pwmcfg8 = PWM_CONF8_DEF; +#if STM32_PWM_USE_TIM8 +static PWMConfig pwmcfg8 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM8_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM9 -static PWMConfig pwmcfg9 = PWM_CONF9_DEF; +#if STM32_PWM_USE_TIM9 +static PWMConfig pwmcfg9 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM9_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM10 -static PWMConfig pwmcfg10 = PWM_CONF10_DEF; +#if STM32_PWM_USE_TIM10 +static PWMConfig pwmcfg10 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM10_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM11 -static PWMConfig pwmcfg11 = PWM_CONF11_DEF; +#if STM32_PWM_USE_TIM11 +static PWMConfig pwmcfg11 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM11_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif -#if PWM_CONF_TIM12 -static PWMConfig pwmcfg12 = PWM_CONF12_DEF; +#if STM32_PWM_USE_TIM12 +static PWMConfig pwmcfg12 = { + .frequency = PWM_FREQUENCY, + .period = PWM_FREQUENCY/TIM12_SERVO_HZ, + .callback = NULL, + .channels = { + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + { PWM_OUTPUT_DISABLED, NULL }, + }, + .cr2 = 0, + .bdtr = 0, + .dier = 0 +}; #endif @@ -99,87 +271,104 @@ void actuators_pwm_arch_init(void) *----------------*/ #ifdef PWM_SERVO_0 gpio_setup_pin_af(PWM_SERVO_0_GPIO, PWM_SERVO_0_PIN, PWM_SERVO_0_AF, true); + PWM_SERVO_0_CONF.channels[PWM_SERVO_0_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_1 gpio_setup_pin_af(PWM_SERVO_1_GPIO, PWM_SERVO_1_PIN, PWM_SERVO_1_AF, true); + PWM_SERVO_1_CONF.channels[PWM_SERVO_1_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_2 gpio_setup_pin_af(PWM_SERVO_2_GPIO, PWM_SERVO_2_PIN, PWM_SERVO_2_AF, true); + PWM_SERVO_2_CONF.channels[PWM_SERVO_2_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_3 gpio_setup_pin_af(PWM_SERVO_3_GPIO, PWM_SERVO_3_PIN, PWM_SERVO_3_AF, true); + PWM_SERVO_3_CONF.channels[PWM_SERVO_3_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_4 gpio_setup_pin_af(PWM_SERVO_4_GPIO, PWM_SERVO_4_PIN, PWM_SERVO_4_AF, true); + PWM_SERVO_4_CONF.channels[PWM_SERVO_4_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_5 gpio_setup_pin_af(PWM_SERVO_5_GPIO, PWM_SERVO_5_PIN, PWM_SERVO_5_AF, true); + PWM_SERVO_5_CONF.channels[PWM_SERVO_5_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_6 gpio_setup_pin_af(PWM_SERVO_6_GPIO, PWM_SERVO_6_PIN, PWM_SERVO_6_AF, true); + PWM_SERVO_6_CONF.channels[PWM_SERVO_6_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_7 gpio_setup_pin_af(PWM_SERVO_7_GPIO, PWM_SERVO_7_PIN, PWM_SERVO_7_AF, true); + PWM_SERVO_7_CONF.channels[PWM_SERVO_7_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_8 gpio_setup_pin_af(PWM_SERVO_8_GPIO, PWM_SERVO_8_PIN, PWM_SERVO_8_AF, true); + PWM_SERVO_8_CONF.channels[PWM_SERVO_8_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_9 gpio_setup_pin_af(PWM_SERVO_9_GPIO, PWM_SERVO_9_PIN, PWM_SERVO_9_AF, true); + PWM_SERVO_9_CONF.channels[PWM_SERVO_9_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_10 gpio_setup_pin_af(PWM_SERVO_10_GPIO, PWM_SERVO_10_PIN, PWM_SERVO_10_AF, true); + PWM_SERVO_10_CONF.channels[PWM_SERVO_10_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_11 gpio_setup_pin_af(PWM_SERVO_11_GPIO, PWM_SERVO_11_PIN, PWM_SERVO_11_AF, true); + PWM_SERVO_11_CONF.channels[PWM_SERVO_11_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_12 gpio_setup_pin_af(PWM_SERVO_12_GPIO, PWM_SERVO_12_PIN, PWM_SERVO_12_AF, true); + PWM_SERVO_12_CONF.channels[PWM_SERVO_12_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_13 gpio_setup_pin_af(PWM_SERVO_13_GPIO, PWM_SERVO_13_PIN, PWM_SERVO_13_AF, true); + PWM_SERVO_13_CONF.channels[PWM_SERVO_13_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_14 gpio_setup_pin_af(PWM_SERVO_14_GPIO, PWM_SERVO_14_PIN, PWM_SERVO_14_AF, true); + PWM_SERVO_14_CONF.channels[PWM_SERVO_14_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_15 gpio_setup_pin_af(PWM_SERVO_15_GPIO, PWM_SERVO_15_PIN, PWM_SERVO_15_AF, true); + PWM_SERVO_15_CONF.channels[PWM_SERVO_15_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif #ifdef PWM_SERVO_16 gpio_setup_pin_af(PWM_SERVO_16_GPIO, PWM_SERVO_16_PIN, PWM_SERVO_16_AF, true); + PWM_SERVO_16_CONF.channels[PWM_SERVO_16_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH; #endif /*--------------- * Configure PWM *---------------*/ -#if PWM_CONF_TIM1 +#if STM32_PWM_USE_TIM1 pwmStart(&PWMD1, &pwmcfg1); #endif -#if PWM_CONF_TIM2 +#if STM32_PWM_USE_TIM2 pwmStart(&PWMD2, &pwmcfg2); #endif -#if PWM_CONF_TIM3 +#if STM32_PWM_USE_TIM3 pwmStart(&PWMD3, &pwmcfg3); #endif -#if PWM_CONF_TIM4 +#if STM32_PWM_USE_TIM4 pwmStart(&PWMD4, &pwmcfg4); #endif -#if PWM_CONF_TIM5 +#if STM32_PWM_USE_TIM5 pwmStart(&PWMD5, &pwmcfg5); #endif -#if PWM_CONF_TIM8 +#if STM32_PWM_USE_TIM8 pwmStart(&PWMD8, &pwmcfg8); #endif -#if PWM_CONF_TIM9 +#if STM32_PWM_USE_TIM9 pwmStart(&PWMD9, &pwmcfg9); #endif -#if PWM_CONF_TIM10 +#if STM32_PWM_USE_TIM10 pwmStart(&PWMD10, &pwmcfg10); #endif -#if PWM_CONF_TIM11 +#if STM32_PWM_USE_TIM11 pwmStart(&PWMD11, &pwmcfg11); #endif -#if PWM_CONF_TIM12 +#if STM32_PWM_USE_TIM12 pwmStart(&PWMD12, &pwmcfg12); #endif } diff --git a/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.h b/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.h index 004f7c1e85..7abf214ae2 100644 --- a/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.h +++ b/sw/airborne/arch/chibios/modules/actuators/actuators_pwm_arch.h @@ -42,42 +42,6 @@ #define ACTUATORS_PWM_NB 8 #endif -/* Default timer base frequency is 1MHz */ -#ifndef PWM_FREQUENCY -#define PWM_FREQUENCY 1000000 -#endif - -/** Default servo update rate in Hz */ -#ifndef SERVO_HZ -#define SERVO_HZ 40 -#endif - -// Update rate can be adapted for each timer -#ifndef TIM1_SERVO_HZ -#define TIM1_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM2_SERVO_HZ -#define TIM2_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM3_SERVO_HZ -#define TIM3_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM4_SERVO_HZ -#define TIM4_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM5_SERVO_HZ -#define TIM5_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM8_SERVO_HZ -#define TIM8_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM9_SERVO_HZ -#define TIM9_SERVO_HZ SERVO_HZ -#endif -#ifndef TIM12_SERVO_HZ -#define TIM12_SERVO_HZ SERVO_HZ -#endif - extern int32_t actuators_pwm_values[ACTUATORS_PWM_NB]; extern void actuators_pwm_commit(void); diff --git a/sw/airborne/arch/chibios/modules/core/rtos_mon_arch.c b/sw/airborne/arch/chibios/modules/core/rtos_mon_arch.c index 6232b7a073..e97c4541d7 100644 --- a/sw/airborne/arch/chibios/modules/core/rtos_mon_arch.c +++ b/sw/airborne/arch/chibios/modules/core/rtos_mon_arch.c @@ -49,88 +49,91 @@ typedef struct _ThreadCpuInfo { } ThreadCpuInfo ; -static void stampThreadCpuInfo (ThreadCpuInfo *ti) +static void stampThreadCpuInfo(ThreadCpuInfo *ti) { const thread_t *tp = chRegFirstThread(); - uint32_t idx=0; + uint32_t idx = 0; - ti->totalTicks =0; + ti->totalTicks = 0; do { ti->ticks[idx] = (float) tp->stats.cumulative; ti->totalTicks += ti->ticks[idx]; - tp = chRegNextThread ((thread_t *)tp); + tp = chRegNextThread((thread_t *)tp); idx++; } while ((tp != NULL) && (idx < RTOS_MON_MAX_THREADS)); - ti->totalISRTicks = ch.kernel_stats.m_crit_isr.cumulative; + ti->totalISRTicks = ch0.kernel_stats.m_crit_isr.cumulative; ti->totalTicks += ti->totalISRTicks; tp = chRegFirstThread(); - idx=0; + idx = 0; do { - ti->cpu[idx] = (ti->ticks[idx]*100.f) / ti->totalTicks; - tp = chRegNextThread ((thread_t *)tp); + ti->cpu[idx] = (ti->ticks[idx] * 100.f) / ti->totalTicks; + tp = chRegNextThread((thread_t *)tp); idx++; } while ((tp != NULL) && (idx < RTOS_MON_MAX_THREADS)); } -static float stampThreadGetCpuPercent (const ThreadCpuInfo *ti, const uint32_t idx) +static float stampThreadGetCpuPercent(const ThreadCpuInfo *ti, const uint32_t idx) { - if (idx >= RTOS_MON_MAX_THREADS) + if (idx >= RTOS_MON_MAX_THREADS) { return -1.f; + } return ti->cpu[idx]; } -static float stampISRGetCpuPercent (const ThreadCpuInfo *ti) +static float stampISRGetCpuPercent(const ThreadCpuInfo *ti) { return ti->totalISRTicks * 100.0f / ti->totalTicks; } -static void cmd_threads(BaseSequentialStream *lchp, int argc,const char * const argv[]) { +static void cmd_threads(BaseSequentialStream *lchp, int argc, const char *const argv[]) +{ static const char *states[] = {CH_STATE_NAMES}; thread_t *tp = chRegFirstThread(); (void)argv; (void)argc; - float totalTicks=0; - float idleTicks=0; + float totalTicks = 0; + float idleTicks = 0; static ThreadCpuInfo threadCpuInfo = { - .ticks = {[0 ... RTOS_MON_MAX_THREADS-1] = 0.f}, - .cpu = {[0 ... RTOS_MON_MAX_THREADS-1] =-1.f}, + .ticks = {[0 ... RTOS_MON_MAX_THREADS - 1] = 0.f}, + .cpu = {[0 ... RTOS_MON_MAX_THREADS - 1] = -1.f}, .totalTicks = 0.f, .totalISRTicks = 0.f }; - stampThreadCpuInfo (&threadCpuInfo); + stampThreadCpuInfo(&threadCpuInfo); - chprintf (lchp, " addr stack frestk prio refs state time \t percent name\r\n"); - uint32_t idx=0; + chprintf(lchp, " addr stack frestk prio refs state time \t percent name\r\n"); + uint32_t idx = 0; do { - chprintf (lchp, "%.8lx %.8lx %6lu %4lu %4lu %9s %9lu %.2f%% \t%s\r\n", - (uint32_t)tp, (uint32_t)tp->ctx.sp, - get_stack_free (tp), - (uint32_t)tp->hdr.pqueue.prio, (uint32_t)(tp->refs - 1), - states[tp->state], - (uint32_t)RTC2MS(STM32_SYSCLK, tp->stats.cumulative), - stampThreadGetCpuPercent (&threadCpuInfo, idx), - chRegGetThreadNameX(tp)); + chprintf(lchp, "%.8lx %.8lx %6lu %4lu %4lu %9s %9lu %.2f%% \t%s\r\n", + (uint32_t)tp, (uint32_t)tp->ctx.sp, + get_stack_free(tp), + (uint32_t)tp->hdr.pqueue.prio, (uint32_t)(tp->refs - 1), + states[tp->state], + (uint32_t)RTC2MS(STM32_SYSCLK, tp->stats.cumulative), + stampThreadGetCpuPercent(&threadCpuInfo, idx), + chRegGetThreadNameX(tp)); - totalTicks+= (float)tp->stats.cumulative; - if (strcmp(chRegGetThreadNameX(tp), "idle") == 0) + totalTicks += (float)tp->stats.cumulative; + if (strcmp(chRegGetThreadNameX(tp), "idle") == 0) { idleTicks = (float)tp->stats.cumulative; - tp = chRegNextThread ((thread_t *)tp); + } + tp = chRegNextThread((thread_t *)tp); idx++; } while (tp != NULL); - totalTicks += ch.kernel_stats.m_crit_isr.cumulative; - const float idlePercent = (idleTicks*100.f)/totalTicks; + totalTicks += ch0.kernel_stats.m_crit_isr.cumulative; + const float idlePercent = (idleTicks * 100.f) / totalTicks; const float cpuPercent = 100.f - idlePercent; - chprintf (lchp, "Interrupt Service Routine \t\t %9lu %.2f%% \tISR\r\n", - (uint32_t)RTC2MS(STM32_SYSCLK,threadCpuInfo.totalISRTicks), - stampISRGetCpuPercent(&threadCpuInfo)); - chprintf (lchp, "\r\ncpu load = %.2f%%\r\n", cpuPercent); + chprintf(lchp, "Interrupt Service Routine \t\t %9lu %.2f%% \tISR\r\n", + (uint32_t)RTC2MS(STM32_SYSCLK, threadCpuInfo.totalISRTicks), + stampISRGetCpuPercent(&threadCpuInfo)); + chprintf(lchp, "\r\ncpu load = %.2f%%\r\n", cpuPercent); } -static void cmd_rtos_mon(shell_stream_t *sh, int argc, const char * const argv[]) +static void cmd_rtos_mon(shell_stream_t *sh, int argc, const char *const argv[]) { (void) argv; if (argc > 0) { @@ -148,7 +151,7 @@ static void cmd_rtos_mon(shell_stream_t *sh, int argc, const char * const argv[] chprintf(sh, " thread names: %s\r\n", rtos_mon.thread_names); for (int i = 0; i < rtos_mon.thread_counter; i++) { chprintf(sh, " thread %d load: %0.1f, free stack: %d\r\n", i, - (float)rtos_mon.thread_load[i] / 10.f, rtos_mon.thread_free_stack[i]); + (float)rtos_mon.thread_load[i] / 10.f, rtos_mon.thread_free_stack[i]); } chprintf(sh, " CPU time: %.2f\r\n", rtos_mon.cpu_time); } @@ -167,9 +170,11 @@ void rtos_mon_periodic_arch(void) { int i; size_t total_fragments, total_fragmented_free_space, largest_free_block; + memory_area_t area; total_fragments = chHeapStatus(NULL, &total_fragmented_free_space, &largest_free_block); + chCoreGetStatusX(&area); - rtos_mon.core_free_memory = chCoreGetStatusX(); + rtos_mon.core_free_memory = area.size; rtos_mon.heap_fragments = total_fragments; rtos_mon.heap_largest = largest_free_block; rtos_mon.heap_free_memory = total_fragmented_free_space; @@ -184,7 +189,7 @@ void rtos_mon_periodic_arch(void) tp = chRegFirstThread(); do { // add beginning of thread name to buffer - for (i = 0; i < RTOS_MON_NAME_LEN-1 && tp->name[i] != '\0'; i++) { + for (i = 0; i < RTOS_MON_NAME_LEN - 1 && tp->name[i] != '\0'; i++) { rtos_mon.thread_names[rtos_mon.thread_name_idx++] = tp->name[i]; } rtos_mon.thread_names[rtos_mon.thread_name_idx++] = ';'; @@ -206,7 +211,7 @@ void rtos_mon_periodic_arch(void) rtos_mon.thread_counter++; } while (tp != NULL && rtos_mon.thread_counter < RTOS_MON_MAX_THREADS); // sum the time spent in ISR - sum += ch.kernel_stats.m_crit_isr.cumulative; + sum += ch0.kernel_stats.m_crit_isr.cumulative; // store individual thread load (as centi-percent integer, i.e. (th_time/sum)*10*100) for (i = 0; i < rtos_mon.thread_counter; i ++) { rtos_mon.thread_load[i] = (uint16_t)(1000.f * (float)thread_p_time[i] / sum); @@ -222,9 +227,10 @@ static uint16_t get_stack_free(const thread_t *tp) { int32_t index = 0; extern const uint8_t __ram0_end__; - unsigned long long *stkAdr = (unsigned long long *) ((uint8_t *) tp->wabase); - while ((stkAdr[index] == 0x5555555555555555) && ( ((uint8_t *) &(stkAdr[index])) < &__ram0_end__)) + unsigned long long *stkAdr = (unsigned long long *)((uint8_t *) tp->wabase); + while ((stkAdr[index] == 0x5555555555555555) && (((uint8_t *) & (stkAdr[index])) < &__ram0_end__)) { index++; + } const int32_t freeBytes = index * (int32_t) sizeof(long long); return (uint16_t)freeBytes; } diff --git a/sw/airborne/arch/chibios/modules/core/shell_arch.c b/sw/airborne/arch/chibios/modules/core/shell_arch.c index 371f0f7913..270a00696e 100644 --- a/sw/airborne/arch/chibios/modules/core/shell_arch.c +++ b/sw/airborne/arch/chibios/modules/core/shell_arch.c @@ -33,19 +33,25 @@ * Basic static commands * *************************/ -static void cmd_mem(BaseSequentialStream *lchp, int argc, const char * const argv[]) +static void cmd_mem(BaseSequentialStream *lchp, int argc, const char *const argv[]) { + size_t n, total, largest; + memory_area_t area; + (void)argv; if (argc > 0) { chprintf(lchp, "Usage: mem\r\n"); return; } - - chprintf (lchp, "core free memory : %u bytes\r\n", chCoreGetStatusX()); - //chprintf (lchp, "heap free memory : %u bytes\r\n", getHeapFree()); + n = chHeapStatus(NULL, &total, &largest); + chCoreGetStatusX(&area); + chprintf(lchp, "core free memory : %u bytes\r\n", area.size); + chprintf(lchp, "heap fragments : %u\r\n", n); + chprintf(lchp, "heap free total : %u bytes\r\n", total); + chprintf(lchp, "heap free largest: %u bytes\r\n", largest); } -static void cmd_abi(BaseSequentialStream *lchp, int argc, const char * const argv[]) +static void cmd_abi(BaseSequentialStream *lchp, int argc, const char *const argv[]) { (void)argv; if (argc > 0) { @@ -93,10 +99,10 @@ void shell_add_entry(char *cmd_name, shell_cmd_t *cmd) void shell_init_arch(void) { // This should be called after mcu periph init - shell_cfg.sc_channel = (BaseSequentialStream *) (SHELL_DEV.reg_addr); + shell_cfg.sc_channel = (BaseSequentialStream *)(SHELL_DEV.reg_addr); shellInit(); - thread_t * shelltp = shellCreateFromHeap(&shell_cfg, 2048U, NORMALPRIO); + thread_t *shelltp = shellCreateFromHeap(&shell_cfg, 2048U, NORMALPRIO); if (shelltp == NULL) { chSysHalt("fail starting shell"); } diff --git a/sw/airborne/arch/chibios/modules/tlsf/tlsf_malloc_arch.h b/sw/airborne/arch/chibios/modules/tlsf/tlsf_malloc_arch.h index 11c31e609c..45a1ade634 100644 --- a/sw/airborne/arch/chibios/modules/tlsf/tlsf_malloc_arch.h +++ b/sw/airborne/arch/chibios/modules/tlsf/tlsf_malloc_arch.h @@ -33,10 +33,10 @@ #define HEAP_CCM ccmHeap -// F7 has more than twice RAM than others families -#if defined STM32F7XX +// F7/H7 has more than twice RAM than others families +#if defined(STM32F7XX) || defined(STM32H7XX) #define HEAP_CCM_SIZE 65536 -#else +#else #define HEAP_CCM_SIZE 16384 #endif #define HEAP_CCM_SECTION FAST_SECTION diff --git a/sw/airborne/arch/chibios/modules/uavcan/uavcan.c b/sw/airborne/arch/chibios/modules/uavcan/uavcan.c index 5bdc9f62b8..9c0fee744d 100644 --- a/sw/airborne/arch/chibios/modules/uavcan/uavcan.c +++ b/sw/airborne/arch/chibios/modules/uavcan/uavcan.c @@ -50,11 +50,8 @@ static THD_WORKING_AREA(uavcan1_tx_wa, 1024 * 2); struct uavcan_iface_t uavcan1 = { .can_driver = &CAND1, - .can_cfg = { - CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP, - CAN_BTR_SJW(0) | CAN_BTR_TS2(1) | - CAN_BTR_TS1(14) | CAN_BTR_BRP((STM32_PCLK1 / 18) / UAVCAN_CAN1_BAUDRATE - 1) - }, + .can_baudrate = UAVCAN_CAN1_BAUDRATE, + .can_cfg = {0}, .thread_rx_wa = uavcan1_rx_wa, .thread_rx_wa_size = sizeof(uavcan1_rx_wa), .thread_tx_wa = uavcan1_tx_wa, @@ -79,11 +76,8 @@ static THD_WORKING_AREA(uavcan2_tx_wa, 1024 * 2); struct uavcan_iface_t uavcan2 = { .can_driver = &CAND2, - .can_cfg = { - CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP, - CAN_BTR_SJW(0) | CAN_BTR_TS2(1) | - CAN_BTR_TS1(14) | CAN_BTR_BRP((STM32_PCLK1 / 18) / UAVCAN_CAN2_BAUDRATE - 1) - }, + .can_baudrate = UAVCAN_CAN2_BAUDRATE, + .can_cfg = {0}, .thread_rx_wa = uavcan2_rx_wa, .thread_rx_wa_size = sizeof(uavcan2_rx_wa), .thread_tx_wa = uavcan2_tx_wa, @@ -118,11 +112,20 @@ static THD_FUNCTION(uavcan_rx, p) const uint32_t timestamp = TIME_I2US(chVTGetSystemTimeX()); memcpy(rx_frame.data, rx_msg.data8, 8); rx_frame.data_len = rx_msg.DLC; +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + if (rx_msg.common.XTD) { + rx_frame.id = CANARD_CAN_FRAME_EFF | rx_msg.ext.EID; + } else { + rx_frame.id = rx_msg.std.SID; + } +#else if (rx_msg.IDE) { rx_frame.id = CANARD_CAN_FRAME_EFF | rx_msg.EID; } else { rx_frame.id = rx_msg.SID; } +#endif + // Let canard handle the frame canardHandleRxFrame(&iface->canard, &rx_frame, timestamp); } @@ -161,11 +164,18 @@ static THD_FUNCTION(uavcan_tx, p) chMtxLock(&iface->mutex); for (const CanardCANFrame *txf = NULL; (txf = canardPeekTxQueue(&iface->canard)) != NULL;) { CANTxFrame tx_msg; - tx_msg.DLC = txf->data_len; memcpy(tx_msg.data8, txf->data, 8); +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + tx_msg.DLC = txf->data_len; // TODO fixme for FDCAN (>8 bytes) + tx_msg.ext.EID = txf->id & CANARD_CAN_EXT_ID_MASK; + tx_msg.common.XTD = 1; + tx_msg.common.RTR = 0; +#else + tx_msg.DLC = txf->data_len; tx_msg.EID = txf->id & CANARD_CAN_EXT_ID_MASK; tx_msg.IDE = CAN_IDE_EXT; tx_msg.RTR = CAN_RTR_DATA; +#endif if (!canTryTransmitI(iface->can_driver, CAN_ANY_MAILBOX, &tx_msg)) { err_cnt = 0; canardPopTxQueue(&iface->canard); @@ -224,11 +234,130 @@ static bool shouldAcceptTransfer(const CanardInstance *ins __attribute__((unused return false; } +/** + * Try to compute the timing registers for the can interface and set the configuration + */ +static bool uavcanConfigureIface(struct uavcan_iface_t *iface) +{ + if (iface->can_baudrate < 1) { + return false; + } + + // Hardware configurationn +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + const uint32_t pclk = STM32_FDCANCLK; +#else + const uint32_t pclk = STM32_PCLK1; +#endif + static const int MaxBS1 = 16; + static const int MaxBS2 = 8; + + /* + * Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG + * CAN in Automation, 2003 + * + * According to the source, optimal quanta per bit are: + * Bitrate Optimal Maximum + * 1000 kbps 8 10 + * 500 kbps 16 17 + * 250 kbps 16 17 + * 125 kbps 16 17 + */ + const int max_quanta_per_bit = (iface->can_baudrate >= 1000000) ? 10 : 17; + static const int MaxSamplePointLocation = 900; + + /* + * Computing (prescaler * BS): + * BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2)) -- See the Reference Manual + * BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2)) -- Simplified + * let: + * BS = 1 + BS1 + BS2 -- Number of time quanta per bit + * PRESCALER_BS = PRESCALER * BS + * ==> + * PRESCALER_BS = PCLK / BITRATE + */ + const uint32_t prescaler_bs = pclk / iface->can_baudrate; + +// Searching for such prescaler value so that the number of quanta per bit is highest. + uint8_t bs1_bs2_sum = max_quanta_per_bit - 1; + while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0) { + if (bs1_bs2_sum <= 2) { + return false; // No solution + } + bs1_bs2_sum--; + } + + const uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum); + if ((prescaler < 1U) || (prescaler > 1024U)) { + return false; // No solution + } + + /* + * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum. + * We need to find the values so that the sample point is as close as possible to the optimal value. + * + * Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2] (* Where 7/8 is 0.875, the recommended sample point location *) + * {{bs2 -> (1 + bs1)/7}} + * + * Hence: + * bs2 = (1 + bs1) / 7 + * bs1 = (7 * bs1_bs2_sum - 1) / 8 + * + * Sample point location can be computed as follows: + * Sample point location = (1 + bs1) / (1 + bs1 + bs2) + * + * Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one: + * - With rounding to nearest + * - With rounding to zero + */ +// First attempt with rounding to nearest + uint8_t bs1 = ((7 * bs1_bs2_sum - 1) + 4) / 8; + uint8_t bs2 = bs1_bs2_sum - bs1; + uint16_t sample_point_permill = 1000 * (1 + bs1) / (1 + bs1 + bs2); + +// Second attempt with rounding to zero + if (sample_point_permill > MaxSamplePointLocation) { + bs1 = (7 * bs1_bs2_sum - 1) / 8; + bs2 = bs1_bs2_sum - bs1; + sample_point_permill = 1000 * (1 + bs1) / (1 + bs1 + bs2); + } + + /* + * Final validation + * Helpful Python: + * def sample_point_from_btr(x): + * assert 0b0011110010000000111111000000000 & x == 0 + * ts2,ts1,brp = (x>>20)&7, (x>>16)&15, x&511 + * return (1+ts1+1)/(1+ts1+1+ts2+1) + * + */ + if ((iface->can_baudrate != (pclk / (prescaler * (1 + bs1 + bs2)))) || (bs1 < 1) || (bs1 > MaxBS1) || (bs2 < 1) + || (bs2 > MaxBS2)) { + return false; + } + + // Configure the interface +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + iface->can_cfg.NBTP = (0 << FDCAN_NBTP_NSJW_Pos) | ((bs1 - 1) << FDCAN_NBTP_NTSEG1_Pos) | (( + bs2 - 1) << FDCAN_NBTP_NTSEG2_Pos) | ((prescaler - 1) << FDCAN_NBTP_NBRP_Pos); + iface->can_cfg.CCCR = FDCAN_CCCR_FDOE | FDCAN_CCCR_BRSE; +#else + iface->can_cfg.mcr = CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP; + iface->can_cfg.btr = CAN_BTR_SJW(0) | CAN_BTR_TS1(bs1 - 1) | CAN_BTR_TS2(bs2 - 1) | CAN_BTR_BRP(prescaler - 1); +#endif + return true; +} + /** * Initialize uavcan interface */ static void uavcanInitIface(struct uavcan_iface_t *iface) { + // First try to configure abort if failed + if (!uavcanConfigureIface(iface)) { + return; + } + // Initialize mutexes/events for multithread locking chMtxObjectInit(&iface->mutex); chEvtObjectInit(&iface->tx_request); @@ -254,9 +383,25 @@ static void uavcanInitIface(struct uavcan_iface_t *iface) void uavcan_init(void) { #if UAVCAN_USE_CAN1 +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + // Configure the RAM + uavcan1.can_cfg.RXF0C = (32 << FDCAN_RXF0C_F0S_Pos) | (0 << FDCAN_RXF0C_F0SA_Pos); + uavcan1.can_cfg.RXF1C = (32 << FDCAN_RXF1C_F1S_Pos) | (128 << FDCAN_RXF1C_F1SA_Pos); + uavcan1.can_cfg.TXBC = (32 << FDCAN_TXBC_TFQS_Pos) | (256 << FDCAN_TXBC_TBSA_Pos); + uavcan1.can_cfg.TXESC = 0x000; // 8 Byte mode only (4 words per message) + uavcan1.can_cfg.RXESC = 0x000; // 8 Byte mode only (4 words per message) +#endif uavcanInitIface(&uavcan1); #endif #if UAVCAN_USE_CAN2 +#if defined(STM32_CAN_USE_FDCAN1) || defined(STM32_CAN_USE_FDCAN2) + // Configure the RAM + uavcan2.can_cfg.RXF0C = (32 << FDCAN_RXF0C_F0S_Pos) | (384 << FDCAN_RXF0C_F0SA_Pos); + uavcan2.can_cfg.RXF1C = (32 << FDCAN_RXF1C_F1S_Pos) | (512 << FDCAN_RXF1C_F1SA_Pos); + uavcan2.can_cfg.TXBC = (32 << FDCAN_TXBC_TFQS_Pos) | (640 << FDCAN_TXBC_TBSA_Pos); + uavcan2.can_cfg.TXESC = 0x000; // 8 Byte mode only (4 words per message) + uavcan2.can_cfg.RXESC = 0x000; // 8 Byte mode only (4 words per message) +#endif uavcanInitIface(&uavcan2); #endif } diff --git a/sw/airborne/arch/chibios/modules/uavcan/uavcan.h b/sw/airborne/arch/chibios/modules/uavcan/uavcan.h index db9ceff370..9b75adb147 100644 --- a/sw/airborne/arch/chibios/modules/uavcan/uavcan.h +++ b/sw/airborne/arch/chibios/modules/uavcan/uavcan.h @@ -33,6 +33,7 @@ /** uavcan interface structure */ struct uavcan_iface_t { CANDriver *can_driver; + uint32_t can_baudrate; CANConfig can_cfg; event_source_t tx_request; diff --git a/sw/airborne/autopilot.c b/sw/airborne/autopilot.c index b6a63625b5..e306a5cb86 100644 --- a/sw/airborne/autopilot.c +++ b/sw/airborne/autopilot.c @@ -98,9 +98,9 @@ static void send_minimal_com(struct transport_tx *trans, struct link_device *dev uint8_t gps_fix = 0; #endif pprz_msg_send_MINIMAL_COM(trans, dev, AC_ID, - &lat, &lon, &hmsl, &gspeed, &course, &climb, - &electrical.vsupply, &throttle, &autopilot.mode, - &nav_block, &gps_fix, &autopilot.flight_time); + &lat, &lon, &hmsl, &gspeed, &course, &climb, + &electrical.vsupply, &throttle, &autopilot.mode, + &nav_block, &gps_fix, &autopilot.flight_time); } void autopilot_init(void) diff --git a/sw/airborne/boards/apogee/chibios/v1.0/board.c b/sw/airborne/boards/apogee/chibios/v1.0/board.c deleted file mode 100644 index 67bf8a4a25..0000000000 --- a/sw/airborne/boards/apogee/chibios/v1.0/board.c +++ /dev/null @@ -1,278 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return !palReadLine(LINE_SDIO_DETECT); -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { -} - -/** Energy saving procedure for SD log closing - */ -void mcu_periph_energy_save(void) -{ - palSetLineMode(LINE_LED1, PAL_MODE_INPUT); - palSetLineMode(LINE_LED2, PAL_MODE_INPUT); - palSetLineMode(LINE_LED3, PAL_MODE_INPUT); - palSetLineMode(LINE_LED4, PAL_MODE_INPUT); - palSetLineMode(LINE_SPI1_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX1, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX2, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX3, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX4, PAL_MODE_INPUT); -} - diff --git a/sw/airborne/boards/apogee/chibios/v1.0/board.cfg b/sw/airborne/boards/apogee/chibios/v1.0/board.cfg index 60858c70d0..694fe1edf6 100644 --- a/sw/airborne/boards/apogee/chibios/v1.0/board.cfg +++ b/sw/airborne/boards/apogee/chibios/v1.0/board.cfg @@ -8,9 +8,7 @@ HEADER Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at - http://www.apache.org/licenses/LICENSE-2.0 - Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -53,11 +51,11 @@ HEADER */ - /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* @@ -135,6 +133,8 @@ HEADER #define LED_8_GPIO_ON gpio_set #define LED_8_GPIO_OFF gpio_clear +/* Power Switch, on PB12 */ +#define POWER_SWITCH_GPIO GPIOB,GPIO12 /* Pint to set Uart2 RX polarity, on PB13, output high inverts, low doesn't */ #define RC_POLARITY_GPIO_PORT GPIOB @@ -193,14 +193,12 @@ HEADER #endif #if USE_PWM0 #define PWM_SERVO_0 0 -#define PWM_SERVO_0_GPIO GPIOB -#define PWM_SERVO_0_PIN GPIO0 -#define PWM_SERVO_0_AF GPIO_AF2 -#define PWM_SERVO_0_DRIVER PWMD3 -#define PWM_SERVO_0_CHANNEL 2 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_GPIO PAL_PORT(LINE_SERVO0) +#define PWM_SERVO_0_PIN PAL_PAD(LINE_SERVO0) +#define PWM_SERVO_0_AF AF_LINE_SERVO0 +#define PWM_SERVO_0_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO0_TIM) +#define PWM_SERVO_0_CHANNEL (SERVO0_TIM_CH-1) +#define PWM_SERVO_0_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO0_TIM) #endif #ifndef USE_PWM1 @@ -208,14 +206,12 @@ HEADER #endif #if USE_PWM1 #define PWM_SERVO_1 1 -#define PWM_SERVO_1_GPIO GPIOA -#define PWM_SERVO_1_PIN GPIO2 -#define PWM_SERVO_1_AF GPIO_AF1 -#define PWM_SERVO_1_DRIVER PWMD2 -#define PWM_SERVO_1_CHANNEL 2 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1) +#define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1) +#define PWM_SERVO_1_AF AF_LINE_SERVO1 +#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM) +#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1) +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM) #endif #ifndef USE_PWM2 @@ -223,14 +219,12 @@ HEADER #endif #if USE_PWM2 #define PWM_SERVO_2 2 -#define PWM_SERVO_2_GPIO GPIOB -#define PWM_SERVO_2_PIN GPIO5 -#define PWM_SERVO_2_AF GPIO_AF2 -#define PWM_SERVO_2_DRIVER PWMD3 -#define PWM_SERVO_2_CHANNEL 1 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2) +#define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2) +#define PWM_SERVO_2_AF AF_LINE_SERVO2 +#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM) +#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1) +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM) #endif #ifndef USE_PWM3 @@ -238,14 +232,12 @@ HEADER #endif #if USE_PWM3 #define PWM_SERVO_3 3 -#define PWM_SERVO_3_GPIO GPIOB -#define PWM_SERVO_3_PIN GPIO4 -#define PWM_SERVO_3_AF GPIO_AF2 -#define PWM_SERVO_3_DRIVER PWMD3 -#define PWM_SERVO_3_CHANNEL 0 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3) +#define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3) +#define PWM_SERVO_3_AF AF_LINE_SERVO3 +#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM) +#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1) +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM) #endif #ifndef USE_PWM4 @@ -253,14 +245,12 @@ HEADER #endif #if USE_PWM4 #define PWM_SERVO_4 4 -#define PWM_SERVO_4_GPIO GPIOB -#define PWM_SERVO_4_PIN GPIO3 -#define PWM_SERVO_4_AF GPIO_AF1 -#define PWM_SERVO_4_DRIVER PWMD2 -#define PWM_SERVO_4_CHANNEL 1 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4) +#define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4) +#define PWM_SERVO_4_AF AF_LINE_SERVO4 +#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM) +#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1) +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM) #endif #ifndef USE_PWM5 @@ -268,66 +258,101 @@ HEADER #endif #if USE_PWM5 #define PWM_SERVO_5 5 -#define PWM_SERVO_5_GPIO GPIOA -#define PWM_SERVO_5_PIN GPIO15 -#define PWM_SERVO_5_AF GPIO_AF1 -#define PWM_SERVO_5_DRIVER PWMD2 -#define PWM_SERVO_5_CHANNEL 0 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5) +#define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5) +#define PWM_SERVO_5_AF AF_LINE_SERVO5 +#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM) +#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1) +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM) #endif #if USE_PWM6 #define PWM_SERVO_6 6 -#define PWM_SERVO_6_GPIO GPIOB -#define PWM_SERVO_6_PIN GPIO1 -#define PWM_SERVO_6_AF GPIO_AF2 -#define PWM_SERVO_6_DRIVER PWMD3 -#define PWM_SERVO_6_CHANNEL 3 -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6) +#define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6) +#define PWM_SERVO_6_AF AF_LINE_SERVO6 +#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM) +#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1) +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM) #endif - -#ifdef STM32_PWM_USE_TIM2 -#define PWM_CONF_TIM2 STM32_PWM_USE_TIM2 -#else -#define PWM_CONF_TIM2 1 +/** + * DSHOT + */ +#ifndef DSHOT_TELEMETRY_DEV +#define DSHOT_TELEMETRY_DEV NULL #endif -#define PWM_CONF2_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM2_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ +#ifndef USE_DSHOT_TIM2 +#define USE_DSHOT_TIM2 1 +#endif +#ifndef USE_DSHOT_TIM3 +#define USE_DSHOT_TIM3 1 +#endif +#if USE_DSHOT_TIM2 // Servo 1, 4, 5 +#define DSHOT_SERVO_1 1 +#define DSHOT_SERVO_1_GPIO GPIOA +#define DSHOT_SERVO_1_PIN GPIO2 +#define DSHOT_SERVO_1_AF GPIO_AF1 +#define DSHOT_SERVO_1_DRIVER DSHOTD2 +#define DSHOT_SERVO_1_CHANNEL 2 +#define DSHOT_SERVO_4 4 +#define DSHOT_SERVO_4_GPIO GPIOB +#define DSHOT_SERVO_4_PIN GPIO3 +#define DSHOT_SERVO_4_AF GPIO_AF1 +#define DSHOT_SERVO_4_DRIVER DSHOTD2 +#define DSHOT_SERVO_4_CHANNEL 1 +#define DSHOT_SERVO_5 5 +#define DSHOT_SERVO_5_GPIO GPIOA +#define DSHOT_SERVO_5_PIN GPIO15 +#define DSHOT_SERVO_5_AF GPIO_AF1 +#define DSHOT_SERVO_5_DRIVER DSHOTD2 +#define DSHOT_SERVO_5_CHANNEL 0 +#define DSHOT_CONF_TIM2 1 +#define DSHOT_CONF2_DEF { \ + .dma_stream = STM32_PWM2_UP_DMA_STREAM, \ + .dma_channel = STM32_PWM2_UP_DMA_CHANNEL, \ + .pwmp = &PWMD2, \ + .tlm_sd = DSHOT_TELEMETRY_DEV, \ + .dma_buf = &dshot2DmaBuffer, \ } - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 #endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_0_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ +#if USE_DSHOT_TIM3 // Servo 0,2,3,6 +#define DSHOT_SERVO_0 0 +#define DSHOT_SERVO_0_GPIO GPIOB +#define DSHOT_SERVO_0_PIN GPIO0 +#define DSHOT_SERVO_0_AF GPIO_AF2 +#define DSHOT_SERVO_0_DRIVER DSHOTD3 +#define DSHOT_SERVO_0_CHANNEL 2 +#define DSHOT_SERVO_2 2 +#define DSHOT_SERVO_2_GPIO GPIOB +#define DSHOT_SERVO_2_PIN GPIO5 +#define DSHOT_SERVO_2_AF GPIO_AF2 +#define DSHOT_SERVO_2_DRIVER DSHOTD3 +#define DSHOT_SERVO_2_CHANNEL 1 +#define DSHOT_SERVO_3 3 +#define DSHOT_SERVO_3_GPIO GPIOB +#define DSHOT_SERVO_3_PIN GPIO4 +#define DSHOT_SERVO_3_AF GPIO_AF2 +#define DSHOT_SERVO_3_DRIVER DSHOTD3 +#define DSHOT_SERVO_3_CHANNEL 0 +#if USE_DSHOT6 +// DSHOT6 on AUX1 pin, not activated by default +#define DSHOT_SERVO_6 6 +#define DSHOT_SERVO_6_GPIO GPIOB +#define DSHOT_SERVO_6_PIN GPIO1 +#define DSHOT_SERVO_6_AF GPIO_AF2 +#define DSHOT_SERVO_6_DRIVER DSHOTD3 +#define DSHOT_SERVO_6_CHANNEL 3 +#endif +#define DSHOT_CONF_TIM3 1 +#define DSHOT_CONF3_DEF { \ + .dma_stream = STM32_PWM3_UP_DMA_STREAM, \ + .dma_channel = STM32_PWM3_UP_DMA_CHANNEL, \ + .pwmp = &PWMD3, \ + .tlm_sd = DSHOT_TELEMETRY_DEV, \ + .dma_buf = &dshot3DmaBuffer, \ } +#endif /** * PPM radio defines @@ -370,15 +395,15 @@ HEADER #define PWM_INPUT1_GPIO_PIN GPIO8 #define PWM_INPUT1_GPIO_AF GPIO_AF1 -// PWM_INPUT 2 on PA3 (also SERVO 1) +// PWM_INPUT 2 on PA2 (also SERVO 1) #if (USE_PWM1 && USE_PWM_INPUT2) #error "PW1 and PWM_INPUT2 are not compatible" #endif -#define PWM_INPUT2_ICU ICUD9 -#define PWM_INPUT2_CHANNEL ICU_CHANNEL_1 +#define PWM_INPUT2_ICU ICUD5 +#define PWM_INPUT2_CHANNEL ICU_CHANNEL_4 #define PWM_INPUT2_GPIO_PORT GPIOA #define PWM_INPUT2_GPIO_PIN GPIO2 -#define PWM_INPUT2_GPIO_AF GPIO_AF3 +#define PWM_INPUT2_GPIO_AF GPIO_AF2 /** * I2C defines @@ -487,11 +512,21 @@ HEADER #define SDLOG_USB_VBUS_PIN GPIO9 - - -/* - * IO pins assignments. +/** + * For WS2812PWM */ +#define WS2812D1_GPIO GPIOA +#define WS2812D1_PIN GPIO8 +#define WS2812D1_AF 1 +#define WS2812D1_CFG_DEF { \ + .dma_stream = STM32_PWM1_UP_DMA_STREAM, \ + .dma_channel = STM32_PWM1_UP_DMA_CHANNEL, \ + .dma_priority = STM32_PWM1_UP_DMA_PRIORITY, \ + .pwm_channel = 0, \ + .pwmp = &PWMD1 \ +} + + CONFIG # PIN NAME PERIPH_TYPE AF_NUMBER or # PIN NAME FUNCTION PUSHPULL|OPENDRAIN PIN_SPEED PULLUP|PULLDOWN|FLOATING LEVEL_LOW|LEVEL_HIGH AF_NUMBER @@ -513,56 +548,56 @@ H01 OSC_OUT SYS AF:RCC_OSC_OUT DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0 # ACTIVE PINS -PA00 UART4_TX UART AF:UART4_TX -PA01 UART4_RX UART AF:UART4_RX -PA02 PWM2_CH3 INPUT FLOATING -PA03 UART2_RX UART AF:USART2_RX -PA04 ADC1_IN4 ADC ADC1_IN4 -PA05 SPI1_SCK SPI AF:SPI1_SCK -PA06 SPI1_MISO SPI AF:SPI1_MISO -PA07 SPI1_MOSI SPI AF:SPI1_MOSI -PA08 CU1_CH1 ICU AF:TIM1_CH1 -PA09 OTG_FS_VBUS INPUT PULLDOWN -PA10 USART1_RX UART AF:USART1_RX -PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM -PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP -PA15 PWM2_CH1 INPUT FLOATING +PA00 UART4_TX UART AF:UART4_TX +PA01 UART4_RX UART AF:UART4_RX +PA02 SERVO1 PWM AF:TIM2_CH3 () +PA03 UART2_RX UART AF:USART2_RX +PA04 ADC1_IN4 ADC ADC1_IN4 +PA05 SPI1_SCK SPI AF:SPI1_SCK +PA06 SPI1_MISO SPI AF:SPI1_MISO +PA07 SPI1_MOSI SPI AF:SPI1_MOSI +PA08 CU1_CH1 ICU AF:TIM1_CH1 +PA09 OTG_FS_VBUS INPUT PULLDOWN +PA10 USART1_RX UART AF:USART1_RX +PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM +PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP +PA15 SERVO5 PWM AF:TIM2_CH1 () -PB00 PWM3_CH3 INPUT FLOATING -PB01 AUX1 INPUT FLOATING -PB02 BOOT1 INPUT FLOATING -PB03 PWM2_CH2 INPUT FLOATING -PB04 PWM3_CH1 INPUT FLOATING -PB05 PWM3_CH2 INPUT FLOATING -PB06 USART1_TX UART AF:USART1_TX -PB07 I2C1_SDA I2C AF:I2C1_SDA -PB08 I2C1_SCL I2C AF:I2C1_SCL -PB09 SPI1_CS OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH -PB10 I2C2_SCL I2C AF:I2C2_SCL -PB11 I2C2_SDA I2C AF:I2C2_SDA -PB12 POWER_SWITCH OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH -PB13 RX2_POL OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH -PB14 SDIO_DETECT INPUT PULLUP -PB15 AUX4 INPUT FLOATING +PB00 SERVO0 PWM AF:TIM3_CH3 () +PB01 SERVO6 PWM AF:TIM3_CH4 () +PB02 BOOT1 INPUT FLOATING +PB03 SERVO4 PWM AF:TIM2_CH2 () +PB04 SERVO3 PWM AF:TIM3_CH1 () +PB05 SERVO2 PWM AF:TIM3_CH2 () +PB06 USART1_TX UART AF:USART1_TX +PB07 I2C1_SDA I2C AF:I2C1_SDA +PB08 I2C1_SCL I2C AF:I2C1_SCL +PB09 SPI1_CS OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH +PB10 I2C2_SCL I2C AF:I2C2_SCL +PB11 I2C2_SDA I2C AF:I2C2_SDA +PB12 POWER_SWITCH OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH +PB13 RX2_POL OUTPUT PUSHPULL SPEED_HIGH LEVEL_HIGH +PB14 SDIO_DETECT INPUT PULLUP +PB15 AUX4 INPUT FLOATING -PC00 LED1 LED -PC01 LED3 LED -PC03 LED4 LED -PC04 AUX3 INPUT FLOATING -PC05 AUX2 INPUT FLOATING -PC06 USART6_TX UART AF:USART6_TX -PC07 USART6_RX UART AF:USART6_RX -PC08 SDIO_D0 SDIO AF:SDIO_D0 -PC09 SDIO_D1 SDIO AF:SDIO_D1 -PC10 SDIO_D2 SDIO AF:SDIO_D2 -PC11 SDIO_D3 SDIO AF:SDIO_D3 -PC12 SDIO_CK SDIOCK AF:SDIO_CK -PC13 LED2 LED - - -PD02 SDIO_CMD SDIO AF:SDIO_CMD +PC00 LED1 LED +PC01 LED3 LED +PC03 LED4 LED +PC04 AUX3 INPUT FLOATING +PC05 AUX2 INPUT FLOATING +PC06 USART6_TX UART AF:USART6_TX +PC07 USART6_RX UART AF:USART6_RX +PC08 SDIO_D0 SDIO AF:SDIO_D0 +PC09 SDIO_D1 SDIO AF:SDIO_D1 +PC10 SDIO_D2 SDIO AF:SDIO_D2 +PC11 SDIO_D3 SDIO AF:SDIO_D3 +PC12 SDIO_CK SDIOCK AF:SDIO_CK +PC13 LED2 LED +PD02 SDIO_CMD SDIO AF:SDIO_CMD +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^SERVO[0-9]+|AUX[0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/boards/apogee/chibios/v1.0/board.h b/sw/airborne/boards/apogee/chibios/v1.0/board.h index f111f2e273..ae5e4a0f03 100644 --- a/sw/airborne/boards/apogee/chibios/v1.0/board.h +++ b/sw/airborne/boards/apogee/chibios/v1.0/board.h @@ -22,9 +22,7 @@ Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at - http://www.apache.org/licenses/LICENSE-2.0 - Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. @@ -67,11 +65,11 @@ */ - /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* @@ -152,7 +150,6 @@ /* Power Switch, on PB12 */ #define POWER_SWITCH_GPIO GPIOB,GPIO12 - /* Pint to set Uart2 RX polarity, on PB13, output high inverts, low doesn't */ #define RC_POLARITY_GPIO_PORT GPIOB #define RC_POLARITY_GPIO_PIN GPIO13 @@ -210,14 +207,12 @@ #endif #if USE_PWM0 #define PWM_SERVO_0 0 -#define PWM_SERVO_0_GPIO GPIOB -#define PWM_SERVO_0_PIN GPIO0 -#define PWM_SERVO_0_AF GPIO_AF2 -#define PWM_SERVO_0_DRIVER PWMD3 -#define PWM_SERVO_0_CHANNEL 2 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_GPIO PAL_PORT(LINE_SERVO0) +#define PWM_SERVO_0_PIN PAL_PAD(LINE_SERVO0) +#define PWM_SERVO_0_AF AF_LINE_SERVO0 +#define PWM_SERVO_0_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO0_TIM) +#define PWM_SERVO_0_CHANNEL (SERVO0_TIM_CH-1) +#define PWM_SERVO_0_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO0_TIM) #endif #ifndef USE_PWM1 @@ -225,14 +220,12 @@ #endif #if USE_PWM1 #define PWM_SERVO_1 1 -#define PWM_SERVO_1_GPIO GPIOA -#define PWM_SERVO_1_PIN GPIO2 -#define PWM_SERVO_1_AF GPIO_AF1 -#define PWM_SERVO_1_DRIVER PWMD2 -#define PWM_SERVO_1_CHANNEL 2 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1) +#define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1) +#define PWM_SERVO_1_AF AF_LINE_SERVO1 +#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM) +#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1) +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM) #endif #ifndef USE_PWM2 @@ -240,14 +233,12 @@ #endif #if USE_PWM2 #define PWM_SERVO_2 2 -#define PWM_SERVO_2_GPIO GPIOB -#define PWM_SERVO_2_PIN GPIO5 -#define PWM_SERVO_2_AF GPIO_AF2 -#define PWM_SERVO_2_DRIVER PWMD3 -#define PWM_SERVO_2_CHANNEL 1 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2) +#define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2) +#define PWM_SERVO_2_AF AF_LINE_SERVO2 +#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM) +#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1) +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM) #endif #ifndef USE_PWM3 @@ -255,14 +246,12 @@ #endif #if USE_PWM3 #define PWM_SERVO_3 3 -#define PWM_SERVO_3_GPIO GPIOB -#define PWM_SERVO_3_PIN GPIO4 -#define PWM_SERVO_3_AF GPIO_AF2 -#define PWM_SERVO_3_DRIVER PWMD3 -#define PWM_SERVO_3_CHANNEL 0 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3) +#define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3) +#define PWM_SERVO_3_AF AF_LINE_SERVO3 +#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM) +#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1) +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM) #endif #ifndef USE_PWM4 @@ -270,14 +259,12 @@ #endif #if USE_PWM4 #define PWM_SERVO_4 4 -#define PWM_SERVO_4_GPIO GPIOB -#define PWM_SERVO_4_PIN GPIO3 -#define PWM_SERVO_4_AF GPIO_AF1 -#define PWM_SERVO_4_DRIVER PWMD2 -#define PWM_SERVO_4_CHANNEL 1 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4) +#define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4) +#define PWM_SERVO_4_AF AF_LINE_SERVO4 +#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM) +#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1) +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM) #endif #ifndef USE_PWM5 @@ -285,105 +272,55 @@ #endif #if USE_PWM5 #define PWM_SERVO_5 5 -#define PWM_SERVO_5_GPIO GPIOA -#define PWM_SERVO_5_PIN GPIO15 -#define PWM_SERVO_5_AF GPIO_AF1 -#define PWM_SERVO_5_DRIVER PWMD2 -#define PWM_SERVO_5_CHANNEL 0 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5) +#define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5) +#define PWM_SERVO_5_AF AF_LINE_SERVO5 +#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM) +#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1) +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM) #endif #if USE_PWM6 #define PWM_SERVO_6 6 -#define PWM_SERVO_6_GPIO GPIOB -#define PWM_SERVO_6_PIN GPIO1 -#define PWM_SERVO_6_AF GPIO_AF2 -#define PWM_SERVO_6_DRIVER PWMD3 -#define PWM_SERVO_6_CHANNEL 3 -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6) +#define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6) +#define PWM_SERVO_6_AF AF_LINE_SERVO6 +#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM) +#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1) +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM) #endif - -#ifdef STM32_PWM_USE_TIM2 -#define PWM_CONF_TIM2 STM32_PWM_USE_TIM2 -#else -#define PWM_CONF_TIM2 1 -#endif -#define PWM_CONF2_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM2_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 -#endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_0_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * DSHOT */ #ifndef DSHOT_TELEMETRY_DEV #define DSHOT_TELEMETRY_DEV NULL #endif - #ifndef USE_DSHOT_TIM2 #define USE_DSHOT_TIM2 1 #endif - #ifndef USE_DSHOT_TIM3 #define USE_DSHOT_TIM3 1 #endif - #if USE_DSHOT_TIM2 // Servo 1, 4, 5 - #define DSHOT_SERVO_1 1 #define DSHOT_SERVO_1_GPIO GPIOA #define DSHOT_SERVO_1_PIN GPIO2 #define DSHOT_SERVO_1_AF GPIO_AF1 #define DSHOT_SERVO_1_DRIVER DSHOTD2 #define DSHOT_SERVO_1_CHANNEL 2 - #define DSHOT_SERVO_4 4 #define DSHOT_SERVO_4_GPIO GPIOB #define DSHOT_SERVO_4_PIN GPIO3 #define DSHOT_SERVO_4_AF GPIO_AF1 #define DSHOT_SERVO_4_DRIVER DSHOTD2 #define DSHOT_SERVO_4_CHANNEL 1 - #define DSHOT_SERVO_5 5 #define DSHOT_SERVO_5_GPIO GPIOA #define DSHOT_SERVO_5_PIN GPIO15 #define DSHOT_SERVO_5_AF GPIO_AF1 #define DSHOT_SERVO_5_DRIVER DSHOTD2 #define DSHOT_SERVO_5_CHANNEL 0 - #define DSHOT_CONF_TIM2 1 #define DSHOT_CONF2_DEF { \ .dma_stream = STM32_PWM2_UP_DMA_STREAM, \ @@ -392,32 +329,26 @@ .tlm_sd = DSHOT_TELEMETRY_DEV, \ .dma_buf = &dshot2DmaBuffer, \ } - #endif - #if USE_DSHOT_TIM3 // Servo 0,2,3,6 - #define DSHOT_SERVO_0 0 #define DSHOT_SERVO_0_GPIO GPIOB #define DSHOT_SERVO_0_PIN GPIO0 #define DSHOT_SERVO_0_AF GPIO_AF2 #define DSHOT_SERVO_0_DRIVER DSHOTD3 #define DSHOT_SERVO_0_CHANNEL 2 - #define DSHOT_SERVO_2 2 #define DSHOT_SERVO_2_GPIO GPIOB #define DSHOT_SERVO_2_PIN GPIO5 #define DSHOT_SERVO_2_AF GPIO_AF2 #define DSHOT_SERVO_2_DRIVER DSHOTD3 #define DSHOT_SERVO_2_CHANNEL 1 - #define DSHOT_SERVO_3 3 #define DSHOT_SERVO_3_GPIO GPIOB #define DSHOT_SERVO_3_PIN GPIO4 #define DSHOT_SERVO_3_AF GPIO_AF2 #define DSHOT_SERVO_3_DRIVER DSHOTD3 #define DSHOT_SERVO_3_CHANNEL 0 - #if USE_DSHOT6 // DSHOT6 on AUX1 pin, not activated by default #define DSHOT_SERVO_6 6 @@ -427,7 +358,6 @@ #define DSHOT_SERVO_6_DRIVER DSHOTD3 #define DSHOT_SERVO_6_CHANNEL 3 #endif - #define DSHOT_CONF_TIM3 1 #define DSHOT_CONF3_DEF { \ .dma_stream = STM32_PWM3_UP_DMA_STREAM, \ @@ -436,7 +366,6 @@ .tlm_sd = DSHOT_TELEMETRY_DEV, \ .dma_buf = &dshot3DmaBuffer, \ } - #endif /** @@ -598,7 +527,7 @@ /** - * For WS2812 + * For WS2812PWM */ #define WS2812D1_GPIO GPIOA #define WS2812D1_PIN GPIO8 @@ -612,15 +541,12 @@ } -/* - * IO pins assignments. - */ /* * IO pins assignments. */ #define UART4_TX 0U #define UART4_RX 1U -#define PWM2_CH3 2U +#define SERVO1 2U #define UART2_RX 3U #define ADC1_IN4 4U #define SPI1_SCK 5U @@ -633,14 +559,14 @@ #define OTG_FS_DP 12U #define SWDIO 13U #define SWCLK 14U -#define PWM2_CH1 15U +#define SERVO5 15U -#define PWM3_CH3 0U -#define AUX1 1U +#define SERVO0 0U +#define SERVO6 1U #define BOOT1 2U -#define PWM2_CH2 3U -#define PWM3_CH1 4U -#define PWM3_CH2 5U +#define SERVO4 3U +#define SERVO3 4U +#define SERVO2 5U #define USART1_TX 6U #define I2C1_SDA 7U #define I2C1_SCL 8U @@ -810,7 +736,7 @@ */ #define LINE_UART4_TX PAL_LINE(GPIOA, 0U) #define LINE_UART4_RX PAL_LINE(GPIOA, 1U) -#define LINE_PWM2_CH3 PAL_LINE(GPIOA, 2U) +#define LINE_SERVO1 PAL_LINE(GPIOA, 2U) #define LINE_UART2_RX PAL_LINE(GPIOA, 3U) #define LINE_ADC1_IN4 PAL_LINE(GPIOA, 4U) #define LINE_SPI1_SCK PAL_LINE(GPIOA, 5U) @@ -823,14 +749,14 @@ #define LINE_OTG_FS_DP PAL_LINE(GPIOA, 12U) #define LINE_SWDIO PAL_LINE(GPIOA, 13U) #define LINE_SWCLK PAL_LINE(GPIOA, 14U) -#define LINE_PWM2_CH1 PAL_LINE(GPIOA, 15U) +#define LINE_SERVO5 PAL_LINE(GPIOA, 15U) -#define LINE_PWM3_CH3 PAL_LINE(GPIOB, 0U) -#define LINE_AUX1 PAL_LINE(GPIOB, 1U) +#define LINE_SERVO0 PAL_LINE(GPIOB, 0U) +#define LINE_SERVO6 PAL_LINE(GPIOB, 1U) #define LINE_BOOT1 PAL_LINE(GPIOB, 2U) -#define LINE_PWM2_CH2 PAL_LINE(GPIOB, 3U) -#define LINE_PWM3_CH1 PAL_LINE(GPIOB, 4U) -#define LINE_PWM3_CH2 PAL_LINE(GPIOB, 5U) +#define LINE_SERVO4 PAL_LINE(GPIOB, 3U) +#define LINE_SERVO3 PAL_LINE(GPIOB, 4U) +#define LINE_SERVO2 PAL_LINE(GPIOB, 5U) #define LINE_USART1_TX PAL_LINE(GPIOB, 6U) #define LINE_I2C1_SDA PAL_LINE(GPIOB, 7U) #define LINE_I2C1_SCL PAL_LINE(GPIOB, 8U) @@ -888,7 +814,7 @@ #define VAL_GPIOA_MODER (PIN_MODE_ALTERNATE(UART4_TX) | \ PIN_MODE_ALTERNATE(UART4_RX) | \ - PIN_MODE_INPUT(PWM2_CH3) | \ + PIN_MODE_ALTERNATE(SERVO1) | \ PIN_MODE_ALTERNATE(UART2_RX) | \ PIN_MODE_ANALOG(ADC1_IN4) | \ PIN_MODE_ALTERNATE(SPI1_SCK) | \ @@ -901,11 +827,11 @@ PIN_MODE_ALTERNATE(OTG_FS_DP) | \ PIN_MODE_ALTERNATE(SWDIO) | \ PIN_MODE_ALTERNATE(SWCLK) | \ - PIN_MODE_INPUT(PWM2_CH1)) + PIN_MODE_ALTERNATE(SERVO5)) #define VAL_GPIOA_OTYPER (PIN_OTYPE_PUSHPULL(UART4_TX) | \ PIN_OTYPE_PUSHPULL(UART4_RX) | \ - PIN_OTYPE_OPENDRAIN(PWM2_CH3) | \ + PIN_OTYPE_PUSHPULL(SERVO1) | \ PIN_OTYPE_PUSHPULL(UART2_RX) | \ PIN_OTYPE_PUSHPULL(ADC1_IN4) | \ PIN_OTYPE_PUSHPULL(SPI1_SCK) | \ @@ -918,11 +844,11 @@ PIN_OTYPE_PUSHPULL(OTG_FS_DP) | \ PIN_OTYPE_PUSHPULL(SWDIO) | \ PIN_OTYPE_PUSHPULL(SWCLK) | \ - PIN_OTYPE_OPENDRAIN(PWM2_CH1)) + PIN_OTYPE_PUSHPULL(SERVO5)) #define VAL_GPIOA_OSPEEDR (PIN_OSPEED_SPEED_HIGH(UART4_TX) | \ PIN_OSPEED_SPEED_HIGH(UART4_RX) | \ - PIN_OSPEED_SPEED_VERYLOW(PWM2_CH3) | \ + PIN_OSPEED_SPEED_HIGH(SERVO1) | \ PIN_OSPEED_SPEED_HIGH(UART2_RX) | \ PIN_OSPEED_SPEED_VERYLOW(ADC1_IN4) | \ PIN_OSPEED_SPEED_HIGH(SPI1_SCK) | \ @@ -935,11 +861,11 @@ PIN_OSPEED_SPEED_HIGH(OTG_FS_DP) | \ PIN_OSPEED_SPEED_HIGH(SWDIO) | \ PIN_OSPEED_SPEED_HIGH(SWCLK) | \ - PIN_OSPEED_SPEED_VERYLOW(PWM2_CH1)) + PIN_OSPEED_SPEED_HIGH(SERVO5)) #define VAL_GPIOA_PUPDR (PIN_PUPDR_FLOATING(UART4_TX) | \ PIN_PUPDR_FLOATING(UART4_RX) | \ - PIN_PUPDR_FLOATING(PWM2_CH3) | \ + PIN_PUPDR_FLOATING(SERVO1) | \ PIN_PUPDR_FLOATING(UART2_RX) | \ PIN_PUPDR_FLOATING(ADC1_IN4) | \ PIN_PUPDR_FLOATING(SPI1_SCK) | \ @@ -952,11 +878,11 @@ PIN_PUPDR_FLOATING(OTG_FS_DP) | \ PIN_PUPDR_FLOATING(SWDIO) | \ PIN_PUPDR_FLOATING(SWCLK) | \ - PIN_PUPDR_FLOATING(PWM2_CH1)) + PIN_PUPDR_FLOATING(SERVO5)) #define VAL_GPIOA_ODR (PIN_ODR_LEVEL_HIGH(UART4_TX) | \ PIN_ODR_LEVEL_HIGH(UART4_RX) | \ - PIN_ODR_LEVEL_LOW(PWM2_CH3) | \ + PIN_ODR_LEVEL_LOW(SERVO1) | \ PIN_ODR_LEVEL_HIGH(UART2_RX) | \ PIN_ODR_LEVEL_LOW(ADC1_IN4) | \ PIN_ODR_LEVEL_HIGH(SPI1_SCK) | \ @@ -969,11 +895,11 @@ PIN_ODR_LEVEL_HIGH(OTG_FS_DP) | \ PIN_ODR_LEVEL_HIGH(SWDIO) | \ PIN_ODR_LEVEL_HIGH(SWCLK) | \ - PIN_ODR_LEVEL_LOW(PWM2_CH1)) + PIN_ODR_LEVEL_LOW(SERVO5)) #define VAL_GPIOA_AFRL (PIN_AFIO_AF(UART4_TX, 8) | \ PIN_AFIO_AF(UART4_RX, 8) | \ - PIN_AFIO_AF(PWM2_CH3, 0) | \ + PIN_AFIO_AF(SERVO1, 1) | \ PIN_AFIO_AF(UART2_RX, 7) | \ PIN_AFIO_AF(ADC1_IN4, 0) | \ PIN_AFIO_AF(SPI1_SCK, 5) | \ @@ -987,14 +913,14 @@ PIN_AFIO_AF(OTG_FS_DP, 10) | \ PIN_AFIO_AF(SWDIO, 0) | \ PIN_AFIO_AF(SWCLK, 0) | \ - PIN_AFIO_AF(PWM2_CH1, 0)) + PIN_AFIO_AF(SERVO5, 1)) -#define VAL_GPIOB_MODER (PIN_MODE_INPUT(PWM3_CH3) | \ - PIN_MODE_INPUT(AUX1) | \ +#define VAL_GPIOB_MODER (PIN_MODE_ALTERNATE(SERVO0) | \ + PIN_MODE_ALTERNATE(SERVO6) | \ PIN_MODE_INPUT(BOOT1) | \ - PIN_MODE_INPUT(PWM2_CH2) | \ - PIN_MODE_INPUT(PWM3_CH1) | \ - PIN_MODE_INPUT(PWM3_CH2) | \ + PIN_MODE_ALTERNATE(SERVO4) | \ + PIN_MODE_ALTERNATE(SERVO3) | \ + PIN_MODE_ALTERNATE(SERVO2) | \ PIN_MODE_ALTERNATE(USART1_TX) | \ PIN_MODE_ALTERNATE(I2C1_SDA) | \ PIN_MODE_ALTERNATE(I2C1_SCL) | \ @@ -1006,12 +932,12 @@ PIN_MODE_INPUT(SDIO_DETECT) | \ PIN_MODE_INPUT(AUX4)) -#define VAL_GPIOB_OTYPER (PIN_OTYPE_OPENDRAIN(PWM3_CH3) | \ - PIN_OTYPE_OPENDRAIN(AUX1) | \ +#define VAL_GPIOB_OTYPER (PIN_OTYPE_PUSHPULL(SERVO0) | \ + PIN_OTYPE_PUSHPULL(SERVO6) | \ PIN_OTYPE_OPENDRAIN(BOOT1) | \ - PIN_OTYPE_OPENDRAIN(PWM2_CH2) | \ - PIN_OTYPE_OPENDRAIN(PWM3_CH1) | \ - PIN_OTYPE_OPENDRAIN(PWM3_CH2) | \ + PIN_OTYPE_PUSHPULL(SERVO4) | \ + PIN_OTYPE_PUSHPULL(SERVO3) | \ + PIN_OTYPE_PUSHPULL(SERVO2) | \ PIN_OTYPE_PUSHPULL(USART1_TX) | \ PIN_OTYPE_OPENDRAIN(I2C1_SDA) | \ PIN_OTYPE_OPENDRAIN(I2C1_SCL) | \ @@ -1023,12 +949,12 @@ PIN_OTYPE_OPENDRAIN(SDIO_DETECT) | \ PIN_OTYPE_OPENDRAIN(AUX4)) -#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PWM3_CH3) | \ - PIN_OSPEED_SPEED_VERYLOW(AUX1) | \ +#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_SPEED_HIGH(SERVO0) | \ + PIN_OSPEED_SPEED_HIGH(SERVO6) | \ PIN_OSPEED_SPEED_VERYLOW(BOOT1) | \ - PIN_OSPEED_SPEED_VERYLOW(PWM2_CH2) | \ - PIN_OSPEED_SPEED_VERYLOW(PWM3_CH1) | \ - PIN_OSPEED_SPEED_VERYLOW(PWM3_CH2) | \ + PIN_OSPEED_SPEED_HIGH(SERVO4) | \ + PIN_OSPEED_SPEED_HIGH(SERVO3) | \ + PIN_OSPEED_SPEED_HIGH(SERVO2) | \ PIN_OSPEED_SPEED_HIGH(USART1_TX) | \ PIN_OSPEED_SPEED_HIGH(I2C1_SDA) | \ PIN_OSPEED_SPEED_HIGH(I2C1_SCL) | \ @@ -1040,12 +966,12 @@ PIN_OSPEED_SPEED_VERYLOW(SDIO_DETECT) | \ PIN_OSPEED_SPEED_VERYLOW(AUX4)) -#define VAL_GPIOB_PUPDR (PIN_PUPDR_FLOATING(PWM3_CH3) | \ - PIN_PUPDR_FLOATING(AUX1) | \ +#define VAL_GPIOB_PUPDR (PIN_PUPDR_FLOATING(SERVO0) | \ + PIN_PUPDR_FLOATING(SERVO6) | \ PIN_PUPDR_FLOATING(BOOT1) | \ - PIN_PUPDR_FLOATING(PWM2_CH2) | \ - PIN_PUPDR_FLOATING(PWM3_CH1) | \ - PIN_PUPDR_FLOATING(PWM3_CH2) | \ + PIN_PUPDR_FLOATING(SERVO4) | \ + PIN_PUPDR_FLOATING(SERVO3) | \ + PIN_PUPDR_FLOATING(SERVO2) | \ PIN_PUPDR_FLOATING(USART1_TX) | \ PIN_PUPDR_PULLUP(I2C1_SDA) | \ PIN_PUPDR_PULLUP(I2C1_SCL) | \ @@ -1057,12 +983,12 @@ PIN_PUPDR_PULLUP(SDIO_DETECT) | \ PIN_PUPDR_FLOATING(AUX4)) -#define VAL_GPIOB_ODR (PIN_ODR_LEVEL_LOW(PWM3_CH3) | \ - PIN_ODR_LEVEL_LOW(AUX1) | \ +#define VAL_GPIOB_ODR (PIN_ODR_LEVEL_LOW(SERVO0) | \ + PIN_ODR_LEVEL_LOW(SERVO6) | \ PIN_ODR_LEVEL_LOW(BOOT1) | \ - PIN_ODR_LEVEL_LOW(PWM2_CH2) | \ - PIN_ODR_LEVEL_LOW(PWM3_CH1) | \ - PIN_ODR_LEVEL_LOW(PWM3_CH2) | \ + PIN_ODR_LEVEL_LOW(SERVO4) | \ + PIN_ODR_LEVEL_LOW(SERVO3) | \ + PIN_ODR_LEVEL_LOW(SERVO2) | \ PIN_ODR_LEVEL_HIGH(USART1_TX) | \ PIN_ODR_LEVEL_HIGH(I2C1_SDA) | \ PIN_ODR_LEVEL_HIGH(I2C1_SCL) | \ @@ -1074,12 +1000,12 @@ PIN_ODR_LEVEL_LOW(SDIO_DETECT) | \ PIN_ODR_LEVEL_LOW(AUX4)) -#define VAL_GPIOB_AFRL (PIN_AFIO_AF(PWM3_CH3, 0) | \ - PIN_AFIO_AF(AUX1, 0) | \ +#define VAL_GPIOB_AFRL (PIN_AFIO_AF(SERVO0, 2) | \ + PIN_AFIO_AF(SERVO6, 2) | \ PIN_AFIO_AF(BOOT1, 0) | \ - PIN_AFIO_AF(PWM2_CH2, 0) | \ - PIN_AFIO_AF(PWM3_CH1, 0) | \ - PIN_AFIO_AF(PWM3_CH2, 0) | \ + PIN_AFIO_AF(SERVO4, 1) | \ + PIN_AFIO_AF(SERVO3, 2) | \ + PIN_AFIO_AF(SERVO2, 2) | \ PIN_AFIO_AF(USART1_TX, 7) | \ PIN_AFIO_AF(I2C1_SDA, 4)) @@ -2023,6 +1949,8 @@ #define AF_LINE_UART4_TX 8U #define AF_UART4_RX 8U #define AF_LINE_UART4_RX 8U +#define AF_SERVO1 1U +#define AF_LINE_SERVO1 1U #define AF_UART2_RX 7U #define AF_LINE_UART2_RX 7U #define AF_SPI1_SCK 5U @@ -2043,6 +1971,18 @@ #define AF_LINE_SWDIO 0U #define AF_SWCLK 0U #define AF_LINE_SWCLK 0U +#define AF_SERVO5 1U +#define AF_LINE_SERVO5 1U +#define AF_SERVO0 2U +#define AF_LINE_SERVO0 2U +#define AF_SERVO6 2U +#define AF_LINE_SERVO6 2U +#define AF_SERVO4 1U +#define AF_LINE_SERVO4 1U +#define AF_SERVO3 2U +#define AF_LINE_SERVO3 2U +#define AF_SERVO2 2U +#define AF_LINE_SERVO2 2U #define AF_USART1_TX 7U #define AF_LINE_USART1_TX 7U #define AF_I2C1_SDA 4U @@ -2079,6 +2019,68 @@ #define AF_LINE_OSC_OUT 0U +#define SERVO1_TIM 2 +#define SERVO1_TIM_FN CH +#define SERVO1_TIM_CH 3 +#define SERVO1_TIM_AF 1 +#define SERVO5_TIM 2 +#define SERVO5_TIM_FN CH +#define SERVO5_TIM_CH 1 +#define SERVO5_TIM_AF 1 +#define SERVO0_TIM 3 +#define SERVO0_TIM_FN CH +#define SERVO0_TIM_CH 3 +#define SERVO0_TIM_AF 2 +#define SERVO6_TIM 3 +#define SERVO6_TIM_FN CH +#define SERVO6_TIM_CH 4 +#define SERVO6_TIM_AF 2 +#define SERVO4_TIM 2 +#define SERVO4_TIM_FN CH +#define SERVO4_TIM_CH 2 +#define SERVO4_TIM_AF 1 +#define SERVO3_TIM 3 +#define SERVO3_TIM_FN CH +#define SERVO3_TIM_CH 1 +#define SERVO3_TIM_AF 2 +#define SERVO2_TIM 3 +#define SERVO2_TIM_FN CH +#define SERVO2_TIM_CH 2 +#define SERVO2_TIM_AF 2 + +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_SERVO1, \ + LINE_SERVO5, \ + LINE_SERVO0, \ + LINE_SERVO6, \ + LINE_SERVO4, \ + LINE_SERVO3, \ + LINE_SERVO2, \ + LINE_SPI1_CS, \ + LINE_AUX4, \ + LINE_LED1, \ + LINE_LED3, \ + LINE_LED4, \ + LINE_AUX3, \ + LINE_AUX2, \ + LINE_LED2 +#define ENERGY_SAVE_INPUT_SIZE 15 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/apogee/chibios/v1.0/board.mk b/sw/airborne/boards/apogee/chibios/v1.0/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/apogee/chibios/v1.0/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/apogee/chibios/v1.0/mcuconf.h b/sw/airborne/boards/apogee/chibios/v1.0/mcuconf.h index 172bae6cb1..b5e0f477f6 100644 --- a/sw/airborne/boards/apogee/chibios/v1.0/mcuconf.h +++ b/sw/airborne/boards/apogee/chibios/v1.0/mcuconf.h @@ -86,6 +86,28 @@ #define STM32_IRQ_EXTI21_PRIORITY 15 #define STM32_IRQ_EXTI22_PRIORITY 15 +#define STM32_IRQ_TIM1_BRK_TIM9_PRIORITY 7 +#define STM32_IRQ_TIM1_UP_TIM10_PRIORITY 7 +#define STM32_IRQ_TIM1_TRGCO_TIM11_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 + /* * ADC driver system settings. */ diff --git a/sw/airborne/boards/chimera/chibios/v1.0/board.c b/sw/airborne/boards/chimera/chibios/v1.0/board.c deleted file mode 100644 index 673a8a5f09..0000000000 --- a/sw/airborne/boards/chimera/chibios/v1.0/board.c +++ /dev/null @@ -1,283 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return !palReadLine (LINE_SD_DETECT); -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} - -/** Energy saving procedure for SD log closing - */ -void mcu_periph_energy_save(void) -{ - palSetLineMode(LINE_LED1, PAL_MODE_INPUT); - palSetLineMode(LINE_LED2, PAL_MODE_INPUT); - palSetLineMode(LINE_LED3, PAL_MODE_INPUT); - palSetLineMode(LINE_LED4, PAL_MODE_INPUT); - palSetLineMode(LINE_SPI1_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX0, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX1, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX2, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX3, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX4, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX5, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX6, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX7, PAL_MODE_INPUT); -} - diff --git a/sw/airborne/boards/chimera/chibios/v1.0/board.cfg b/sw/airborne/boards/chimera/chibios/v1.0/board.cfg index ef423a1c5f..9e1383adb0 100644 --- a/sw/airborne/boards/chimera/chibios/v1.0/board.cfg +++ b/sw/airborne/boards/chimera/chibios/v1.0/board.cfg @@ -77,70 +77,73 @@ DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0 # ACTIVE PINS -PA00 AUX3 PASSIVE -PA01 RC1_UART4_RX PASSIVE -PA02 AUX2 PASSIVE -PA03 AUX1 PASSIVE -PA04 VBAT_MEAS ADC ADC1_IN4 -PA05 AUX0 PASSIVE -PA06 SRV0_TIM3_CH1 PASSIVE -PA07 SRV1_TIM3_CH2 PASSIVE -PA08 XB_ASSO INPUT FLOATING -PA09 USB_VBUS INPUT PULLDOWN -PA10 SD_DETECT INPUT PULLUP -PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM -PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP -PA15 SPI1_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH -PB00 SRV2_TIM3_CH3 PASSIVE -PB01 SRV3_TIM3_CH4 PASSIVE -PB02 RC1 PASSIVE -PB03 SPI1_SCK SPI AF:SPI1_SCK -PB04 SPI1_MISO SPI AF:SPI1_MISO -PB05 SPI1_MOSI SPI AF:SPI1_MOSI -PB06 USART1_TX UART AF:USART1_TX -PB07 USART1_RX UART AF:USART1_RX -PB08 I2C1_SCL I2C AF:I2C1_SCL -PB09 I2C1_SDA I2C AF:I2C1_SDA -PB10 I2C2_SCL I2C AF:I2C2_SCL -PB11 I2C2_SDA I2C AF:I2C2_SDA -PB12 LED1 LED -PB13 LED2 LED -PB14 DIS_C LED -PB15 DIS_DP LED -PC02 AUX5 PASSIVE -PC03 AUX4 PASSIVE -PC04 EN_COMP OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PC06 AUX6 PASSIVE -PC07 AUX7 PASSIVE -PC08 SDMMC1_D0 SDIO AF:SDMMC1_D0 -PC09 SDMMC1_D1 SDIO AF:SDMMC1_D1 -PC10 SDMMC1_D2 SDIO AF:SDMMC1_D2 -PC11 SDMMC1_D3 SDIO AF:SDMMC1_D3 -PC12 SDMMC1_CK SDIO AF:SDMMC1_CK -PD00 CAN1_RX CAN AF:CAN1_RX -PD01 CAN1_TX CAN AF:CAN1_TX -PD02 SDMMC1_CMD SDIO AF:SDMMC1_CMD -PD03 USART2_CTS PASSIVE -PD04 USART2_RTS PASSIVE -PD05 USART2_TX PASSIVE -PD06 USART2_RX PASSIVE -PD07 IMU_INT INPUT FLOATING -PD08 USART3_TX UART AF:USART3_TX -PD09 USART3_RX UART AF:USART3_RX -PD10 LED3 LED -PD11 LED4 LED -PD12 SRV4_TIM4_CH1 PASSIVE -PD13 SRV5_TIM4_CH2 PASSIVE -PD14 SRV6_TIM4_CH3 PASSIVE -PD15 SRV7_TIM4_CH4 PASSIVE -PE00 UART8_RX UART AF:UART8_RX -PE01 UART8_TX UART AF:UART8_TX -PE02 DIS_G LED -PE03 DIS_F LED -PE04 DIS_A LED -PE05 DIS_B LED -PE06 APSW OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PE07 RC2_UART7_RX PASSIVE -PE08 DIS_E LED -PE09 DIS_D LED -PE15 XB_RST OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PA00 AUX3 PASSIVE +PA01 RC1_UART4_RX PASSIVE +PA02 AUX2 PASSIVE +PA03 AUX1 PASSIVE +PA04 VBAT_MEAS ADC ADC1_IN4 +PA05 AUX0 PASSIVE +PA06 SERVO0 PWM AF:TIM3_CH1 () +PA07 SERVO1 PWM AF:TIM3_CH2 () +PA08 XB_ASSO INPUT FLOATING +PA09 USB_VBUS INPUT PULLDOWN +PA10 SD_DETECT INPUT PULLUP +PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM +PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP +PA15 SPI1_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PB00 SERVO2 PWM AF:TIM3_CH3 () +PB01 SERVO3 PWM AF:TIM3_CH4 () +PB02 RC1 PASSIVE +PB03 SPI1_SCK SPI AF:SPI1_SCK +PB04 SPI1_MISO SPI AF:SPI1_MISO +PB05 SPI1_MOSI SPI AF:SPI1_MOSI +PB06 USART1_TX UART AF:USART1_TX +PB07 USART1_RX UART AF:USART1_RX +PB08 I2C1_SCL I2C AF:I2C1_SCL +PB09 I2C1_SDA I2C AF:I2C1_SDA +PB10 I2C2_SCL I2C AF:I2C2_SCL +PB11 I2C2_SDA I2C AF:I2C2_SDA +PB12 LED1 LED +PB13 LED2 LED +PB14 DIS_C LED +PB15 DIS_DP LED +PC02 AUX5 PASSIVE +PC03 AUX4 PASSIVE +PC04 EN_COMP OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PC06 AUX6 PASSIVE +PC07 AUX7 PASSIVE +PC08 SDMMC1_D0 SDIO AF:SDMMC1_D0 +PC09 SDMMC1_D1 SDIO AF:SDMMC1_D1 +PC10 SDMMC1_D2 SDIO AF:SDMMC1_D2 +PC11 SDMMC1_D3 SDIO AF:SDMMC1_D3 +PC12 SDMMC1_CK SDIO AF:SDMMC1_CK +PD00 CAN1_RX CAN AF:CAN1_RX +PD01 CAN1_TX CAN AF:CAN1_TX +PD02 SDMMC1_CMD SDIO AF:SDMMC1_CMD +PD03 USART2_CTS PASSIVE +PD04 USART2_RTS PASSIVE +PD05 USART2_TX PASSIVE +PD06 USART2_RX PASSIVE +PD07 IMU_INT INPUT FLOATING +PD08 USART3_TX UART AF:USART3_TX +PD09 USART3_RX UART AF:USART3_RX +PD10 LED3 LED +PD11 LED4 LED +PD12 SERVO4 PWM AF:TIM4_CH1 () +PD13 SERVO5 PWM AF:TIM4_CH2 () +PD14 SERVO6 PWM AF:TIM4_CH3 () +PD15 SERVO7 PWM AF:TIM4_CH4 () +PE00 UART8_RX UART AF:UART8_RX +PE01 UART8_TX UART AF:UART8_TX +PE02 DIS_G LED +PE03 DIS_F LED +PE04 DIS_A LED +PE05 DIS_B LED +PE06 APSW OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PE07 RC2_UART7_RX PASSIVE +PE08 DIS_E LED +PE09 DIS_D LED +PE15 XB_RST OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH + +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^SERVO[1-9=]+|AUX[0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/boards/chimera/chibios/v1.0/board.h b/sw/airborne/boards/chimera/chibios/v1.0/board.h index 0d84ec271a..f3bc08b7f7 100644 --- a/sw/airborne/boards/chimera/chibios/v1.0/board.h +++ b/sw/airborne/boards/chimera/chibios/v1.0/board.h @@ -55,8 +55,8 @@ #define AUX1 3U #define VBAT_MEAS 4U #define AUX0 5U -#define SRV0_TIM3_CH1 6U -#define SRV1_TIM3_CH2 7U +#define SERVO0 6U +#define SERVO1 7U #define XB_ASSO 8U #define USB_VBUS 9U #define SD_DETECT 10U @@ -66,8 +66,8 @@ #define SWCLK 14U #define SPI1_CS 15U -#define SRV2_TIM3_CH3 0U -#define SRV3_TIM3_CH4 1U +#define SERVO2 0U +#define SERVO3 1U #define RC1 2U #define SPI1_SCK 3U #define SPI1_MISO 4U @@ -112,10 +112,10 @@ #define USART3_RX 9U #define LED3 10U #define LED4 11U -#define SRV4_TIM4_CH1 12U -#define SRV5_TIM4_CH2 13U -#define SRV6_TIM4_CH3 14U -#define SRV7_TIM4_CH4 15U +#define SERVO4 12U +#define SERVO5 13U +#define SERVO6 14U +#define SERVO7 15U #define UART8_RX 0U #define UART8_TX 1U @@ -245,8 +245,8 @@ #define LINE_AUX1 PAL_LINE(GPIOA, 3U) #define LINE_VBAT_MEAS PAL_LINE(GPIOA, 4U) #define LINE_AUX0 PAL_LINE(GPIOA, 5U) -#define LINE_SRV0_TIM3_CH1 PAL_LINE(GPIOA, 6U) -#define LINE_SRV1_TIM3_CH2 PAL_LINE(GPIOA, 7U) +#define LINE_SERVO0 PAL_LINE(GPIOA, 6U) +#define LINE_SERVO1 PAL_LINE(GPIOA, 7U) #define LINE_XB_ASSO PAL_LINE(GPIOA, 8U) #define LINE_USB_VBUS PAL_LINE(GPIOA, 9U) #define LINE_SD_DETECT PAL_LINE(GPIOA, 10U) @@ -256,8 +256,8 @@ #define LINE_SWCLK PAL_LINE(GPIOA, 14U) #define LINE_SPI1_CS PAL_LINE(GPIOA, 15U) -#define LINE_SRV2_TIM3_CH3 PAL_LINE(GPIOB, 0U) -#define LINE_SRV3_TIM3_CH4 PAL_LINE(GPIOB, 1U) +#define LINE_SERVO2 PAL_LINE(GPIOB, 0U) +#define LINE_SERVO3 PAL_LINE(GPIOB, 1U) #define LINE_RC1 PAL_LINE(GPIOB, 2U) #define LINE_SPI1_SCK PAL_LINE(GPIOB, 3U) #define LINE_SPI1_MISO PAL_LINE(GPIOB, 4U) @@ -298,10 +298,10 @@ #define LINE_USART3_RX PAL_LINE(GPIOD, 9U) #define LINE_LED3 PAL_LINE(GPIOD, 10U) #define LINE_LED4 PAL_LINE(GPIOD, 11U) -#define LINE_SRV4_TIM4_CH1 PAL_LINE(GPIOD, 12U) -#define LINE_SRV5_TIM4_CH2 PAL_LINE(GPIOD, 13U) -#define LINE_SRV6_TIM4_CH3 PAL_LINE(GPIOD, 14U) -#define LINE_SRV7_TIM4_CH4 PAL_LINE(GPIOD, 15U) +#define LINE_SERVO4 PAL_LINE(GPIOD, 12U) +#define LINE_SERVO5 PAL_LINE(GPIOD, 13U) +#define LINE_SERVO6 PAL_LINE(GPIOD, 14U) +#define LINE_SERVO7 PAL_LINE(GPIOD, 15U) #define LINE_UART8_RX PAL_LINE(GPIOE, 0U) #define LINE_UART8_TX PAL_LINE(GPIOE, 1U) @@ -347,8 +347,8 @@ PIN_MODE_INPUT(AUX1) | \ PIN_MODE_ANALOG(VBAT_MEAS) | \ PIN_MODE_INPUT(AUX0) | \ - PIN_MODE_INPUT(SRV0_TIM3_CH1) | \ - PIN_MODE_INPUT(SRV1_TIM3_CH2) | \ + PIN_MODE_ALTERNATE(SERVO0) | \ + PIN_MODE_ALTERNATE(SERVO1) | \ PIN_MODE_INPUT(XB_ASSO) | \ PIN_MODE_INPUT(USB_VBUS) | \ PIN_MODE_INPUT(SD_DETECT) | \ @@ -364,8 +364,8 @@ PIN_OTYPE_OPENDRAIN(AUX1) | \ PIN_OTYPE_PUSHPULL(VBAT_MEAS) | \ PIN_OTYPE_OPENDRAIN(AUX0) | \ - PIN_OTYPE_OPENDRAIN(SRV0_TIM3_CH1) | \ - PIN_OTYPE_OPENDRAIN(SRV1_TIM3_CH2) | \ + PIN_OTYPE_PUSHPULL(SERVO0) | \ + PIN_OTYPE_PUSHPULL(SERVO1) | \ PIN_OTYPE_OPENDRAIN(XB_ASSO) | \ PIN_OTYPE_OPENDRAIN(USB_VBUS) | \ PIN_OTYPE_OPENDRAIN(SD_DETECT) | \ @@ -381,8 +381,8 @@ PIN_OSPEED_SPEED_VERYLOW(AUX1) | \ PIN_OSPEED_SPEED_VERYLOW(VBAT_MEAS) | \ PIN_OSPEED_SPEED_VERYLOW(AUX0) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV0_TIM3_CH1) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV1_TIM3_CH2) | \ + PIN_OSPEED_SPEED_HIGH(SERVO0) | \ + PIN_OSPEED_SPEED_HIGH(SERVO1) | \ PIN_OSPEED_SPEED_VERYLOW(XB_ASSO) | \ PIN_OSPEED_SPEED_VERYLOW(USB_VBUS) | \ PIN_OSPEED_SPEED_VERYLOW(SD_DETECT) | \ @@ -398,8 +398,8 @@ PIN_PUPDR_PULLDOWN(AUX1) | \ PIN_PUPDR_FLOATING(VBAT_MEAS) | \ PIN_PUPDR_PULLDOWN(AUX0) | \ - PIN_PUPDR_PULLDOWN(SRV0_TIM3_CH1) | \ - PIN_PUPDR_PULLDOWN(SRV1_TIM3_CH2) | \ + PIN_PUPDR_FLOATING(SERVO0) | \ + PIN_PUPDR_FLOATING(SERVO1) | \ PIN_PUPDR_FLOATING(XB_ASSO) | \ PIN_PUPDR_PULLDOWN(USB_VBUS) | \ PIN_PUPDR_PULLUP(SD_DETECT) | \ @@ -415,8 +415,8 @@ PIN_ODR_LEVEL_HIGH(AUX1) | \ PIN_ODR_LEVEL_LOW(VBAT_MEAS) | \ PIN_ODR_LEVEL_HIGH(AUX0) | \ - PIN_ODR_LEVEL_HIGH(SRV0_TIM3_CH1) | \ - PIN_ODR_LEVEL_HIGH(SRV1_TIM3_CH2) | \ + PIN_ODR_LEVEL_LOW(SERVO0) | \ + PIN_ODR_LEVEL_LOW(SERVO1) | \ PIN_ODR_LEVEL_LOW(XB_ASSO) | \ PIN_ODR_LEVEL_LOW(USB_VBUS) | \ PIN_ODR_LEVEL_LOW(SD_DETECT) | \ @@ -432,8 +432,8 @@ PIN_AFIO_AF(AUX1, 0) | \ PIN_AFIO_AF(VBAT_MEAS, 0) | \ PIN_AFIO_AF(AUX0, 0) | \ - PIN_AFIO_AF(SRV0_TIM3_CH1, 0) | \ - PIN_AFIO_AF(SRV1_TIM3_CH2, 0)) + PIN_AFIO_AF(SERVO0, 2) | \ + PIN_AFIO_AF(SERVO1, 2)) #define VAL_GPIOA_AFRH (PIN_AFIO_AF(XB_ASSO, 0) | \ PIN_AFIO_AF(USB_VBUS, 0) | \ @@ -444,8 +444,8 @@ PIN_AFIO_AF(SWCLK, 0) | \ PIN_AFIO_AF(SPI1_CS, 0)) -#define VAL_GPIOB_MODER (PIN_MODE_INPUT(SRV2_TIM3_CH3) | \ - PIN_MODE_INPUT(SRV3_TIM3_CH4) | \ +#define VAL_GPIOB_MODER (PIN_MODE_ALTERNATE(SERVO2) | \ + PIN_MODE_ALTERNATE(SERVO3) | \ PIN_MODE_INPUT(RC1) | \ PIN_MODE_ALTERNATE(SPI1_SCK) | \ PIN_MODE_ALTERNATE(SPI1_MISO) | \ @@ -461,8 +461,8 @@ PIN_MODE_OUTPUT(DIS_C) | \ PIN_MODE_OUTPUT(DIS_DP)) -#define VAL_GPIOB_OTYPER (PIN_OTYPE_OPENDRAIN(SRV2_TIM3_CH3) | \ - PIN_OTYPE_OPENDRAIN(SRV3_TIM3_CH4) | \ +#define VAL_GPIOB_OTYPER (PIN_OTYPE_PUSHPULL(SERVO2) | \ + PIN_OTYPE_PUSHPULL(SERVO3) | \ PIN_OTYPE_OPENDRAIN(RC1) | \ PIN_OTYPE_PUSHPULL(SPI1_SCK) | \ PIN_OTYPE_PUSHPULL(SPI1_MISO) | \ @@ -478,8 +478,8 @@ PIN_OTYPE_PUSHPULL(DIS_C) | \ PIN_OTYPE_PUSHPULL(DIS_DP)) -#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(SRV2_TIM3_CH3) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV3_TIM3_CH4) | \ +#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_SPEED_HIGH(SERVO2) | \ + PIN_OSPEED_SPEED_HIGH(SERVO3) | \ PIN_OSPEED_SPEED_VERYLOW(RC1) | \ PIN_OSPEED_SPEED_HIGH(SPI1_SCK) | \ PIN_OSPEED_SPEED_HIGH(SPI1_MISO) | \ @@ -495,8 +495,8 @@ PIN_OSPEED_SPEED_VERYLOW(DIS_C) | \ PIN_OSPEED_SPEED_VERYLOW(DIS_DP)) -#define VAL_GPIOB_PUPDR (PIN_PUPDR_PULLDOWN(SRV2_TIM3_CH3) | \ - PIN_PUPDR_PULLDOWN(SRV3_TIM3_CH4) | \ +#define VAL_GPIOB_PUPDR (PIN_PUPDR_FLOATING(SERVO2) | \ + PIN_PUPDR_FLOATING(SERVO3) | \ PIN_PUPDR_PULLDOWN(RC1) | \ PIN_PUPDR_FLOATING(SPI1_SCK) | \ PIN_PUPDR_FLOATING(SPI1_MISO) | \ @@ -512,8 +512,8 @@ PIN_PUPDR_FLOATING(DIS_C) | \ PIN_PUPDR_FLOATING(DIS_DP)) -#define VAL_GPIOB_ODR (PIN_ODR_LEVEL_HIGH(SRV2_TIM3_CH3) | \ - PIN_ODR_LEVEL_HIGH(SRV3_TIM3_CH4) | \ +#define VAL_GPIOB_ODR (PIN_ODR_LEVEL_LOW(SERVO2) | \ + PIN_ODR_LEVEL_LOW(SERVO3) | \ PIN_ODR_LEVEL_HIGH(RC1) | \ PIN_ODR_LEVEL_HIGH(SPI1_SCK) | \ PIN_ODR_LEVEL_HIGH(SPI1_MISO) | \ @@ -529,8 +529,8 @@ PIN_ODR_LEVEL_LOW(DIS_C) | \ PIN_ODR_LEVEL_LOW(DIS_DP)) -#define VAL_GPIOB_AFRL (PIN_AFIO_AF(SRV2_TIM3_CH3, 0) | \ - PIN_AFIO_AF(SRV3_TIM3_CH4, 0) | \ +#define VAL_GPIOB_AFRL (PIN_AFIO_AF(SERVO2, 2) | \ + PIN_AFIO_AF(SERVO3, 2) | \ PIN_AFIO_AF(RC1, 0) | \ PIN_AFIO_AF(SPI1_SCK, 5) | \ PIN_AFIO_AF(SPI1_MISO, 5) | \ @@ -662,10 +662,10 @@ PIN_MODE_ALTERNATE(USART3_RX) | \ PIN_MODE_OUTPUT(LED3) | \ PIN_MODE_OUTPUT(LED4) | \ - PIN_MODE_INPUT(SRV4_TIM4_CH1) | \ - PIN_MODE_INPUT(SRV5_TIM4_CH2) | \ - PIN_MODE_INPUT(SRV6_TIM4_CH3) | \ - PIN_MODE_INPUT(SRV7_TIM4_CH4)) + PIN_MODE_ALTERNATE(SERVO4) | \ + PIN_MODE_ALTERNATE(SERVO5) | \ + PIN_MODE_ALTERNATE(SERVO6) | \ + PIN_MODE_ALTERNATE(SERVO7)) #define VAL_GPIOD_OTYPER (PIN_OTYPE_PUSHPULL(CAN1_RX) | \ PIN_OTYPE_PUSHPULL(CAN1_TX) | \ @@ -679,10 +679,10 @@ PIN_OTYPE_PUSHPULL(USART3_RX) | \ PIN_OTYPE_PUSHPULL(LED3) | \ PIN_OTYPE_PUSHPULL(LED4) | \ - PIN_OTYPE_OPENDRAIN(SRV4_TIM4_CH1) | \ - PIN_OTYPE_OPENDRAIN(SRV5_TIM4_CH2) | \ - PIN_OTYPE_OPENDRAIN(SRV6_TIM4_CH3) | \ - PIN_OTYPE_OPENDRAIN(SRV7_TIM4_CH4)) + PIN_OTYPE_PUSHPULL(SERVO4) | \ + PIN_OTYPE_PUSHPULL(SERVO5) | \ + PIN_OTYPE_PUSHPULL(SERVO6) | \ + PIN_OTYPE_PUSHPULL(SERVO7)) #define VAL_GPIOD_OSPEEDR (PIN_OSPEED_SPEED_HIGH(CAN1_RX) | \ PIN_OSPEED_SPEED_HIGH(CAN1_TX) | \ @@ -696,10 +696,10 @@ PIN_OSPEED_SPEED_HIGH(USART3_RX) | \ PIN_OSPEED_SPEED_VERYLOW(LED3) | \ PIN_OSPEED_SPEED_VERYLOW(LED4) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV4_TIM4_CH1) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV5_TIM4_CH2) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV6_TIM4_CH3) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV7_TIM4_CH4)) + PIN_OSPEED_SPEED_HIGH(SERVO4) | \ + PIN_OSPEED_SPEED_HIGH(SERVO5) | \ + PIN_OSPEED_SPEED_HIGH(SERVO6) | \ + PIN_OSPEED_SPEED_HIGH(SERVO7)) #define VAL_GPIOD_PUPDR (PIN_PUPDR_FLOATING(CAN1_RX) | \ PIN_PUPDR_FLOATING(CAN1_TX) | \ @@ -713,10 +713,10 @@ PIN_PUPDR_FLOATING(USART3_RX) | \ PIN_PUPDR_FLOATING(LED3) | \ PIN_PUPDR_FLOATING(LED4) | \ - PIN_PUPDR_PULLDOWN(SRV4_TIM4_CH1) | \ - PIN_PUPDR_PULLDOWN(SRV5_TIM4_CH2) | \ - PIN_PUPDR_PULLDOWN(SRV6_TIM4_CH3) | \ - PIN_PUPDR_PULLDOWN(SRV7_TIM4_CH4)) + PIN_PUPDR_FLOATING(SERVO4) | \ + PIN_PUPDR_FLOATING(SERVO5) | \ + PIN_PUPDR_FLOATING(SERVO6) | \ + PIN_PUPDR_FLOATING(SERVO7)) #define VAL_GPIOD_ODR (PIN_ODR_LEVEL_HIGH(CAN1_RX) | \ PIN_ODR_LEVEL_HIGH(CAN1_TX) | \ @@ -730,10 +730,10 @@ PIN_ODR_LEVEL_HIGH(USART3_RX) | \ PIN_ODR_LEVEL_LOW(LED3) | \ PIN_ODR_LEVEL_LOW(LED4) | \ - PIN_ODR_LEVEL_HIGH(SRV4_TIM4_CH1) | \ - PIN_ODR_LEVEL_HIGH(SRV5_TIM4_CH2) | \ - PIN_ODR_LEVEL_HIGH(SRV6_TIM4_CH3) | \ - PIN_ODR_LEVEL_HIGH(SRV7_TIM4_CH4)) + PIN_ODR_LEVEL_LOW(SERVO4) | \ + PIN_ODR_LEVEL_LOW(SERVO5) | \ + PIN_ODR_LEVEL_LOW(SERVO6) | \ + PIN_ODR_LEVEL_LOW(SERVO7)) #define VAL_GPIOD_AFRL (PIN_AFIO_AF(CAN1_RX, 9) | \ PIN_AFIO_AF(CAN1_TX, 9) | \ @@ -748,10 +748,10 @@ PIN_AFIO_AF(USART3_RX, 7) | \ PIN_AFIO_AF(LED3, 0) | \ PIN_AFIO_AF(LED4, 0) | \ - PIN_AFIO_AF(SRV4_TIM4_CH1, 0) | \ - PIN_AFIO_AF(SRV5_TIM4_CH2, 0) | \ - PIN_AFIO_AF(SRV6_TIM4_CH3, 0) | \ - PIN_AFIO_AF(SRV7_TIM4_CH4, 0)) + PIN_AFIO_AF(SERVO4, 2) | \ + PIN_AFIO_AF(SERVO5, 2) | \ + PIN_AFIO_AF(SERVO6, 2) | \ + PIN_AFIO_AF(SERVO7, 2)) #define VAL_GPIOE_MODER (PIN_MODE_ALTERNATE(UART8_RX) | \ PIN_MODE_ALTERNATE(UART8_TX) | \ @@ -1474,6 +1474,10 @@ PIN_AFIO_AF(PK14, 0) | \ PIN_AFIO_AF(PK15, 0)) +#define AF_SERVO0 2U +#define AF_LINE_SERVO0 2U +#define AF_SERVO1 2U +#define AF_LINE_SERVO1 2U #define AF_OTG_FS_DM 10U #define AF_LINE_OTG_FS_DM 10U #define AF_OTG_FS_DP 10U @@ -1482,6 +1486,10 @@ #define AF_LINE_SWDIO 0U #define AF_SWCLK 0U #define AF_LINE_SWCLK 0U +#define AF_SERVO2 2U +#define AF_LINE_SERVO2 2U +#define AF_SERVO3 2U +#define AF_LINE_SERVO3 2U #define AF_SPI1_SCK 5U #define AF_LINE_SPI1_SCK 5U #define AF_SPI1_MISO 5U @@ -1524,6 +1532,14 @@ #define AF_LINE_USART3_TX 7U #define AF_USART3_RX 7U #define AF_LINE_USART3_RX 7U +#define AF_SERVO4 2U +#define AF_LINE_SERVO4 2U +#define AF_SERVO5 2U +#define AF_LINE_SERVO5 2U +#define AF_SERVO6 2U +#define AF_LINE_SERVO6 2U +#define AF_SERVO7 2U +#define AF_LINE_SERVO7 2U #define AF_UART8_RX 8U #define AF_LINE_UART8_RX 8U #define AF_UART8_TX 8U @@ -1534,6 +1550,77 @@ #define AF_LINE_OSC_OUT 0U +#define SERVO0_TIM 3 +#define SERVO0_TIM_FN CH +#define SERVO0_TIM_CH 1 +#define SERVO0_TIM_AF 2 +#define SERVO1_TIM 3 +#define SERVO1_TIM_FN CH +#define SERVO1_TIM_CH 2 +#define SERVO1_TIM_AF 2 +#define SERVO2_TIM 3 +#define SERVO2_TIM_FN CH +#define SERVO2_TIM_CH 3 +#define SERVO2_TIM_AF 2 +#define SERVO3_TIM 3 +#define SERVO3_TIM_FN CH +#define SERVO3_TIM_CH 4 +#define SERVO3_TIM_AF 2 +#define SERVO4_TIM 4 +#define SERVO4_TIM_FN CH +#define SERVO4_TIM_CH 1 +#define SERVO4_TIM_AF 2 +#define SERVO5_TIM 4 +#define SERVO5_TIM_FN CH +#define SERVO5_TIM_CH 2 +#define SERVO5_TIM_AF 2 +#define SERVO6_TIM 4 +#define SERVO6_TIM_FN CH +#define SERVO6_TIM_CH 3 +#define SERVO6_TIM_AF 2 +#define SERVO7_TIM 4 +#define SERVO7_TIM_FN CH +#define SERVO7_TIM_CH 4 +#define SERVO7_TIM_AF 2 + +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_AUX3, \ + LINE_AUX2, \ + LINE_AUX1, \ + LINE_AUX0, \ + LINE_SERVO1, \ + LINE_SPI1_CS, \ + LINE_SERVO2, \ + LINE_SERVO3, \ + LINE_LED1, \ + LINE_LED2, \ + LINE_AUX5, \ + LINE_AUX4, \ + LINE_AUX6, \ + LINE_AUX7, \ + LINE_LED3, \ + LINE_LED4, \ + LINE_SERVO4, \ + LINE_SERVO5, \ + LINE_SERVO6, \ + LINE_SERVO7 +#define ENERGY_SAVE_INPUT_SIZE 20 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/chimera/chibios/v1.0/board.mk b/sw/airborne/boards/chimera/chibios/v1.0/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/chimera/chibios/v1.0/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/chimera/chibios/v1.0/chimera.h b/sw/airborne/boards/chimera/chibios/v1.0/chimera.h index 8c454b81f5..2d8654f9a8 100644 --- a/sw/airborne/boards/chimera/chibios/v1.0/chimera.h +++ b/sw/airborne/boards/chimera/chibios/v1.0/chimera.h @@ -13,10 +13,10 @@ */ /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK - +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* * LEDs @@ -210,165 +210,143 @@ /* * PWM defines */ +/* + * PWM defines + */ +#if defined(LINE_SERVO0) #ifndef USE_PWM0 #define USE_PWM0 1 #endif #if USE_PWM0 #define PWM_SERVO_0 0 -#define PWM_SERVO_0_GPIO GPIOA -#define PWM_SERVO_0_PIN GPIO6 -#define PWM_SERVO_0_AF GPIO_AF2 -#define PWM_SERVO_0_DRIVER PWMD3 -#define PWM_SERVO_0_CHANNEL 0 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_GPIO PAL_PORT(LINE_SERVO0) +#define PWM_SERVO_0_PIN PAL_PAD(LINE_SERVO0) +#define PWM_SERVO_0_AF AF_LINE_SERVO0 +#define PWM_SERVO_0_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO0_TIM) +#define PWM_SERVO_0_CHANNEL (SERVO0_TIM_CH-1) +#define PWM_SERVO_0_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO0_TIM) +#endif #endif +#if defined(LINE_SERVO1) #ifndef USE_PWM1 #define USE_PWM1 1 #endif #if USE_PWM1 #define PWM_SERVO_1 1 -#define PWM_SERVO_1_GPIO GPIOA -#define PWM_SERVO_1_PIN GPIO7 -#define PWM_SERVO_1_AF GPIO_AF2 -#define PWM_SERVO_1_DRIVER PWMD3 -#define PWM_SERVO_1_CHANNEL 1 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1) +#define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1) +#define PWM_SERVO_1_AF AF_LINE_SERVO1 +#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM) +#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1) +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM) +#endif #endif +#if defined(LINE_SERVO2) #ifndef USE_PWM2 #define USE_PWM2 1 #endif #if USE_PWM2 #define PWM_SERVO_2 2 -#define PWM_SERVO_2_GPIO GPIOB -#define PWM_SERVO_2_PIN GPIO0 -#define PWM_SERVO_2_AF GPIO_AF2 -#define PWM_SERVO_2_DRIVER PWMD3 -#define PWM_SERVO_2_CHANNEL 2 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2) +#define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2) +#define PWM_SERVO_2_AF AF_LINE_SERVO2 +#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM) +#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1) +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM) +#endif #endif +#if defined(LINE_SERVO3) #ifndef USE_PWM3 #define USE_PWM3 1 #endif #if USE_PWM3 #define PWM_SERVO_3 3 -#define PWM_SERVO_3_GPIO GPIOB -#define PWM_SERVO_3_PIN GPIO1 -#define PWM_SERVO_3_AF GPIO_AF2 -#define PWM_SERVO_3_DRIVER PWMD3 -#define PWM_SERVO_3_CHANNEL 3 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3) +#define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3) +#define PWM_SERVO_3_AF AF_LINE_SERVO3 +#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM) +#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1) +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM) +#endif #endif +#if defined(LINE_SERVO4) #ifndef USE_PWM4 #define USE_PWM4 1 #endif #if USE_PWM4 #define PWM_SERVO_4 4 -#define PWM_SERVO_4_GPIO GPIOD -#define PWM_SERVO_4_PIN GPIO12 -#define PWM_SERVO_4_AF GPIO_AF2 -#define PWM_SERVO_4_DRIVER PWMD4 -#define PWM_SERVO_4_CHANNEL 0 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4) +#define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4) +#define PWM_SERVO_4_AF AF_LINE_SERVO4 +#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM) +#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1) +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM) +#endif #endif +#if defined(LINE_SERVO5) #ifndef USE_PWM5 #define USE_PWM5 1 #endif #if USE_PWM5 #define PWM_SERVO_5 5 -#define PWM_SERVO_5_GPIO GPIOD -#define PWM_SERVO_5_PIN GPIO13 -#define PWM_SERVO_5_AF GPIO_AF2 -#define PWM_SERVO_5_DRIVER PWMD4 -#define PWM_SERVO_5_CHANNEL 1 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5) +#define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5) +#define PWM_SERVO_5_AF AF_LINE_SERVO5 +#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM) +#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1) +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM) +#endif #endif +#if defined(LINE_SERVO6) #ifndef USE_PWM6 #define USE_PWM6 1 #endif #if USE_PWM6 #define PWM_SERVO_6 6 -#define PWM_SERVO_6_GPIO GPIOD -#define PWM_SERVO_6_PIN GPIO14 -#define PWM_SERVO_6_AF GPIO_AF2 -#define PWM_SERVO_6_DRIVER PWMD4 -#define PWM_SERVO_6_CHANNEL 2 -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6) +#define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6) +#define PWM_SERVO_6_AF AF_LINE_SERVO6 +#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM) +#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1) +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM) +#endif #endif -#ifndef USE_PWM6 -#define USE_PWM6 1 +#if defined(LINE_SERVO7) +#ifndef USE_PWM7 +#define USE_PWM7 1 #endif #if USE_PWM7 #define PWM_SERVO_7 7 -#define PWM_SERVO_7_GPIO GPIOD -#define PWM_SERVO_7_PIN GPIO15 -#define PWM_SERVO_7_AF GPIO_AF2 -#define PWM_SERVO_7_DRIVER PWMD4 -#define PWM_SERVO_7_CHANNEL 3 -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_7_GPIO PAL_PORT(LINE_SERVO7) +#define PWM_SERVO_7_PIN PAL_PAD(LINE_SERVO7) +#define PWM_SERVO_7_AF AF_LINE_SERVO7 +#define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO7_TIM) +#define PWM_SERVO_7_CHANNEL (SERVO7_TIM_CH-1) +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO7_TIM) +#endif #endif -// TODO PWM on AUX pins - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 +#if defined(LINE_SERVO8) +#ifndef USE_PWM8 +#define USE_PWM8 1 +#endif +#if USE_PWM8 +#define PWM_SERVO_8 8 +#define PWM_SERVO_8_GPIO PAL_PORT(LINE_SERVO8) +#define PWM_SERVO_8_PIN PAL_PAD(LINE_SERVO8) +#define PWM_SERVO_8_AF AF_LINE_SERVO8 +#define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO8_TIM) +#define PWM_SERVO_8_CHANNEL (SERVO8_TIM_CH-1) +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO8_TIM) #endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_0_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 #endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - { PWM_SERVO_7_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} /** * UART2 (with optional flow control activated by default) diff --git a/sw/airborne/boards/crazyflie/chibios/v2.1/board.c b/sw/airborne/boards/crazyflie/chibios/v2.1/board.c deleted file mode 100644 index 1b64a9202b..0000000000 --- a/sw/airborne/boards/crazyflie/chibios/v2.1/board.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return !palReadLine(LINE_SDIO_DETECT); -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { -} - diff --git a/sw/airborne/boards/crazyflie/chibios/v2.1/board.mk b/sw/airborne/boards/crazyflie/chibios/v2.1/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/crazyflie/chibios/v2.1/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/crazyflie/chibios/v2.1/crazyflie.h b/sw/airborne/boards/crazyflie/chibios/v2.1/crazyflie.h index 82a1333761..3f9efda885 100644 --- a/sw/airborne/boards/crazyflie/chibios/v2.1/crazyflie.h +++ b/sw/airborne/boards/crazyflie/chibios/v2.1/crazyflie.h @@ -82,9 +82,7 @@ #define PWM_SERVO_1_AF AF_MOTOR1 #define PWM_SERVO_1_DRIVER PWMD2 #define PWM_SERVO_1_CHANNEL 1 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF pwmcfg2 #endif #ifndef USE_PWM2 @@ -97,9 +95,7 @@ #define PWM_SERVO_2_AF AF_MOTOR2 #define PWM_SERVO_2_DRIVER PWMD2 #define PWM_SERVO_2_CHANNEL 3 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF pwmcfg2 #endif #ifndef USE_PWM3 @@ -112,9 +108,7 @@ #define PWM_SERVO_3_AF AF_MOTOR3 #define PWM_SERVO_3_DRIVER PWMD2 #define PWM_SERVO_3_CHANNEL 0 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF pwmcfg2 #endif #ifndef USE_PWM4 @@ -127,9 +121,7 @@ #define PWM_SERVO_4_AF AF_MOTOR4 #define PWM_SERVO_4_DRIVER PWMD4 #define PWM_SERVO_4_CHANNEL 3 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF pwmcfg4 #endif // servo index starting at 1 + regular servos + aux servos @@ -144,46 +136,9 @@ // than 128 kHz // It is also needed to redefined PWM_CMD_TO_US to get the proper converstion // from command to clock pulses number - #define PWM_CMD_TO_US(_t) (_t) - -#ifdef STM32_PWM_USE_TIM2 -#define PWM_CONF_TIM2 STM32_PWM_USE_TIM2 -#else -#define PWM_CONF_TIM2 1 -#endif -#define PWM_CONF2_DEF { \ - 84000000, \ - 256, \ - NULL, \ - { \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 -#endif -#define PWM_CONF4_DEF { \ - 84000000, \ - 256, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} +#define PWM_FREQUENCY 84000000 +#define SERVO_HZ (PWM_FREQUENCY / 256) // 328125 /** * UART2 E_TX2 diff --git a/sw/airborne/boards/crazyflie/chibios/v2.1/mcuconf.h b/sw/airborne/boards/crazyflie/chibios/v2.1/mcuconf.h index e2c0264510..0d92f7e437 100644 --- a/sw/airborne/boards/crazyflie/chibios/v2.1/mcuconf.h +++ b/sw/airborne/boards/crazyflie/chibios/v2.1/mcuconf.h @@ -86,6 +86,28 @@ #define STM32_IRQ_EXTI21_PRIORITY 15 #define STM32_IRQ_EXTI22_PRIORITY 15 +#define STM32_IRQ_TIM1_BRK_TIM9_PRIORITY 7 +#define STM32_IRQ_TIM1_UP_TIM10_PRIORITY 7 +#define STM32_IRQ_TIM1_TRGCO_TIM11_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 + /* * ADC driver system settings. */ diff --git a/sw/airborne/boards/cube/orange/Makefile b/sw/airborne/boards/cube/orange/Makefile new file mode 100644 index 0000000000..c720ec330d --- /dev/null +++ b/sw/airborne/boards/cube/orange/Makefile @@ -0,0 +1,9 @@ +# file board.h is generated from file board.cfg by a script which is hosted here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/boardGen.pl + +# documentation is here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/DOC/boardGen.pdf + +board.h: board.cfg Makefile + boardGen.pl --no-pp-line $< $@ + diff --git a/sw/airborne/boards/cube/orange/board.cfg b/sw/airborne/boards/cube/orange/board.cfg new file mode 100644 index 0000000000..02c23924a9 --- /dev/null +++ b/sw/airborne/boards/cube/orange/board.cfg @@ -0,0 +1,166 @@ +MCU_MODEL = STM32H743VITx +CHIBIOS_VERSION = 3.0 + +HEADER +/* + * Board identifier. + */ +#define BOARD_CUBE_ORANGE +#define BOARD_NAME "ProfiCNC Cube Orange" + +/* + * Board oscillators-related settings. + */ +#if !defined(STM32_LSECLK) +#define STM32_LSECLK 32768U +#endif + +#define STM32_LSEDRV (3U << 3U) + +#if !defined(STM32_HSECLK) +#define STM32_HSECLK 24000000U +#endif + +/* + * MCU type as defined in the ST header. + */ +#define STM32H743xx + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_1 +#endif + +/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/ +#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE +#define ADC_CHANNEL_CURRENT ADC_2 +#endif + +/* Default powerbrick values */ +#define DefaultVoltageOfAdc(adc) ((3.3f/65536.0f) * 13.38f * adc) +#define DefaultMilliAmpereOfAdc(adc) ((3.3f/65536.0f) * 39.877f * adc) + +/* Battery monitoring for file closing */ +#define SDLOG_BAT_ADC ADCD1 +#define SDLOG_BAT_CHAN AD1_1_CHANNEL + +CONFIG + + +# PIN NAME PERIPH_TYPE AF_NUMBER or +# PIN NAME FUNCTION PP_or_OPENDRAIN PIN_SPEED PULL_RESISTOR INITIAL_LEVEL AF_NUMBER +# SPEED : SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH +# +# DEFAULT AND SYS +# +# 'SYS' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'ADC' => ['ANALOG', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_LOW'], +# 'PWM' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_LOW'], +# 'ICU' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'I2C' => ['ALTERNATE', 'OPENDRAIN', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'], +# 'SPI' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'UART' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'], +# 'OTG' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'ETH' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'FSMC' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'SDIO' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'], +# 'SDIOCK' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'CAN' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'DCMI' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'], +# 'LED' => ['OUTPUT', 'PUSHPULL', 'SPEED_VERYLOW', 'FLOATING', 'LEVEL_LOW'], +# 'PASSIVE' => ['INPUT', 'PUSHPULL', 'SPEED_VERYLOW', 'FLOATING', 'LEVEL_LOW']); +# +# SYSTEM +A13 SWDIO SYS AF:DEBUG_JTMS-SWDIO +A14 SWCLK SYS AF:DEBUG_JTCK-SWCLK +H00 OSC_IN SYS AF0 +H01 OSC_OUT SYS AF0 + +# DEFAULT +DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0 + +# ACTIVE PINS +PA00 UART4_TX UART AF:UART4_TX # GPS +PA01 UART4_RX UART AF:UART4_RX # GPS +PA02 ADC1 ADC ADC1_INP14 () # BATT_VOLTAGE_SENS +PA03 ADC2 ADC ADC1_INP15 () # BATT_CURRENT_SENS +PA04 ADC3 ADC ADC1_INP18 () # VDD_5V_SENS +PA05 SPI1_SCK SPI AF:SPI1_SCK +PA06 SPI1_MISO SPI AF:SPI1_MISO +PA07 SPI1_MOSI SPI AF:SPI1_MOSI +PA08 VDD_5V_PERIPH_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW # INV +PA09 USB_VBUS INPUT PULLDOWN +PA10 UART1_RX UART AF:USART1_RX # IO debug console +PA11 USB_DM OTG AF:USB_OTG_FS_DM +PA12 USB_DP OTG AF:USB_OTG_FS_DP +PA15 ALARM OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH + +PB00 SPI_SLAVE0_DRDY PASSIVE # EXTERNAL +PB01 SPI_SLAVE0 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV EXTERNAL +PB04 PWM_VOLT_SEL OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW +PB05 VDD_BRICK_VALID PASSIVE # INV +PB06 CAN2_TX CAN AF:FDCAN2_TX +PB07 VDD_BACKUP_VALID PASSIVE # INV +PB08 I2C1_SCL I2C AF:I2C1_SCL +PB09 I2C1_SDA I2C AF:I2C1_SDA +PB10 I2C2_SCL I2C AF:I2C2_SCL +PB11 I2C2_SDA I2C AF:I2C2_SDA +PB12 CAN2_RX CAN AF:FDCAN2_RX +PB13 SPI2_SCK SPI AF:SPI2_SCK # FRAM +PB14 SPI2_MISO SPI AF:SPI2_MISO # FRAM +PB15 SPI2_MOSI SPI AF:SPI2_MOSI # FRAM + +PC00 VBUS_VALID PASSIVE # INV +PC01 SPI_SLAVE1 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INT_MAG_CS +PC02 SPI_SLAVE2 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV MPU_CS +PC03 ADC6 ADC ADC3_INP1 () # AUX_POWER +PC04 ADC4 ADC ADC1_INP4 () # AUX_ADC2 +PC05 ADC5 ADC ADC1_INP8 () # PRESSURE_SENS +PC06 UART6_TX UART AF:USART6_TX # InterMCU to IO +PC07 UART6_RX UART AF:USART6_RX # InterMCU to IO +PC08 SDIO_D0 SDIO AF:SDMMC1_D0 +PC09 SDIO_D1 SDIO AF:SDMMC1_D1 +PC10 SDIO_D2 SDIO AF:SDMMC1_D2 +PC11 SDIO_D3 SDIO AF:SDMMC1_D3 +PC12 SDIO_CK SDIOCK AF:SDMMC1_CK +PC13 SPI_SLAVE3 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV GYRO_EXT_CS +PC14 SPI_SLAVE4 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV BARO_EXT_CS +PC15 SPI_SLAVE5 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV ACCEL_MAG_EXT_CS + +PD00 CAN1_RX CAN AF:FDCAN1_RX +PD01 CAN1_TX CAN AF:FDCAN1_TX +PD02 SDIO_CMD SDIO AF:SDMMC1_CMD +PD03 UART2_CTS PASSIVE # TELEM1 +PD04 UART2_RTS PASSIVE # TELEM1 +PD05 UART2_TX UART AF:USART2_TX # TELEM1 +PD06 UART2_RX UART AF:USART2_RX # TELEM1 +PD07 SPI_SLAVE6 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV BARO_CS +PD08 UART3_TX UART AF:USART3_TX # TELEM2 +PD09 UART3_RX UART AF:USART3_RX # TELEM2 +PD10 SPI_SLAVE7 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV FRAM_CS +PD11 UART3_CTS PASSIVE # TELEM2 +PD12 UART3_RTS PASSIVE # TELEM2 +PD13 SERVO5 PWM AF:TIM4_CH2 () +PD14 SERVO6 PWM AF:TIM4_CH3 () +PD15 MPU_DRDY PASSIVE + +PE00 UART8_RX UART AF:UART8_RX # GPS2 +PE01 UART8_TX UART AF:UART8_TX # GPS2 +PE02 SPI4_SCK SPI AF:SPI4_SCK # EXTERNAL +PE03 VDD_3V3_SENSORS_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PE04 SPI_SLAVE8 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # INV MPU_EXT_CS +PE05 SPI4_MISO SPI AF:SPI4_MISO # EXTERNAL +PE06 SPI4_MOSI SPI AF:SPI4_MOSI # EXTERNAL +PE07 UART7_RX UART AF:UART7_RX +PE08 UART7_TX UART AF:UART7_TX +PE09 SERVO4 PWM AF:TIM1_CH1 () +PE10 VDD_5V_HIPOWER_OC PASSIVE # INV +PE11 SERVO3 PWM AF:TIM1_CH2 () +PE12 LED1 LED # LED_AMBER +PE13 SERVO2 PWM AF:TIM1_CH3 () +PE14 SERVO1 PWM AF:TIM1_CH4 () +PE15 VDD_5V_PERIPH_OC PASSIVE # INV + +# GROUPS +GROUP ENERGY_SAVE_INPUTS %NAME=~/^SERVO[0-9]+|LED[0-9]+|SPI_SLAVE[0-9]+$/ +GROUP ENERGY_SAVE_LOWS %NAME=~/^VDD_3V3_SENSORS_EN|VDD_5V_PERIPH_EN|PWM_VOLT_SEL$/ diff --git a/sw/airborne/boards/cube/orange/board.h b/sw/airborne/boards/cube/orange/board.h new file mode 100644 index 0000000000..d1f5b30f1c --- /dev/null +++ b/sw/airborne/boards/cube/orange/board.h @@ -0,0 +1,1691 @@ +/* + ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#pragma once + +/* + * Board identifier. + */ +#define BOARD_CUBE_ORANGE +#define BOARD_NAME "ProfiCNC Cube Orange" + +/* + * Board oscillators-related settings. + */ +#if !defined(STM32_LSECLK) +#define STM32_LSECLK 32768U +#endif + +#define STM32_LSEDRV (3U << 3U) + +#if !defined(STM32_HSECLK) +#define STM32_HSECLK 24000000U +#endif + +/* + * MCU type as defined in the ST header. + */ +#define STM32H743xx + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_1 +#endif + +/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/ +#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE +#define ADC_CHANNEL_CURRENT ADC_2 +#endif + +/* Default powerbrick values */ +#define DefaultVoltageOfAdc(adc) ((3.3f/65536.0f) * 13.38f * adc) +#define DefaultMilliAmpereOfAdc(adc) ((3.3f/65536.0f) * 39.877f * adc) + +/* Battery monitoring for file closing */ +#define SDLOG_BAT_ADC ADCD1 +#define SDLOG_BAT_CHAN AD1_1_CHANNEL + +/* + * Include generic board file + */ +//#include "arch/chibios/board.h" + +/* + * IO pins assignments. + */ +#define PA00_UART4_TX 0U +#define PA01_UART4_RX 1U +#define PA02_ADC1 2U +#define PA03_ADC2 3U +#define PA04_ADC3 4U +#define PA05_SPI1_SCK 5U +#define PA06_SPI1_MISO 6U +#define PA07_SPI1_MOSI 7U +#define PA08_VDD_5V_PERIPH_EN 8U +#define PA09_USB_VBUS 9U +#define PA10_UART1_RX 10U +#define PA11_USB_DM 11U +#define PA12_USB_DP 12U +#define PA13_SWDIO 13U +#define PA14_SWCLK 14U +#define PA15_ALARM 15U + +#define PB00_SPI_SLAVE0_DRDY 0U +#define PB01_SPI_SLAVE0 1U +#define PB02 2U +#define PB03 3U +#define PB04_PWM_VOLT_SEL 4U +#define PB05_VDD_BRICK_VALID 5U +#define PB06_CAN2_TX 6U +#define PB07_VDD_BACKUP_VALID 7U +#define PB08_I2C1_SCL 8U +#define PB09_I2C1_SDA 9U +#define PB10_I2C2_SCL 10U +#define PB11_I2C2_SDA 11U +#define PB12_CAN2_RX 12U +#define PB13_SPI2_SCK 13U +#define PB14_SPI2_MISO 14U +#define PB15_SPI2_MOSI 15U + +#define PC00_VBUS_VALID 0U +#define PC01_SPI_SLAVE1 1U +#define PC02_SPI_SLAVE2 2U +#define PC03_ADC6 3U +#define PC04_ADC4 4U +#define PC05_ADC5 5U +#define PC06_UART6_TX 6U +#define PC07_UART6_RX 7U +#define PC08_SDIO_D0 8U +#define PC09_SDIO_D1 9U +#define PC10_SDIO_D2 10U +#define PC11_SDIO_D3 11U +#define PC12_SDIO_CK 12U +#define PC13_SPI_SLAVE3 13U +#define PC14_SPI_SLAVE4 14U +#define PC15_SPI_SLAVE5 15U + +#define PD00_CAN1_RX 0U +#define PD01_CAN1_TX 1U +#define PD02_SDIO_CMD 2U +#define PD03_UART2_CTS 3U +#define PD04_UART2_RTS 4U +#define PD05_UART2_TX 5U +#define PD06_UART2_RX 6U +#define PD07_SPI_SLAVE6 7U +#define PD08_UART3_TX 8U +#define PD09_UART3_RX 9U +#define PD10_SPI_SLAVE7 10U +#define PD11_UART3_CTS 11U +#define PD12_UART3_RTS 12U +#define PD13_SERVO5 13U +#define PD14_SERVO6 14U +#define PD15_MPU_DRDY 15U + +#define PE00_UART8_RX 0U +#define PE01_UART8_TX 1U +#define PE02_SPI4_SCK 2U +#define PE03_VDD_3V3_SENSORS_EN 3U +#define PE04_SPI_SLAVE8 4U +#define PE05_SPI4_MISO 5U +#define PE06_SPI4_MOSI 6U +#define PE07_UART7_RX 7U +#define PE08_UART7_TX 8U +#define PE09_SERVO4 9U +#define PE10_VDD_5V_HIPOWER_OC 10U +#define PE11_SERVO3 11U +#define PE12_LED1 12U +#define PE13_SERVO2 13U +#define PE14_SERVO1 14U +#define PE15_VDD_5V_PERIPH_OC 15U + +#define PF00 0U +#define PF01 1U +#define PF02 2U +#define PF03 3U +#define PF04 4U +#define PF05 5U +#define PF06 6U +#define PF07 7U +#define PF08 8U +#define PF09 9U +#define PF10 10U +#define PF11 11U +#define PF12 12U +#define PF13 13U +#define PF14 14U +#define PF15 15U + +#define PG00 0U +#define PG01 1U +#define PG02 2U +#define PG03 3U +#define PG04 4U +#define PG05 5U +#define PG06 6U +#define PG07 7U +#define PG08 8U +#define PG09 9U +#define PG10 10U +#define PG11 11U +#define PG12 12U +#define PG13 13U +#define PG14 14U +#define PG15 15U + +#define PH00_OSC_IN 0U +#define PH01_OSC_OUT 1U +#define PH02 2U +#define PH03 3U +#define PH04 4U +#define PH05 5U +#define PH06 6U +#define PH07 7U +#define PH08 8U +#define PH09 9U +#define PH10 10U +#define PH11 11U +#define PH12 12U +#define PH13 13U +#define PH14 14U +#define PH15 15U + +#define PI00 0U +#define PI01 1U +#define PI02 2U +#define PI03 3U +#define PI04 4U +#define PI05 5U +#define PI06 6U +#define PI07 7U +#define PI08 8U +#define PI09 9U +#define PI10 10U +#define PI11 11U +#define PI12 12U +#define PI13 13U +#define PI14 14U +#define PI15 15U + +#define PJ00 0U +#define PJ01 1U +#define PJ02 2U +#define PJ03 3U +#define PJ04 4U +#define PJ05 5U +#define PJ06 6U +#define PJ07 7U +#define PJ08 8U +#define PJ09 9U +#define PJ10 10U +#define PJ11 11U +#define PJ12 12U +#define PJ13 13U +#define PJ14 14U +#define PJ15 15U + +#define PK00 0U +#define PK01 1U +#define PK02 2U +#define PK03 3U +#define PK04 4U +#define PK05 5U +#define PK06 6U +#define PK07 7U +#define PK08 8U +#define PK09 9U +#define PK10 10U +#define PK11 11U +#define PK12 12U +#define PK13 13U +#define PK14 14U +#define PK15 15U + +/* + * IO lines assignments. + */ +#define LINE_UART4_TX PAL_LINE(GPIOA, 0U) +#define LINE_UART4_RX PAL_LINE(GPIOA, 1U) +#define LINE_ADC1 PAL_LINE(GPIOA, 2U) +#define LINE_ADC2 PAL_LINE(GPIOA, 3U) +#define LINE_ADC3 PAL_LINE(GPIOA, 4U) +#define LINE_SPI1_SCK PAL_LINE(GPIOA, 5U) +#define LINE_SPI1_MISO PAL_LINE(GPIOA, 6U) +#define LINE_SPI1_MOSI PAL_LINE(GPIOA, 7U) +#define LINE_VDD_5V_PERIPH_EN PAL_LINE(GPIOA, 8U) +#define LINE_USB_VBUS PAL_LINE(GPIOA, 9U) +#define LINE_UART1_RX PAL_LINE(GPIOA, 10U) +#define LINE_USB_DM PAL_LINE(GPIOA, 11U) +#define LINE_USB_DP PAL_LINE(GPIOA, 12U) +#define LINE_SWDIO PAL_LINE(GPIOA, 13U) +#define LINE_SWCLK PAL_LINE(GPIOA, 14U) +#define LINE_ALARM PAL_LINE(GPIOA, 15U) + +#define LINE_SPI_SLAVE0_DRDY PAL_LINE(GPIOB, 0U) +#define LINE_SPI_SLAVE0 PAL_LINE(GPIOB, 1U) +#define LINE_PWM_VOLT_SEL PAL_LINE(GPIOB, 4U) +#define LINE_VDD_BRICK_VALID PAL_LINE(GPIOB, 5U) +#define LINE_CAN2_TX PAL_LINE(GPIOB, 6U) +#define LINE_VDD_BACKUP_VALID PAL_LINE(GPIOB, 7U) +#define LINE_I2C1_SCL PAL_LINE(GPIOB, 8U) +#define LINE_I2C1_SDA PAL_LINE(GPIOB, 9U) +#define LINE_I2C2_SCL PAL_LINE(GPIOB, 10U) +#define LINE_I2C2_SDA PAL_LINE(GPIOB, 11U) +#define LINE_CAN2_RX PAL_LINE(GPIOB, 12U) +#define LINE_SPI2_SCK PAL_LINE(GPIOB, 13U) +#define LINE_SPI2_MISO PAL_LINE(GPIOB, 14U) +#define LINE_SPI2_MOSI PAL_LINE(GPIOB, 15U) + +#define LINE_VBUS_VALID PAL_LINE(GPIOC, 0U) +#define LINE_SPI_SLAVE1 PAL_LINE(GPIOC, 1U) +#define LINE_SPI_SLAVE2 PAL_LINE(GPIOC, 2U) +#define LINE_ADC6 PAL_LINE(GPIOC, 3U) +#define LINE_ADC4 PAL_LINE(GPIOC, 4U) +#define LINE_ADC5 PAL_LINE(GPIOC, 5U) +#define LINE_UART6_TX PAL_LINE(GPIOC, 6U) +#define LINE_UART6_RX PAL_LINE(GPIOC, 7U) +#define LINE_SDIO_D0 PAL_LINE(GPIOC, 8U) +#define LINE_SDIO_D1 PAL_LINE(GPIOC, 9U) +#define LINE_SDIO_D2 PAL_LINE(GPIOC, 10U) +#define LINE_SDIO_D3 PAL_LINE(GPIOC, 11U) +#define LINE_SDIO_CK PAL_LINE(GPIOC, 12U) +#define LINE_SPI_SLAVE3 PAL_LINE(GPIOC, 13U) +#define LINE_SPI_SLAVE4 PAL_LINE(GPIOC, 14U) +#define LINE_SPI_SLAVE5 PAL_LINE(GPIOC, 15U) + +#define LINE_CAN1_RX PAL_LINE(GPIOD, 0U) +#define LINE_CAN1_TX PAL_LINE(GPIOD, 1U) +#define LINE_SDIO_CMD PAL_LINE(GPIOD, 2U) +#define LINE_UART2_CTS PAL_LINE(GPIOD, 3U) +#define LINE_UART2_RTS PAL_LINE(GPIOD, 4U) +#define LINE_UART2_TX PAL_LINE(GPIOD, 5U) +#define LINE_UART2_RX PAL_LINE(GPIOD, 6U) +#define LINE_SPI_SLAVE6 PAL_LINE(GPIOD, 7U) +#define LINE_UART3_TX PAL_LINE(GPIOD, 8U) +#define LINE_UART3_RX PAL_LINE(GPIOD, 9U) +#define LINE_SPI_SLAVE7 PAL_LINE(GPIOD, 10U) +#define LINE_UART3_CTS PAL_LINE(GPIOD, 11U) +#define LINE_UART3_RTS PAL_LINE(GPIOD, 12U) +#define LINE_SERVO5 PAL_LINE(GPIOD, 13U) +#define LINE_SERVO6 PAL_LINE(GPIOD, 14U) +#define LINE_MPU_DRDY PAL_LINE(GPIOD, 15U) + +#define LINE_UART8_RX PAL_LINE(GPIOE, 0U) +#define LINE_UART8_TX PAL_LINE(GPIOE, 1U) +#define LINE_SPI4_SCK PAL_LINE(GPIOE, 2U) +#define LINE_VDD_3V3_SENSORS_EN PAL_LINE(GPIOE, 3U) +#define LINE_SPI_SLAVE8 PAL_LINE(GPIOE, 4U) +#define LINE_SPI4_MISO PAL_LINE(GPIOE, 5U) +#define LINE_SPI4_MOSI PAL_LINE(GPIOE, 6U) +#define LINE_UART7_RX PAL_LINE(GPIOE, 7U) +#define LINE_UART7_TX PAL_LINE(GPIOE, 8U) +#define LINE_SERVO4 PAL_LINE(GPIOE, 9U) +#define LINE_VDD_5V_HIPOWER_OC PAL_LINE(GPIOE, 10U) +#define LINE_SERVO3 PAL_LINE(GPIOE, 11U) +#define LINE_LED1 PAL_LINE(GPIOE, 12U) +#define LINE_SERVO2 PAL_LINE(GPIOE, 13U) +#define LINE_SERVO1 PAL_LINE(GPIOE, 14U) +#define LINE_VDD_5V_PERIPH_OC PAL_LINE(GPIOE, 15U) + +#define LINE_OSC_IN PAL_LINE(GPIOH, 0U) +#define LINE_OSC_OUT PAL_LINE(GPIOH, 1U) + + +/* + * I/O ports initial setup, this configuration is established soon after reset + * in the initialization code. + * Please refer to the STM32 Reference Manual for details. + */ +#define PIN_MODE_INPUT(n) (0U << ((n) * 2U)) +#define PIN_MODE_OUTPUT(n) (1U << ((n) * 2U)) +#define PIN_MODE_ALTERNATE(n) (2U << ((n) * 2U)) +#define PIN_MODE_ANALOG(n) (3U << ((n) * 2U)) +#define PIN_ODR_LEVEL_LOW(n) (0U << (n)) +#define PIN_ODR_LEVEL_HIGH(n) (1U << (n)) +#define PIN_OTYPE_PUSHPULL(n) (0U << (n)) +#define PIN_OTYPE_OPENDRAIN(n) (1U << (n)) +#define PIN_OSPEED_SPEED_VERYLOW(n) (0U << ((n) * 2U)) +#define PIN_OSPEED_SPEED_LOW(n) (1U << ((n) * 2U)) +#define PIN_OSPEED_SPEED_MEDIUM(n) (2U << ((n) * 2U)) +#define PIN_OSPEED_SPEED_HIGH(n) (3U << ((n) * 2U)) +#define PIN_PUPDR_FLOATING(n) (0U << ((n) * 2U)) +#define PIN_PUPDR_PULLUP(n) (1U << ((n) * 2U)) +#define PIN_PUPDR_PULLDOWN(n) (2U << ((n) * 2U)) +#define PIN_AFIO_AF(n, v) ((v) << (((n) % 8U) * 4U)) + +#define VAL_GPIOA_MODER (PIN_MODE_ALTERNATE(PA00_UART4_TX) | \ + PIN_MODE_ALTERNATE(PA01_UART4_RX) | \ + PIN_MODE_ANALOG(PA02_ADC1) | \ + PIN_MODE_ANALOG(PA03_ADC2) | \ + PIN_MODE_ANALOG(PA04_ADC3) | \ + PIN_MODE_ALTERNATE(PA05_SPI1_SCK) | \ + PIN_MODE_ALTERNATE(PA06_SPI1_MISO) | \ + PIN_MODE_ALTERNATE(PA07_SPI1_MOSI) | \ + PIN_MODE_OUTPUT(PA08_VDD_5V_PERIPH_EN) | \ + PIN_MODE_INPUT(PA09_USB_VBUS) | \ + PIN_MODE_ALTERNATE(PA10_UART1_RX) | \ + PIN_MODE_ALTERNATE(PA11_USB_DM) | \ + PIN_MODE_ALTERNATE(PA12_USB_DP) | \ + PIN_MODE_ALTERNATE(PA13_SWDIO) | \ + PIN_MODE_ALTERNATE(PA14_SWCLK) | \ + PIN_MODE_OUTPUT(PA15_ALARM)) + +#define VAL_GPIOA_OTYPER (PIN_OTYPE_PUSHPULL(PA00_UART4_TX) | \ + PIN_OTYPE_PUSHPULL(PA01_UART4_RX) | \ + PIN_OTYPE_PUSHPULL(PA02_ADC1) | \ + PIN_OTYPE_PUSHPULL(PA03_ADC2) | \ + PIN_OTYPE_PUSHPULL(PA04_ADC3) | \ + PIN_OTYPE_PUSHPULL(PA05_SPI1_SCK) | \ + PIN_OTYPE_PUSHPULL(PA06_SPI1_MISO) | \ + PIN_OTYPE_PUSHPULL(PA07_SPI1_MOSI) | \ + PIN_OTYPE_PUSHPULL(PA08_VDD_5V_PERIPH_EN) | \ + PIN_OTYPE_OPENDRAIN(PA09_USB_VBUS) | \ + PIN_OTYPE_PUSHPULL(PA10_UART1_RX) | \ + PIN_OTYPE_PUSHPULL(PA11_USB_DM) | \ + PIN_OTYPE_PUSHPULL(PA12_USB_DP) | \ + PIN_OTYPE_PUSHPULL(PA13_SWDIO) | \ + PIN_OTYPE_PUSHPULL(PA14_SWCLK) | \ + PIN_OTYPE_PUSHPULL(PA15_ALARM)) + +#define VAL_GPIOA_OSPEEDR (PIN_OSPEED_SPEED_HIGH(PA00_UART4_TX) | \ + PIN_OSPEED_SPEED_HIGH(PA01_UART4_RX) | \ + PIN_OSPEED_SPEED_VERYLOW(PA02_ADC1) | \ + PIN_OSPEED_SPEED_VERYLOW(PA03_ADC2) | \ + PIN_OSPEED_SPEED_VERYLOW(PA04_ADC3) | \ + PIN_OSPEED_SPEED_HIGH(PA05_SPI1_SCK) | \ + PIN_OSPEED_SPEED_HIGH(PA06_SPI1_MISO) | \ + PIN_OSPEED_SPEED_HIGH(PA07_SPI1_MOSI) | \ + PIN_OSPEED_SPEED_VERYLOW(PA08_VDD_5V_PERIPH_EN) | \ + PIN_OSPEED_SPEED_VERYLOW(PA09_USB_VBUS) | \ + PIN_OSPEED_SPEED_HIGH(PA10_UART1_RX) | \ + PIN_OSPEED_SPEED_HIGH(PA11_USB_DM) | \ + PIN_OSPEED_SPEED_HIGH(PA12_USB_DP) | \ + PIN_OSPEED_SPEED_HIGH(PA13_SWDIO) | \ + PIN_OSPEED_SPEED_HIGH(PA14_SWCLK) | \ + PIN_OSPEED_SPEED_VERYLOW(PA15_ALARM)) + +#define VAL_GPIOA_PUPDR (PIN_PUPDR_FLOATING(PA00_UART4_TX) | \ + PIN_PUPDR_FLOATING(PA01_UART4_RX) | \ + PIN_PUPDR_FLOATING(PA02_ADC1) | \ + PIN_PUPDR_FLOATING(PA03_ADC2) | \ + PIN_PUPDR_FLOATING(PA04_ADC3) | \ + PIN_PUPDR_FLOATING(PA05_SPI1_SCK) | \ + PIN_PUPDR_FLOATING(PA06_SPI1_MISO) | \ + PIN_PUPDR_FLOATING(PA07_SPI1_MOSI) | \ + PIN_PUPDR_FLOATING(PA08_VDD_5V_PERIPH_EN) | \ + PIN_PUPDR_PULLDOWN(PA09_USB_VBUS) | \ + PIN_PUPDR_FLOATING(PA10_UART1_RX) | \ + PIN_PUPDR_FLOATING(PA11_USB_DM) | \ + PIN_PUPDR_FLOATING(PA12_USB_DP) | \ + PIN_PUPDR_FLOATING(PA13_SWDIO) | \ + PIN_PUPDR_FLOATING(PA14_SWCLK) | \ + PIN_PUPDR_FLOATING(PA15_ALARM)) + +#define VAL_GPIOA_ODR (PIN_ODR_LEVEL_HIGH(PA00_UART4_TX) | \ + PIN_ODR_LEVEL_HIGH(PA01_UART4_RX) | \ + PIN_ODR_LEVEL_LOW(PA02_ADC1) | \ + PIN_ODR_LEVEL_LOW(PA03_ADC2) | \ + PIN_ODR_LEVEL_LOW(PA04_ADC3) | \ + PIN_ODR_LEVEL_HIGH(PA05_SPI1_SCK) | \ + PIN_ODR_LEVEL_HIGH(PA06_SPI1_MISO) | \ + PIN_ODR_LEVEL_HIGH(PA07_SPI1_MOSI) | \ + PIN_ODR_LEVEL_LOW(PA08_VDD_5V_PERIPH_EN) | \ + PIN_ODR_LEVEL_LOW(PA09_USB_VBUS) | \ + PIN_ODR_LEVEL_HIGH(PA10_UART1_RX) | \ + PIN_ODR_LEVEL_HIGH(PA11_USB_DM) | \ + PIN_ODR_LEVEL_HIGH(PA12_USB_DP) | \ + PIN_ODR_LEVEL_HIGH(PA13_SWDIO) | \ + PIN_ODR_LEVEL_HIGH(PA14_SWCLK) | \ + PIN_ODR_LEVEL_HIGH(PA15_ALARM)) + +#define VAL_GPIOA_AFRL (PIN_AFIO_AF(PA00_UART4_TX, 8) | \ + PIN_AFIO_AF(PA01_UART4_RX, 8) | \ + PIN_AFIO_AF(PA02_ADC1, 0) | \ + PIN_AFIO_AF(PA03_ADC2, 0) | \ + PIN_AFIO_AF(PA04_ADC3, 0) | \ + PIN_AFIO_AF(PA05_SPI1_SCK, 5) | \ + PIN_AFIO_AF(PA06_SPI1_MISO, 5) | \ + PIN_AFIO_AF(PA07_SPI1_MOSI, 5)) + +#define VAL_GPIOA_AFRH (PIN_AFIO_AF(PA08_VDD_5V_PERIPH_EN, 0) | \ + PIN_AFIO_AF(PA09_USB_VBUS, 0) | \ + PIN_AFIO_AF(PA10_UART1_RX, 7) | \ + PIN_AFIO_AF(PA11_USB_DM, 10) | \ + PIN_AFIO_AF(PA12_USB_DP, 10) | \ + PIN_AFIO_AF(PA13_SWDIO, 0) | \ + PIN_AFIO_AF(PA14_SWCLK, 0) | \ + PIN_AFIO_AF(PA15_ALARM, 0)) + +#define VAL_GPIOB_MODER (PIN_MODE_INPUT(PB00_SPI_SLAVE0_DRDY) | \ + PIN_MODE_OUTPUT(PB01_SPI_SLAVE0) | \ + PIN_MODE_INPUT(PB02) | \ + PIN_MODE_INPUT(PB03) | \ + PIN_MODE_OUTPUT(PB04_PWM_VOLT_SEL) | \ + PIN_MODE_INPUT(PB05_VDD_BRICK_VALID) | \ + PIN_MODE_ALTERNATE(PB06_CAN2_TX) | \ + PIN_MODE_INPUT(PB07_VDD_BACKUP_VALID) | \ + PIN_MODE_ALTERNATE(PB08_I2C1_SCL) | \ + PIN_MODE_ALTERNATE(PB09_I2C1_SDA) | \ + PIN_MODE_ALTERNATE(PB10_I2C2_SCL) | \ + PIN_MODE_ALTERNATE(PB11_I2C2_SDA) | \ + PIN_MODE_ALTERNATE(PB12_CAN2_RX) | \ + PIN_MODE_ALTERNATE(PB13_SPI2_SCK) | \ + PIN_MODE_ALTERNATE(PB14_SPI2_MISO) | \ + PIN_MODE_ALTERNATE(PB15_SPI2_MOSI)) + +#define VAL_GPIOB_OTYPER (PIN_OTYPE_OPENDRAIN(PB00_SPI_SLAVE0_DRDY) | \ + PIN_OTYPE_PUSHPULL(PB01_SPI_SLAVE0) | \ + PIN_OTYPE_PUSHPULL(PB02) | \ + PIN_OTYPE_PUSHPULL(PB03) | \ + PIN_OTYPE_PUSHPULL(PB04_PWM_VOLT_SEL) | \ + PIN_OTYPE_OPENDRAIN(PB05_VDD_BRICK_VALID) | \ + PIN_OTYPE_PUSHPULL(PB06_CAN2_TX) | \ + PIN_OTYPE_OPENDRAIN(PB07_VDD_BACKUP_VALID) | \ + PIN_OTYPE_OPENDRAIN(PB08_I2C1_SCL) | \ + PIN_OTYPE_OPENDRAIN(PB09_I2C1_SDA) | \ + PIN_OTYPE_OPENDRAIN(PB10_I2C2_SCL) | \ + PIN_OTYPE_OPENDRAIN(PB11_I2C2_SDA) | \ + PIN_OTYPE_PUSHPULL(PB12_CAN2_RX) | \ + PIN_OTYPE_PUSHPULL(PB13_SPI2_SCK) | \ + PIN_OTYPE_PUSHPULL(PB14_SPI2_MISO) | \ + PIN_OTYPE_PUSHPULL(PB15_SPI2_MOSI)) + +#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PB00_SPI_SLAVE0_DRDY) | \ + PIN_OSPEED_SPEED_HIGH(PB01_SPI_SLAVE0) | \ + PIN_OSPEED_SPEED_VERYLOW(PB02) | \ + PIN_OSPEED_SPEED_VERYLOW(PB03) | \ + PIN_OSPEED_SPEED_VERYLOW(PB04_PWM_VOLT_SEL) | \ + PIN_OSPEED_SPEED_VERYLOW(PB05_VDD_BRICK_VALID) | \ + PIN_OSPEED_SPEED_HIGH(PB06_CAN2_TX) | \ + PIN_OSPEED_SPEED_VERYLOW(PB07_VDD_BACKUP_VALID) | \ + PIN_OSPEED_SPEED_HIGH(PB08_I2C1_SCL) | \ + PIN_OSPEED_SPEED_HIGH(PB09_I2C1_SDA) | \ + PIN_OSPEED_SPEED_HIGH(PB10_I2C2_SCL) | \ + PIN_OSPEED_SPEED_HIGH(PB11_I2C2_SDA) | \ + PIN_OSPEED_SPEED_HIGH(PB12_CAN2_RX) | \ + PIN_OSPEED_SPEED_HIGH(PB13_SPI2_SCK) | \ + PIN_OSPEED_SPEED_HIGH(PB14_SPI2_MISO) | \ + PIN_OSPEED_SPEED_HIGH(PB15_SPI2_MOSI)) + +#define VAL_GPIOB_PUPDR (PIN_PUPDR_PULLDOWN(PB00_SPI_SLAVE0_DRDY) | \ + PIN_PUPDR_FLOATING(PB01_SPI_SLAVE0) | \ + PIN_PUPDR_PULLDOWN(PB02) | \ + PIN_PUPDR_PULLDOWN(PB03) | \ + PIN_PUPDR_FLOATING(PB04_PWM_VOLT_SEL) | \ + PIN_PUPDR_PULLDOWN(PB05_VDD_BRICK_VALID) | \ + PIN_PUPDR_FLOATING(PB06_CAN2_TX) | \ + PIN_PUPDR_PULLDOWN(PB07_VDD_BACKUP_VALID) | \ + PIN_PUPDR_PULLUP(PB08_I2C1_SCL) | \ + PIN_PUPDR_PULLUP(PB09_I2C1_SDA) | \ + PIN_PUPDR_PULLUP(PB10_I2C2_SCL) | \ + PIN_PUPDR_PULLUP(PB11_I2C2_SDA) | \ + PIN_PUPDR_FLOATING(PB12_CAN2_RX) | \ + PIN_PUPDR_FLOATING(PB13_SPI2_SCK) | \ + PIN_PUPDR_FLOATING(PB14_SPI2_MISO) | \ + PIN_PUPDR_FLOATING(PB15_SPI2_MOSI)) + +#define VAL_GPIOB_ODR (PIN_ODR_LEVEL_HIGH(PB00_SPI_SLAVE0_DRDY) | \ + PIN_ODR_LEVEL_HIGH(PB01_SPI_SLAVE0) | \ + PIN_ODR_LEVEL_LOW(PB02) | \ + PIN_ODR_LEVEL_LOW(PB03) | \ + PIN_ODR_LEVEL_LOW(PB04_PWM_VOLT_SEL) | \ + PIN_ODR_LEVEL_HIGH(PB05_VDD_BRICK_VALID) | \ + PIN_ODR_LEVEL_HIGH(PB06_CAN2_TX) | \ + PIN_ODR_LEVEL_HIGH(PB07_VDD_BACKUP_VALID) | \ + PIN_ODR_LEVEL_HIGH(PB08_I2C1_SCL) | \ + PIN_ODR_LEVEL_HIGH(PB09_I2C1_SDA) | \ + PIN_ODR_LEVEL_HIGH(PB10_I2C2_SCL) | \ + PIN_ODR_LEVEL_HIGH(PB11_I2C2_SDA) | \ + PIN_ODR_LEVEL_HIGH(PB12_CAN2_RX) | \ + PIN_ODR_LEVEL_HIGH(PB13_SPI2_SCK) | \ + PIN_ODR_LEVEL_HIGH(PB14_SPI2_MISO) | \ + PIN_ODR_LEVEL_HIGH(PB15_SPI2_MOSI)) + +#define VAL_GPIOB_AFRL (PIN_AFIO_AF(PB00_SPI_SLAVE0_DRDY, 0) | \ + PIN_AFIO_AF(PB01_SPI_SLAVE0, 0) | \ + PIN_AFIO_AF(PB02, 0) | \ + PIN_AFIO_AF(PB03, 0) | \ + PIN_AFIO_AF(PB04_PWM_VOLT_SEL, 0) | \ + PIN_AFIO_AF(PB05_VDD_BRICK_VALID, 0) | \ + PIN_AFIO_AF(PB06_CAN2_TX, 9) | \ + PIN_AFIO_AF(PB07_VDD_BACKUP_VALID, 0)) + +#define VAL_GPIOB_AFRH (PIN_AFIO_AF(PB08_I2C1_SCL, 4) | \ + PIN_AFIO_AF(PB09_I2C1_SDA, 4) | \ + PIN_AFIO_AF(PB10_I2C2_SCL, 4) | \ + PIN_AFIO_AF(PB11_I2C2_SDA, 4) | \ + PIN_AFIO_AF(PB12_CAN2_RX, 9) | \ + PIN_AFIO_AF(PB13_SPI2_SCK, 5) | \ + PIN_AFIO_AF(PB14_SPI2_MISO, 5) | \ + PIN_AFIO_AF(PB15_SPI2_MOSI, 5)) + +#define VAL_GPIOC_MODER (PIN_MODE_INPUT(PC00_VBUS_VALID) | \ + PIN_MODE_OUTPUT(PC01_SPI_SLAVE1) | \ + PIN_MODE_OUTPUT(PC02_SPI_SLAVE2) | \ + PIN_MODE_ANALOG(PC03_ADC6) | \ + PIN_MODE_ANALOG(PC04_ADC4) | \ + PIN_MODE_ANALOG(PC05_ADC5) | \ + PIN_MODE_ALTERNATE(PC06_UART6_TX) | \ + PIN_MODE_ALTERNATE(PC07_UART6_RX) | \ + PIN_MODE_ALTERNATE(PC08_SDIO_D0) | \ + PIN_MODE_ALTERNATE(PC09_SDIO_D1) | \ + PIN_MODE_ALTERNATE(PC10_SDIO_D2) | \ + PIN_MODE_ALTERNATE(PC11_SDIO_D3) | \ + PIN_MODE_ALTERNATE(PC12_SDIO_CK) | \ + PIN_MODE_OUTPUT(PC13_SPI_SLAVE3) | \ + PIN_MODE_OUTPUT(PC14_SPI_SLAVE4) | \ + PIN_MODE_OUTPUT(PC15_SPI_SLAVE5)) + +#define VAL_GPIOC_OTYPER (PIN_OTYPE_OPENDRAIN(PC00_VBUS_VALID) | \ + PIN_OTYPE_PUSHPULL(PC01_SPI_SLAVE1) | \ + PIN_OTYPE_PUSHPULL(PC02_SPI_SLAVE2) | \ + PIN_OTYPE_PUSHPULL(PC03_ADC6) | \ + PIN_OTYPE_PUSHPULL(PC04_ADC4) | \ + PIN_OTYPE_PUSHPULL(PC05_ADC5) | \ + PIN_OTYPE_PUSHPULL(PC06_UART6_TX) | \ + PIN_OTYPE_PUSHPULL(PC07_UART6_RX) | \ + PIN_OTYPE_PUSHPULL(PC08_SDIO_D0) | \ + PIN_OTYPE_PUSHPULL(PC09_SDIO_D1) | \ + PIN_OTYPE_PUSHPULL(PC10_SDIO_D2) | \ + PIN_OTYPE_PUSHPULL(PC11_SDIO_D3) | \ + PIN_OTYPE_PUSHPULL(PC12_SDIO_CK) | \ + PIN_OTYPE_PUSHPULL(PC13_SPI_SLAVE3) | \ + PIN_OTYPE_PUSHPULL(PC14_SPI_SLAVE4) | \ + PIN_OTYPE_PUSHPULL(PC15_SPI_SLAVE5)) + +#define VAL_GPIOC_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PC00_VBUS_VALID) | \ + PIN_OSPEED_SPEED_HIGH(PC01_SPI_SLAVE1) | \ + PIN_OSPEED_SPEED_HIGH(PC02_SPI_SLAVE2) | \ + PIN_OSPEED_SPEED_VERYLOW(PC03_ADC6) | \ + PIN_OSPEED_SPEED_VERYLOW(PC04_ADC4) | \ + PIN_OSPEED_SPEED_VERYLOW(PC05_ADC5) | \ + PIN_OSPEED_SPEED_HIGH(PC06_UART6_TX) | \ + PIN_OSPEED_SPEED_HIGH(PC07_UART6_RX) | \ + PIN_OSPEED_SPEED_HIGH(PC08_SDIO_D0) | \ + PIN_OSPEED_SPEED_HIGH(PC09_SDIO_D1) | \ + PIN_OSPEED_SPEED_HIGH(PC10_SDIO_D2) | \ + PIN_OSPEED_SPEED_HIGH(PC11_SDIO_D3) | \ + PIN_OSPEED_SPEED_HIGH(PC12_SDIO_CK) | \ + PIN_OSPEED_SPEED_HIGH(PC13_SPI_SLAVE3) | \ + PIN_OSPEED_SPEED_HIGH(PC14_SPI_SLAVE4) | \ + PIN_OSPEED_SPEED_HIGH(PC15_SPI_SLAVE5)) + +#define VAL_GPIOC_PUPDR (PIN_PUPDR_PULLDOWN(PC00_VBUS_VALID) | \ + PIN_PUPDR_FLOATING(PC01_SPI_SLAVE1) | \ + PIN_PUPDR_FLOATING(PC02_SPI_SLAVE2) | \ + PIN_PUPDR_FLOATING(PC03_ADC6) | \ + PIN_PUPDR_FLOATING(PC04_ADC4) | \ + PIN_PUPDR_FLOATING(PC05_ADC5) | \ + PIN_PUPDR_FLOATING(PC06_UART6_TX) | \ + PIN_PUPDR_FLOATING(PC07_UART6_RX) | \ + PIN_PUPDR_PULLUP(PC08_SDIO_D0) | \ + PIN_PUPDR_PULLUP(PC09_SDIO_D1) | \ + PIN_PUPDR_PULLUP(PC10_SDIO_D2) | \ + PIN_PUPDR_PULLUP(PC11_SDIO_D3) | \ + PIN_PUPDR_FLOATING(PC12_SDIO_CK) | \ + PIN_PUPDR_FLOATING(PC13_SPI_SLAVE3) | \ + PIN_PUPDR_FLOATING(PC14_SPI_SLAVE4) | \ + PIN_PUPDR_FLOATING(PC15_SPI_SLAVE5)) + +#define VAL_GPIOC_ODR (PIN_ODR_LEVEL_HIGH(PC00_VBUS_VALID) | \ + PIN_ODR_LEVEL_HIGH(PC01_SPI_SLAVE1) | \ + PIN_ODR_LEVEL_HIGH(PC02_SPI_SLAVE2) | \ + PIN_ODR_LEVEL_LOW(PC03_ADC6) | \ + PIN_ODR_LEVEL_LOW(PC04_ADC4) | \ + PIN_ODR_LEVEL_LOW(PC05_ADC5) | \ + PIN_ODR_LEVEL_HIGH(PC06_UART6_TX) | \ + PIN_ODR_LEVEL_HIGH(PC07_UART6_RX) | \ + PIN_ODR_LEVEL_HIGH(PC08_SDIO_D0) | \ + PIN_ODR_LEVEL_HIGH(PC09_SDIO_D1) | \ + PIN_ODR_LEVEL_HIGH(PC10_SDIO_D2) | \ + PIN_ODR_LEVEL_HIGH(PC11_SDIO_D3) | \ + PIN_ODR_LEVEL_HIGH(PC12_SDIO_CK) | \ + PIN_ODR_LEVEL_HIGH(PC13_SPI_SLAVE3) | \ + PIN_ODR_LEVEL_HIGH(PC14_SPI_SLAVE4) | \ + PIN_ODR_LEVEL_HIGH(PC15_SPI_SLAVE5)) + +#define VAL_GPIOC_AFRL (PIN_AFIO_AF(PC00_VBUS_VALID, 0) | \ + PIN_AFIO_AF(PC01_SPI_SLAVE1, 0) | \ + PIN_AFIO_AF(PC02_SPI_SLAVE2, 0) | \ + PIN_AFIO_AF(PC03_ADC6, 0) | \ + PIN_AFIO_AF(PC04_ADC4, 0) | \ + PIN_AFIO_AF(PC05_ADC5, 0) | \ + PIN_AFIO_AF(PC06_UART6_TX, 7) | \ + PIN_AFIO_AF(PC07_UART6_RX, 7)) + +#define VAL_GPIOC_AFRH (PIN_AFIO_AF(PC08_SDIO_D0, 12) | \ + PIN_AFIO_AF(PC09_SDIO_D1, 12) | \ + PIN_AFIO_AF(PC10_SDIO_D2, 12) | \ + PIN_AFIO_AF(PC11_SDIO_D3, 12) | \ + PIN_AFIO_AF(PC12_SDIO_CK, 12) | \ + PIN_AFIO_AF(PC13_SPI_SLAVE3, 0) | \ + PIN_AFIO_AF(PC14_SPI_SLAVE4, 0) | \ + PIN_AFIO_AF(PC15_SPI_SLAVE5, 0)) + +#define VAL_GPIOD_MODER (PIN_MODE_ALTERNATE(PD00_CAN1_RX) | \ + PIN_MODE_ALTERNATE(PD01_CAN1_TX) | \ + PIN_MODE_ALTERNATE(PD02_SDIO_CMD) | \ + PIN_MODE_INPUT(PD03_UART2_CTS) | \ + PIN_MODE_INPUT(PD04_UART2_RTS) | \ + PIN_MODE_ALTERNATE(PD05_UART2_TX) | \ + PIN_MODE_ALTERNATE(PD06_UART2_RX) | \ + PIN_MODE_OUTPUT(PD07_SPI_SLAVE6) | \ + PIN_MODE_ALTERNATE(PD08_UART3_TX) | \ + PIN_MODE_ALTERNATE(PD09_UART3_RX) | \ + PIN_MODE_OUTPUT(PD10_SPI_SLAVE7) | \ + PIN_MODE_INPUT(PD11_UART3_CTS) | \ + PIN_MODE_INPUT(PD12_UART3_RTS) | \ + PIN_MODE_ALTERNATE(PD13_SERVO5) | \ + PIN_MODE_ALTERNATE(PD14_SERVO6) | \ + PIN_MODE_INPUT(PD15_MPU_DRDY)) + +#define VAL_GPIOD_OTYPER (PIN_OTYPE_PUSHPULL(PD00_CAN1_RX) | \ + PIN_OTYPE_PUSHPULL(PD01_CAN1_TX) | \ + PIN_OTYPE_PUSHPULL(PD02_SDIO_CMD) | \ + PIN_OTYPE_OPENDRAIN(PD03_UART2_CTS) | \ + PIN_OTYPE_OPENDRAIN(PD04_UART2_RTS) | \ + PIN_OTYPE_PUSHPULL(PD05_UART2_TX) | \ + PIN_OTYPE_PUSHPULL(PD06_UART2_RX) | \ + PIN_OTYPE_PUSHPULL(PD07_SPI_SLAVE6) | \ + PIN_OTYPE_PUSHPULL(PD08_UART3_TX) | \ + PIN_OTYPE_PUSHPULL(PD09_UART3_RX) | \ + PIN_OTYPE_PUSHPULL(PD10_SPI_SLAVE7) | \ + PIN_OTYPE_OPENDRAIN(PD11_UART3_CTS) | \ + PIN_OTYPE_OPENDRAIN(PD12_UART3_RTS) | \ + PIN_OTYPE_PUSHPULL(PD13_SERVO5) | \ + PIN_OTYPE_PUSHPULL(PD14_SERVO6) | \ + PIN_OTYPE_OPENDRAIN(PD15_MPU_DRDY)) + +#define VAL_GPIOD_OSPEEDR (PIN_OSPEED_SPEED_HIGH(PD00_CAN1_RX) | \ + PIN_OSPEED_SPEED_HIGH(PD01_CAN1_TX) | \ + PIN_OSPEED_SPEED_HIGH(PD02_SDIO_CMD) | \ + PIN_OSPEED_SPEED_VERYLOW(PD03_UART2_CTS) | \ + PIN_OSPEED_SPEED_VERYLOW(PD04_UART2_RTS) | \ + PIN_OSPEED_SPEED_HIGH(PD05_UART2_TX) | \ + PIN_OSPEED_SPEED_HIGH(PD06_UART2_RX) | \ + PIN_OSPEED_SPEED_HIGH(PD07_SPI_SLAVE6) | \ + PIN_OSPEED_SPEED_HIGH(PD08_UART3_TX) | \ + PIN_OSPEED_SPEED_HIGH(PD09_UART3_RX) | \ + PIN_OSPEED_SPEED_HIGH(PD10_SPI_SLAVE7) | \ + PIN_OSPEED_SPEED_VERYLOW(PD11_UART3_CTS) | \ + PIN_OSPEED_SPEED_VERYLOW(PD12_UART3_RTS) | \ + PIN_OSPEED_SPEED_HIGH(PD13_SERVO5) | \ + PIN_OSPEED_SPEED_HIGH(PD14_SERVO6) | \ + PIN_OSPEED_SPEED_VERYLOW(PD15_MPU_DRDY)) + +#define VAL_GPIOD_PUPDR (PIN_PUPDR_FLOATING(PD00_CAN1_RX) | \ + PIN_PUPDR_FLOATING(PD01_CAN1_TX) | \ + PIN_PUPDR_PULLUP(PD02_SDIO_CMD) | \ + PIN_PUPDR_PULLDOWN(PD03_UART2_CTS) | \ + PIN_PUPDR_PULLDOWN(PD04_UART2_RTS) | \ + PIN_PUPDR_FLOATING(PD05_UART2_TX) | \ + PIN_PUPDR_FLOATING(PD06_UART2_RX) | \ + PIN_PUPDR_FLOATING(PD07_SPI_SLAVE6) | \ + PIN_PUPDR_FLOATING(PD08_UART3_TX) | \ + PIN_PUPDR_FLOATING(PD09_UART3_RX) | \ + PIN_PUPDR_FLOATING(PD10_SPI_SLAVE7) | \ + PIN_PUPDR_PULLDOWN(PD11_UART3_CTS) | \ + PIN_PUPDR_PULLDOWN(PD12_UART3_RTS) | \ + PIN_PUPDR_FLOATING(PD13_SERVO5) | \ + PIN_PUPDR_FLOATING(PD14_SERVO6) | \ + PIN_PUPDR_PULLDOWN(PD15_MPU_DRDY)) + +#define VAL_GPIOD_ODR (PIN_ODR_LEVEL_HIGH(PD00_CAN1_RX) | \ + PIN_ODR_LEVEL_HIGH(PD01_CAN1_TX) | \ + PIN_ODR_LEVEL_HIGH(PD02_SDIO_CMD) | \ + PIN_ODR_LEVEL_HIGH(PD03_UART2_CTS) | \ + PIN_ODR_LEVEL_HIGH(PD04_UART2_RTS) | \ + PIN_ODR_LEVEL_HIGH(PD05_UART2_TX) | \ + PIN_ODR_LEVEL_HIGH(PD06_UART2_RX) | \ + PIN_ODR_LEVEL_HIGH(PD07_SPI_SLAVE6) | \ + PIN_ODR_LEVEL_HIGH(PD08_UART3_TX) | \ + PIN_ODR_LEVEL_HIGH(PD09_UART3_RX) | \ + PIN_ODR_LEVEL_HIGH(PD10_SPI_SLAVE7) | \ + PIN_ODR_LEVEL_HIGH(PD11_UART3_CTS) | \ + PIN_ODR_LEVEL_HIGH(PD12_UART3_RTS) | \ + PIN_ODR_LEVEL_LOW(PD13_SERVO5) | \ + PIN_ODR_LEVEL_LOW(PD14_SERVO6) | \ + PIN_ODR_LEVEL_HIGH(PD15_MPU_DRDY)) + +#define VAL_GPIOD_AFRL (PIN_AFIO_AF(PD00_CAN1_RX, 9) | \ + PIN_AFIO_AF(PD01_CAN1_TX, 9) | \ + PIN_AFIO_AF(PD02_SDIO_CMD, 12) | \ + PIN_AFIO_AF(PD03_UART2_CTS, 0) | \ + PIN_AFIO_AF(PD04_UART2_RTS, 0) | \ + PIN_AFIO_AF(PD05_UART2_TX, 7) | \ + PIN_AFIO_AF(PD06_UART2_RX, 7) | \ + PIN_AFIO_AF(PD07_SPI_SLAVE6, 0)) + +#define VAL_GPIOD_AFRH (PIN_AFIO_AF(PD08_UART3_TX, 7) | \ + PIN_AFIO_AF(PD09_UART3_RX, 7) | \ + PIN_AFIO_AF(PD10_SPI_SLAVE7, 0) | \ + PIN_AFIO_AF(PD11_UART3_CTS, 0) | \ + PIN_AFIO_AF(PD12_UART3_RTS, 0) | \ + PIN_AFIO_AF(PD13_SERVO5, 2) | \ + PIN_AFIO_AF(PD14_SERVO6, 2) | \ + PIN_AFIO_AF(PD15_MPU_DRDY, 0)) + +#define VAL_GPIOE_MODER (PIN_MODE_ALTERNATE(PE00_UART8_RX) | \ + PIN_MODE_ALTERNATE(PE01_UART8_TX) | \ + PIN_MODE_ALTERNATE(PE02_SPI4_SCK) | \ + PIN_MODE_OUTPUT(PE03_VDD_3V3_SENSORS_EN) | \ + PIN_MODE_OUTPUT(PE04_SPI_SLAVE8) | \ + PIN_MODE_ALTERNATE(PE05_SPI4_MISO) | \ + PIN_MODE_ALTERNATE(PE06_SPI4_MOSI) | \ + PIN_MODE_ALTERNATE(PE07_UART7_RX) | \ + PIN_MODE_ALTERNATE(PE08_UART7_TX) | \ + PIN_MODE_ALTERNATE(PE09_SERVO4) | \ + PIN_MODE_INPUT(PE10_VDD_5V_HIPOWER_OC) | \ + PIN_MODE_ALTERNATE(PE11_SERVO3) | \ + PIN_MODE_OUTPUT(PE12_LED1) | \ + PIN_MODE_ALTERNATE(PE13_SERVO2) | \ + PIN_MODE_ALTERNATE(PE14_SERVO1) | \ + PIN_MODE_INPUT(PE15_VDD_5V_PERIPH_OC)) + +#define VAL_GPIOE_OTYPER (PIN_OTYPE_PUSHPULL(PE00_UART8_RX) | \ + PIN_OTYPE_PUSHPULL(PE01_UART8_TX) | \ + PIN_OTYPE_PUSHPULL(PE02_SPI4_SCK) | \ + PIN_OTYPE_PUSHPULL(PE03_VDD_3V3_SENSORS_EN) | \ + PIN_OTYPE_PUSHPULL(PE04_SPI_SLAVE8) | \ + PIN_OTYPE_PUSHPULL(PE05_SPI4_MISO) | \ + PIN_OTYPE_PUSHPULL(PE06_SPI4_MOSI) | \ + PIN_OTYPE_PUSHPULL(PE07_UART7_RX) | \ + PIN_OTYPE_PUSHPULL(PE08_UART7_TX) | \ + PIN_OTYPE_PUSHPULL(PE09_SERVO4) | \ + PIN_OTYPE_OPENDRAIN(PE10_VDD_5V_HIPOWER_OC) | \ + PIN_OTYPE_PUSHPULL(PE11_SERVO3) | \ + PIN_OTYPE_PUSHPULL(PE12_LED1) | \ + PIN_OTYPE_PUSHPULL(PE13_SERVO2) | \ + PIN_OTYPE_PUSHPULL(PE14_SERVO1) | \ + PIN_OTYPE_OPENDRAIN(PE15_VDD_5V_PERIPH_OC)) + +#define VAL_GPIOE_OSPEEDR (PIN_OSPEED_SPEED_HIGH(PE00_UART8_RX) | \ + PIN_OSPEED_SPEED_HIGH(PE01_UART8_TX) | \ + PIN_OSPEED_SPEED_HIGH(PE02_SPI4_SCK) | \ + PIN_OSPEED_SPEED_VERYLOW(PE03_VDD_3V3_SENSORS_EN) | \ + PIN_OSPEED_SPEED_HIGH(PE04_SPI_SLAVE8) | \ + PIN_OSPEED_SPEED_HIGH(PE05_SPI4_MISO) | \ + PIN_OSPEED_SPEED_HIGH(PE06_SPI4_MOSI) | \ + PIN_OSPEED_SPEED_HIGH(PE07_UART7_RX) | \ + PIN_OSPEED_SPEED_HIGH(PE08_UART7_TX) | \ + PIN_OSPEED_SPEED_HIGH(PE09_SERVO4) | \ + PIN_OSPEED_SPEED_VERYLOW(PE10_VDD_5V_HIPOWER_OC) | \ + PIN_OSPEED_SPEED_HIGH(PE11_SERVO3) | \ + PIN_OSPEED_SPEED_VERYLOW(PE12_LED1) | \ + PIN_OSPEED_SPEED_HIGH(PE13_SERVO2) | \ + PIN_OSPEED_SPEED_HIGH(PE14_SERVO1) | \ + PIN_OSPEED_SPEED_VERYLOW(PE15_VDD_5V_PERIPH_OC)) + +#define VAL_GPIOE_PUPDR (PIN_PUPDR_FLOATING(PE00_UART8_RX) | \ + PIN_PUPDR_FLOATING(PE01_UART8_TX) | \ + PIN_PUPDR_FLOATING(PE02_SPI4_SCK) | \ + PIN_PUPDR_FLOATING(PE03_VDD_3V3_SENSORS_EN) | \ + PIN_PUPDR_FLOATING(PE04_SPI_SLAVE8) | \ + PIN_PUPDR_FLOATING(PE05_SPI4_MISO) | \ + PIN_PUPDR_FLOATING(PE06_SPI4_MOSI) | \ + PIN_PUPDR_FLOATING(PE07_UART7_RX) | \ + PIN_PUPDR_FLOATING(PE08_UART7_TX) | \ + PIN_PUPDR_FLOATING(PE09_SERVO4) | \ + PIN_PUPDR_PULLDOWN(PE10_VDD_5V_HIPOWER_OC) | \ + PIN_PUPDR_FLOATING(PE11_SERVO3) | \ + PIN_PUPDR_FLOATING(PE12_LED1) | \ + PIN_PUPDR_FLOATING(PE13_SERVO2) | \ + PIN_PUPDR_FLOATING(PE14_SERVO1) | \ + PIN_PUPDR_PULLDOWN(PE15_VDD_5V_PERIPH_OC)) + +#define VAL_GPIOE_ODR (PIN_ODR_LEVEL_HIGH(PE00_UART8_RX) | \ + PIN_ODR_LEVEL_HIGH(PE01_UART8_TX) | \ + PIN_ODR_LEVEL_HIGH(PE02_SPI4_SCK) | \ + PIN_ODR_LEVEL_HIGH(PE03_VDD_3V3_SENSORS_EN) | \ + PIN_ODR_LEVEL_HIGH(PE04_SPI_SLAVE8) | \ + PIN_ODR_LEVEL_HIGH(PE05_SPI4_MISO) | \ + PIN_ODR_LEVEL_HIGH(PE06_SPI4_MOSI) | \ + PIN_ODR_LEVEL_HIGH(PE07_UART7_RX) | \ + PIN_ODR_LEVEL_HIGH(PE08_UART7_TX) | \ + PIN_ODR_LEVEL_LOW(PE09_SERVO4) | \ + PIN_ODR_LEVEL_HIGH(PE10_VDD_5V_HIPOWER_OC) | \ + PIN_ODR_LEVEL_LOW(PE11_SERVO3) | \ + PIN_ODR_LEVEL_LOW(PE12_LED1) | \ + PIN_ODR_LEVEL_LOW(PE13_SERVO2) | \ + PIN_ODR_LEVEL_LOW(PE14_SERVO1) | \ + PIN_ODR_LEVEL_HIGH(PE15_VDD_5V_PERIPH_OC)) + +#define VAL_GPIOE_AFRL (PIN_AFIO_AF(PE00_UART8_RX, 8) | \ + PIN_AFIO_AF(PE01_UART8_TX, 8) | \ + PIN_AFIO_AF(PE02_SPI4_SCK, 5) | \ + PIN_AFIO_AF(PE03_VDD_3V3_SENSORS_EN, 0) | \ + PIN_AFIO_AF(PE04_SPI_SLAVE8, 0) | \ + PIN_AFIO_AF(PE05_SPI4_MISO, 5) | \ + PIN_AFIO_AF(PE06_SPI4_MOSI, 5) | \ + PIN_AFIO_AF(PE07_UART7_RX, 7)) + +#define VAL_GPIOE_AFRH (PIN_AFIO_AF(PE08_UART7_TX, 7) | \ + PIN_AFIO_AF(PE09_SERVO4, 1) | \ + PIN_AFIO_AF(PE10_VDD_5V_HIPOWER_OC, 0) | \ + PIN_AFIO_AF(PE11_SERVO3, 1) | \ + PIN_AFIO_AF(PE12_LED1, 0) | \ + PIN_AFIO_AF(PE13_SERVO2, 1) | \ + PIN_AFIO_AF(PE14_SERVO1, 1) | \ + PIN_AFIO_AF(PE15_VDD_5V_PERIPH_OC, 0)) + +#define VAL_GPIOF_MODER (PIN_MODE_INPUT(PF00) | \ + PIN_MODE_INPUT(PF01) | \ + PIN_MODE_INPUT(PF02) | \ + PIN_MODE_INPUT(PF03) | \ + PIN_MODE_INPUT(PF04) | \ + PIN_MODE_INPUT(PF05) | \ + PIN_MODE_INPUT(PF06) | \ + PIN_MODE_INPUT(PF07) | \ + PIN_MODE_INPUT(PF08) | \ + PIN_MODE_INPUT(PF09) | \ + PIN_MODE_INPUT(PF10) | \ + PIN_MODE_INPUT(PF11) | \ + PIN_MODE_INPUT(PF12) | \ + PIN_MODE_INPUT(PF13) | \ + PIN_MODE_INPUT(PF14) | \ + PIN_MODE_INPUT(PF15)) + +#define VAL_GPIOF_OTYPER (PIN_OTYPE_PUSHPULL(PF00) | \ + PIN_OTYPE_PUSHPULL(PF01) | \ + PIN_OTYPE_PUSHPULL(PF02) | \ + PIN_OTYPE_PUSHPULL(PF03) | \ + PIN_OTYPE_PUSHPULL(PF04) | \ + PIN_OTYPE_PUSHPULL(PF05) | \ + PIN_OTYPE_PUSHPULL(PF06) | \ + PIN_OTYPE_PUSHPULL(PF07) | \ + PIN_OTYPE_PUSHPULL(PF08) | \ + PIN_OTYPE_PUSHPULL(PF09) | \ + PIN_OTYPE_PUSHPULL(PF10) | \ + PIN_OTYPE_PUSHPULL(PF11) | \ + PIN_OTYPE_PUSHPULL(PF12) | \ + PIN_OTYPE_PUSHPULL(PF13) | \ + PIN_OTYPE_PUSHPULL(PF14) | \ + PIN_OTYPE_PUSHPULL(PF15)) + +#define VAL_GPIOF_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PF00) | \ + PIN_OSPEED_SPEED_VERYLOW(PF01) | \ + PIN_OSPEED_SPEED_VERYLOW(PF02) | \ + PIN_OSPEED_SPEED_VERYLOW(PF03) | \ + PIN_OSPEED_SPEED_VERYLOW(PF04) | \ + PIN_OSPEED_SPEED_VERYLOW(PF05) | \ + PIN_OSPEED_SPEED_VERYLOW(PF06) | \ + PIN_OSPEED_SPEED_VERYLOW(PF07) | \ + PIN_OSPEED_SPEED_VERYLOW(PF08) | \ + PIN_OSPEED_SPEED_VERYLOW(PF09) | \ + PIN_OSPEED_SPEED_VERYLOW(PF10) | \ + PIN_OSPEED_SPEED_VERYLOW(PF11) | \ + PIN_OSPEED_SPEED_VERYLOW(PF12) | \ + PIN_OSPEED_SPEED_VERYLOW(PF13) | \ + PIN_OSPEED_SPEED_VERYLOW(PF14) | \ + PIN_OSPEED_SPEED_VERYLOW(PF15)) + +#define VAL_GPIOF_PUPDR (PIN_PUPDR_PULLDOWN(PF00) | \ + PIN_PUPDR_PULLDOWN(PF01) | \ + PIN_PUPDR_PULLDOWN(PF02) | \ + PIN_PUPDR_PULLDOWN(PF03) | \ + PIN_PUPDR_PULLDOWN(PF04) | \ + PIN_PUPDR_PULLDOWN(PF05) | \ + PIN_PUPDR_PULLDOWN(PF06) | \ + PIN_PUPDR_PULLDOWN(PF07) | \ + PIN_PUPDR_PULLDOWN(PF08) | \ + PIN_PUPDR_PULLDOWN(PF09) | \ + PIN_PUPDR_PULLDOWN(PF10) | \ + PIN_PUPDR_PULLDOWN(PF11) | \ + PIN_PUPDR_PULLDOWN(PF12) | \ + PIN_PUPDR_PULLDOWN(PF13) | \ + PIN_PUPDR_PULLDOWN(PF14) | \ + PIN_PUPDR_PULLDOWN(PF15)) + +#define VAL_GPIOF_ODR (PIN_ODR_LEVEL_LOW(PF00) | \ + PIN_ODR_LEVEL_LOW(PF01) | \ + PIN_ODR_LEVEL_LOW(PF02) | \ + PIN_ODR_LEVEL_LOW(PF03) | \ + PIN_ODR_LEVEL_LOW(PF04) | \ + PIN_ODR_LEVEL_LOW(PF05) | \ + PIN_ODR_LEVEL_LOW(PF06) | \ + PIN_ODR_LEVEL_LOW(PF07) | \ + PIN_ODR_LEVEL_LOW(PF08) | \ + PIN_ODR_LEVEL_LOW(PF09) | \ + PIN_ODR_LEVEL_LOW(PF10) | \ + PIN_ODR_LEVEL_LOW(PF11) | \ + PIN_ODR_LEVEL_LOW(PF12) | \ + PIN_ODR_LEVEL_LOW(PF13) | \ + PIN_ODR_LEVEL_LOW(PF14) | \ + PIN_ODR_LEVEL_LOW(PF15)) + +#define VAL_GPIOF_AFRL (PIN_AFIO_AF(PF00, 0) | \ + PIN_AFIO_AF(PF01, 0) | \ + PIN_AFIO_AF(PF02, 0) | \ + PIN_AFIO_AF(PF03, 0) | \ + PIN_AFIO_AF(PF04, 0) | \ + PIN_AFIO_AF(PF05, 0) | \ + PIN_AFIO_AF(PF06, 0) | \ + PIN_AFIO_AF(PF07, 0)) + +#define VAL_GPIOF_AFRH (PIN_AFIO_AF(PF08, 0) | \ + PIN_AFIO_AF(PF09, 0) | \ + PIN_AFIO_AF(PF10, 0) | \ + PIN_AFIO_AF(PF11, 0) | \ + PIN_AFIO_AF(PF12, 0) | \ + PIN_AFIO_AF(PF13, 0) | \ + PIN_AFIO_AF(PF14, 0) | \ + PIN_AFIO_AF(PF15, 0)) + +#define VAL_GPIOG_MODER (PIN_MODE_INPUT(PG00) | \ + PIN_MODE_INPUT(PG01) | \ + PIN_MODE_INPUT(PG02) | \ + PIN_MODE_INPUT(PG03) | \ + PIN_MODE_INPUT(PG04) | \ + PIN_MODE_INPUT(PG05) | \ + PIN_MODE_INPUT(PG06) | \ + PIN_MODE_INPUT(PG07) | \ + PIN_MODE_INPUT(PG08) | \ + PIN_MODE_INPUT(PG09) | \ + PIN_MODE_INPUT(PG10) | \ + PIN_MODE_INPUT(PG11) | \ + PIN_MODE_INPUT(PG12) | \ + PIN_MODE_INPUT(PG13) | \ + PIN_MODE_INPUT(PG14) | \ + PIN_MODE_INPUT(PG15)) + +#define VAL_GPIOG_OTYPER (PIN_OTYPE_PUSHPULL(PG00) | \ + PIN_OTYPE_PUSHPULL(PG01) | \ + PIN_OTYPE_PUSHPULL(PG02) | \ + PIN_OTYPE_PUSHPULL(PG03) | \ + PIN_OTYPE_PUSHPULL(PG04) | \ + PIN_OTYPE_PUSHPULL(PG05) | \ + PIN_OTYPE_PUSHPULL(PG06) | \ + PIN_OTYPE_PUSHPULL(PG07) | \ + PIN_OTYPE_PUSHPULL(PG08) | \ + PIN_OTYPE_PUSHPULL(PG09) | \ + PIN_OTYPE_PUSHPULL(PG10) | \ + PIN_OTYPE_PUSHPULL(PG11) | \ + PIN_OTYPE_PUSHPULL(PG12) | \ + PIN_OTYPE_PUSHPULL(PG13) | \ + PIN_OTYPE_PUSHPULL(PG14) | \ + PIN_OTYPE_PUSHPULL(PG15)) + +#define VAL_GPIOG_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PG00) | \ + PIN_OSPEED_SPEED_VERYLOW(PG01) | \ + PIN_OSPEED_SPEED_VERYLOW(PG02) | \ + PIN_OSPEED_SPEED_VERYLOW(PG03) | \ + PIN_OSPEED_SPEED_VERYLOW(PG04) | \ + PIN_OSPEED_SPEED_VERYLOW(PG05) | \ + PIN_OSPEED_SPEED_VERYLOW(PG06) | \ + PIN_OSPEED_SPEED_VERYLOW(PG07) | \ + PIN_OSPEED_SPEED_VERYLOW(PG08) | \ + PIN_OSPEED_SPEED_VERYLOW(PG09) | \ + PIN_OSPEED_SPEED_VERYLOW(PG10) | \ + PIN_OSPEED_SPEED_VERYLOW(PG11) | \ + PIN_OSPEED_SPEED_VERYLOW(PG12) | \ + PIN_OSPEED_SPEED_VERYLOW(PG13) | \ + PIN_OSPEED_SPEED_VERYLOW(PG14) | \ + PIN_OSPEED_SPEED_VERYLOW(PG15)) + +#define VAL_GPIOG_PUPDR (PIN_PUPDR_PULLDOWN(PG00) | \ + PIN_PUPDR_PULLDOWN(PG01) | \ + PIN_PUPDR_PULLDOWN(PG02) | \ + PIN_PUPDR_PULLDOWN(PG03) | \ + PIN_PUPDR_PULLDOWN(PG04) | \ + PIN_PUPDR_PULLDOWN(PG05) | \ + PIN_PUPDR_PULLDOWN(PG06) | \ + PIN_PUPDR_PULLDOWN(PG07) | \ + PIN_PUPDR_PULLDOWN(PG08) | \ + PIN_PUPDR_PULLDOWN(PG09) | \ + PIN_PUPDR_PULLDOWN(PG10) | \ + PIN_PUPDR_PULLDOWN(PG11) | \ + PIN_PUPDR_PULLDOWN(PG12) | \ + PIN_PUPDR_PULLDOWN(PG13) | \ + PIN_PUPDR_PULLDOWN(PG14) | \ + PIN_PUPDR_PULLDOWN(PG15)) + +#define VAL_GPIOG_ODR (PIN_ODR_LEVEL_LOW(PG00) | \ + PIN_ODR_LEVEL_LOW(PG01) | \ + PIN_ODR_LEVEL_LOW(PG02) | \ + PIN_ODR_LEVEL_LOW(PG03) | \ + PIN_ODR_LEVEL_LOW(PG04) | \ + PIN_ODR_LEVEL_LOW(PG05) | \ + PIN_ODR_LEVEL_LOW(PG06) | \ + PIN_ODR_LEVEL_LOW(PG07) | \ + PIN_ODR_LEVEL_LOW(PG08) | \ + PIN_ODR_LEVEL_LOW(PG09) | \ + PIN_ODR_LEVEL_LOW(PG10) | \ + PIN_ODR_LEVEL_LOW(PG11) | \ + PIN_ODR_LEVEL_LOW(PG12) | \ + PIN_ODR_LEVEL_LOW(PG13) | \ + PIN_ODR_LEVEL_LOW(PG14) | \ + PIN_ODR_LEVEL_LOW(PG15)) + +#define VAL_GPIOG_AFRL (PIN_AFIO_AF(PG00, 0) | \ + PIN_AFIO_AF(PG01, 0) | \ + PIN_AFIO_AF(PG02, 0) | \ + PIN_AFIO_AF(PG03, 0) | \ + PIN_AFIO_AF(PG04, 0) | \ + PIN_AFIO_AF(PG05, 0) | \ + PIN_AFIO_AF(PG06, 0) | \ + PIN_AFIO_AF(PG07, 0)) + +#define VAL_GPIOG_AFRH (PIN_AFIO_AF(PG08, 0) | \ + PIN_AFIO_AF(PG09, 0) | \ + PIN_AFIO_AF(PG10, 0) | \ + PIN_AFIO_AF(PG11, 0) | \ + PIN_AFIO_AF(PG12, 0) | \ + PIN_AFIO_AF(PG13, 0) | \ + PIN_AFIO_AF(PG14, 0) | \ + PIN_AFIO_AF(PG15, 0)) + +#define VAL_GPIOH_MODER (PIN_MODE_ALTERNATE(PH00_OSC_IN) | \ + PIN_MODE_ALTERNATE(PH01_OSC_OUT) | \ + PIN_MODE_INPUT(PH02) | \ + PIN_MODE_INPUT(PH03) | \ + PIN_MODE_INPUT(PH04) | \ + PIN_MODE_INPUT(PH05) | \ + PIN_MODE_INPUT(PH06) | \ + PIN_MODE_INPUT(PH07) | \ + PIN_MODE_INPUT(PH08) | \ + PIN_MODE_INPUT(PH09) | \ + PIN_MODE_INPUT(PH10) | \ + PIN_MODE_INPUT(PH11) | \ + PIN_MODE_INPUT(PH12) | \ + PIN_MODE_INPUT(PH13) | \ + PIN_MODE_INPUT(PH14) | \ + PIN_MODE_INPUT(PH15)) + +#define VAL_GPIOH_OTYPER (PIN_OTYPE_PUSHPULL(PH00_OSC_IN) | \ + PIN_OTYPE_PUSHPULL(PH01_OSC_OUT) | \ + PIN_OTYPE_PUSHPULL(PH02) | \ + PIN_OTYPE_PUSHPULL(PH03) | \ + PIN_OTYPE_PUSHPULL(PH04) | \ + PIN_OTYPE_PUSHPULL(PH05) | \ + PIN_OTYPE_PUSHPULL(PH06) | \ + PIN_OTYPE_PUSHPULL(PH07) | \ + PIN_OTYPE_PUSHPULL(PH08) | \ + PIN_OTYPE_PUSHPULL(PH09) | \ + PIN_OTYPE_PUSHPULL(PH10) | \ + PIN_OTYPE_PUSHPULL(PH11) | \ + PIN_OTYPE_PUSHPULL(PH12) | \ + PIN_OTYPE_PUSHPULL(PH13) | \ + PIN_OTYPE_PUSHPULL(PH14) | \ + PIN_OTYPE_PUSHPULL(PH15)) + +#define VAL_GPIOH_OSPEEDR (PIN_OSPEED_SPEED_HIGH(PH00_OSC_IN) | \ + PIN_OSPEED_SPEED_HIGH(PH01_OSC_OUT) | \ + PIN_OSPEED_SPEED_VERYLOW(PH02) | \ + PIN_OSPEED_SPEED_VERYLOW(PH03) | \ + PIN_OSPEED_SPEED_VERYLOW(PH04) | \ + PIN_OSPEED_SPEED_VERYLOW(PH05) | \ + PIN_OSPEED_SPEED_VERYLOW(PH06) | \ + PIN_OSPEED_SPEED_VERYLOW(PH07) | \ + PIN_OSPEED_SPEED_VERYLOW(PH08) | \ + PIN_OSPEED_SPEED_VERYLOW(PH09) | \ + PIN_OSPEED_SPEED_VERYLOW(PH10) | \ + PIN_OSPEED_SPEED_VERYLOW(PH11) | \ + PIN_OSPEED_SPEED_VERYLOW(PH12) | \ + PIN_OSPEED_SPEED_VERYLOW(PH13) | \ + PIN_OSPEED_SPEED_VERYLOW(PH14) | \ + PIN_OSPEED_SPEED_VERYLOW(PH15)) + +#define VAL_GPIOH_PUPDR (PIN_PUPDR_FLOATING(PH00_OSC_IN) | \ + PIN_PUPDR_FLOATING(PH01_OSC_OUT) | \ + PIN_PUPDR_PULLDOWN(PH02) | \ + PIN_PUPDR_PULLDOWN(PH03) | \ + PIN_PUPDR_PULLDOWN(PH04) | \ + PIN_PUPDR_PULLDOWN(PH05) | \ + PIN_PUPDR_PULLDOWN(PH06) | \ + PIN_PUPDR_PULLDOWN(PH07) | \ + PIN_PUPDR_PULLDOWN(PH08) | \ + PIN_PUPDR_PULLDOWN(PH09) | \ + PIN_PUPDR_PULLDOWN(PH10) | \ + PIN_PUPDR_PULLDOWN(PH11) | \ + PIN_PUPDR_PULLDOWN(PH12) | \ + PIN_PUPDR_PULLDOWN(PH13) | \ + PIN_PUPDR_PULLDOWN(PH14) | \ + PIN_PUPDR_PULLDOWN(PH15)) + +#define VAL_GPIOH_ODR (PIN_ODR_LEVEL_HIGH(PH00_OSC_IN) | \ + PIN_ODR_LEVEL_HIGH(PH01_OSC_OUT) | \ + PIN_ODR_LEVEL_LOW(PH02) | \ + PIN_ODR_LEVEL_LOW(PH03) | \ + PIN_ODR_LEVEL_LOW(PH04) | \ + PIN_ODR_LEVEL_LOW(PH05) | \ + PIN_ODR_LEVEL_LOW(PH06) | \ + PIN_ODR_LEVEL_LOW(PH07) | \ + PIN_ODR_LEVEL_LOW(PH08) | \ + PIN_ODR_LEVEL_LOW(PH09) | \ + PIN_ODR_LEVEL_LOW(PH10) | \ + PIN_ODR_LEVEL_LOW(PH11) | \ + PIN_ODR_LEVEL_LOW(PH12) | \ + PIN_ODR_LEVEL_LOW(PH13) | \ + PIN_ODR_LEVEL_LOW(PH14) | \ + PIN_ODR_LEVEL_LOW(PH15)) + +#define VAL_GPIOH_AFRL (PIN_AFIO_AF(PH00_OSC_IN, 0) | \ + PIN_AFIO_AF(PH01_OSC_OUT, 0) | \ + PIN_AFIO_AF(PH02, 0) | \ + PIN_AFIO_AF(PH03, 0) | \ + PIN_AFIO_AF(PH04, 0) | \ + PIN_AFIO_AF(PH05, 0) | \ + PIN_AFIO_AF(PH06, 0) | \ + PIN_AFIO_AF(PH07, 0)) + +#define VAL_GPIOH_AFRH (PIN_AFIO_AF(PH08, 0) | \ + PIN_AFIO_AF(PH09, 0) | \ + PIN_AFIO_AF(PH10, 0) | \ + PIN_AFIO_AF(PH11, 0) | \ + PIN_AFIO_AF(PH12, 0) | \ + PIN_AFIO_AF(PH13, 0) | \ + PIN_AFIO_AF(PH14, 0) | \ + PIN_AFIO_AF(PH15, 0)) + +#define VAL_GPIOI_MODER (PIN_MODE_INPUT(PI00) | \ + PIN_MODE_INPUT(PI01) | \ + PIN_MODE_INPUT(PI02) | \ + PIN_MODE_INPUT(PI03) | \ + PIN_MODE_INPUT(PI04) | \ + PIN_MODE_INPUT(PI05) | \ + PIN_MODE_INPUT(PI06) | \ + PIN_MODE_INPUT(PI07) | \ + PIN_MODE_INPUT(PI08) | \ + PIN_MODE_INPUT(PI09) | \ + PIN_MODE_INPUT(PI10) | \ + PIN_MODE_INPUT(PI11) | \ + PIN_MODE_INPUT(PI12) | \ + PIN_MODE_INPUT(PI13) | \ + PIN_MODE_INPUT(PI14) | \ + PIN_MODE_INPUT(PI15)) + +#define VAL_GPIOI_OTYPER (PIN_OTYPE_PUSHPULL(PI00) | \ + PIN_OTYPE_PUSHPULL(PI01) | \ + PIN_OTYPE_PUSHPULL(PI02) | \ + PIN_OTYPE_PUSHPULL(PI03) | \ + PIN_OTYPE_PUSHPULL(PI04) | \ + PIN_OTYPE_PUSHPULL(PI05) | \ + PIN_OTYPE_PUSHPULL(PI06) | \ + PIN_OTYPE_PUSHPULL(PI07) | \ + PIN_OTYPE_PUSHPULL(PI08) | \ + PIN_OTYPE_PUSHPULL(PI09) | \ + PIN_OTYPE_PUSHPULL(PI10) | \ + PIN_OTYPE_PUSHPULL(PI11) | \ + PIN_OTYPE_PUSHPULL(PI12) | \ + PIN_OTYPE_PUSHPULL(PI13) | \ + PIN_OTYPE_PUSHPULL(PI14) | \ + PIN_OTYPE_PUSHPULL(PI15)) + +#define VAL_GPIOI_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PI00) | \ + PIN_OSPEED_SPEED_VERYLOW(PI01) | \ + PIN_OSPEED_SPEED_VERYLOW(PI02) | \ + PIN_OSPEED_SPEED_VERYLOW(PI03) | \ + PIN_OSPEED_SPEED_VERYLOW(PI04) | \ + PIN_OSPEED_SPEED_VERYLOW(PI05) | \ + PIN_OSPEED_SPEED_VERYLOW(PI06) | \ + PIN_OSPEED_SPEED_VERYLOW(PI07) | \ + PIN_OSPEED_SPEED_VERYLOW(PI08) | \ + PIN_OSPEED_SPEED_VERYLOW(PI09) | \ + PIN_OSPEED_SPEED_VERYLOW(PI10) | \ + PIN_OSPEED_SPEED_VERYLOW(PI11) | \ + PIN_OSPEED_SPEED_VERYLOW(PI12) | \ + PIN_OSPEED_SPEED_VERYLOW(PI13) | \ + PIN_OSPEED_SPEED_VERYLOW(PI14) | \ + PIN_OSPEED_SPEED_VERYLOW(PI15)) + +#define VAL_GPIOI_PUPDR (PIN_PUPDR_PULLDOWN(PI00) | \ + PIN_PUPDR_PULLDOWN(PI01) | \ + PIN_PUPDR_PULLDOWN(PI02) | \ + PIN_PUPDR_PULLDOWN(PI03) | \ + PIN_PUPDR_PULLDOWN(PI04) | \ + PIN_PUPDR_PULLDOWN(PI05) | \ + PIN_PUPDR_PULLDOWN(PI06) | \ + PIN_PUPDR_PULLDOWN(PI07) | \ + PIN_PUPDR_PULLDOWN(PI08) | \ + PIN_PUPDR_PULLDOWN(PI09) | \ + PIN_PUPDR_PULLDOWN(PI10) | \ + PIN_PUPDR_PULLDOWN(PI11) | \ + PIN_PUPDR_PULLDOWN(PI12) | \ + PIN_PUPDR_PULLDOWN(PI13) | \ + PIN_PUPDR_PULLDOWN(PI14) | \ + PIN_PUPDR_PULLDOWN(PI15)) + +#define VAL_GPIOI_ODR (PIN_ODR_LEVEL_LOW(PI00) | \ + PIN_ODR_LEVEL_LOW(PI01) | \ + PIN_ODR_LEVEL_LOW(PI02) | \ + PIN_ODR_LEVEL_LOW(PI03) | \ + PIN_ODR_LEVEL_LOW(PI04) | \ + PIN_ODR_LEVEL_LOW(PI05) | \ + PIN_ODR_LEVEL_LOW(PI06) | \ + PIN_ODR_LEVEL_LOW(PI07) | \ + PIN_ODR_LEVEL_LOW(PI08) | \ + PIN_ODR_LEVEL_LOW(PI09) | \ + PIN_ODR_LEVEL_LOW(PI10) | \ + PIN_ODR_LEVEL_LOW(PI11) | \ + PIN_ODR_LEVEL_LOW(PI12) | \ + PIN_ODR_LEVEL_LOW(PI13) | \ + PIN_ODR_LEVEL_LOW(PI14) | \ + PIN_ODR_LEVEL_LOW(PI15)) + +#define VAL_GPIOI_AFRL (PIN_AFIO_AF(PI00, 0) | \ + PIN_AFIO_AF(PI01, 0) | \ + PIN_AFIO_AF(PI02, 0) | \ + PIN_AFIO_AF(PI03, 0) | \ + PIN_AFIO_AF(PI04, 0) | \ + PIN_AFIO_AF(PI05, 0) | \ + PIN_AFIO_AF(PI06, 0) | \ + PIN_AFIO_AF(PI07, 0)) + +#define VAL_GPIOI_AFRH (PIN_AFIO_AF(PI08, 0) | \ + PIN_AFIO_AF(PI09, 0) | \ + PIN_AFIO_AF(PI10, 0) | \ + PIN_AFIO_AF(PI11, 0) | \ + PIN_AFIO_AF(PI12, 0) | \ + PIN_AFIO_AF(PI13, 0) | \ + PIN_AFIO_AF(PI14, 0) | \ + PIN_AFIO_AF(PI15, 0)) + +#define VAL_GPIOJ_MODER (PIN_MODE_INPUT(PJ00) | \ + PIN_MODE_INPUT(PJ01) | \ + PIN_MODE_INPUT(PJ02) | \ + PIN_MODE_INPUT(PJ03) | \ + PIN_MODE_INPUT(PJ04) | \ + PIN_MODE_INPUT(PJ05) | \ + PIN_MODE_INPUT(PJ06) | \ + PIN_MODE_INPUT(PJ07) | \ + PIN_MODE_INPUT(PJ08) | \ + PIN_MODE_INPUT(PJ09) | \ + PIN_MODE_INPUT(PJ10) | \ + PIN_MODE_INPUT(PJ11) | \ + PIN_MODE_INPUT(PJ12) | \ + PIN_MODE_INPUT(PJ13) | \ + PIN_MODE_INPUT(PJ14) | \ + PIN_MODE_INPUT(PJ15)) + +#define VAL_GPIOJ_OTYPER (PIN_OTYPE_PUSHPULL(PJ00) | \ + PIN_OTYPE_PUSHPULL(PJ01) | \ + PIN_OTYPE_PUSHPULL(PJ02) | \ + PIN_OTYPE_PUSHPULL(PJ03) | \ + PIN_OTYPE_PUSHPULL(PJ04) | \ + PIN_OTYPE_PUSHPULL(PJ05) | \ + PIN_OTYPE_PUSHPULL(PJ06) | \ + PIN_OTYPE_PUSHPULL(PJ07) | \ + PIN_OTYPE_PUSHPULL(PJ08) | \ + PIN_OTYPE_PUSHPULL(PJ09) | \ + PIN_OTYPE_PUSHPULL(PJ10) | \ + PIN_OTYPE_PUSHPULL(PJ11) | \ + PIN_OTYPE_PUSHPULL(PJ12) | \ + PIN_OTYPE_PUSHPULL(PJ13) | \ + PIN_OTYPE_PUSHPULL(PJ14) | \ + PIN_OTYPE_PUSHPULL(PJ15)) + +#define VAL_GPIOJ_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PJ00) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ01) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ02) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ03) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ04) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ05) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ06) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ07) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ08) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ09) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ10) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ11) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ12) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ13) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ14) | \ + PIN_OSPEED_SPEED_VERYLOW(PJ15)) + +#define VAL_GPIOJ_PUPDR (PIN_PUPDR_PULLDOWN(PJ00) | \ + PIN_PUPDR_PULLDOWN(PJ01) | \ + PIN_PUPDR_PULLDOWN(PJ02) | \ + PIN_PUPDR_PULLDOWN(PJ03) | \ + PIN_PUPDR_PULLDOWN(PJ04) | \ + PIN_PUPDR_PULLDOWN(PJ05) | \ + PIN_PUPDR_PULLDOWN(PJ06) | \ + PIN_PUPDR_PULLDOWN(PJ07) | \ + PIN_PUPDR_PULLDOWN(PJ08) | \ + PIN_PUPDR_PULLDOWN(PJ09) | \ + PIN_PUPDR_PULLDOWN(PJ10) | \ + PIN_PUPDR_PULLDOWN(PJ11) | \ + PIN_PUPDR_PULLDOWN(PJ12) | \ + PIN_PUPDR_PULLDOWN(PJ13) | \ + PIN_PUPDR_PULLDOWN(PJ14) | \ + PIN_PUPDR_PULLDOWN(PJ15)) + +#define VAL_GPIOJ_ODR (PIN_ODR_LEVEL_LOW(PJ00) | \ + PIN_ODR_LEVEL_LOW(PJ01) | \ + PIN_ODR_LEVEL_LOW(PJ02) | \ + PIN_ODR_LEVEL_LOW(PJ03) | \ + PIN_ODR_LEVEL_LOW(PJ04) | \ + PIN_ODR_LEVEL_LOW(PJ05) | \ + PIN_ODR_LEVEL_LOW(PJ06) | \ + PIN_ODR_LEVEL_LOW(PJ07) | \ + PIN_ODR_LEVEL_LOW(PJ08) | \ + PIN_ODR_LEVEL_LOW(PJ09) | \ + PIN_ODR_LEVEL_LOW(PJ10) | \ + PIN_ODR_LEVEL_LOW(PJ11) | \ + PIN_ODR_LEVEL_LOW(PJ12) | \ + PIN_ODR_LEVEL_LOW(PJ13) | \ + PIN_ODR_LEVEL_LOW(PJ14) | \ + PIN_ODR_LEVEL_LOW(PJ15)) + +#define VAL_GPIOJ_AFRL (PIN_AFIO_AF(PJ00, 0) | \ + PIN_AFIO_AF(PJ01, 0) | \ + PIN_AFIO_AF(PJ02, 0) | \ + PIN_AFIO_AF(PJ03, 0) | \ + PIN_AFIO_AF(PJ04, 0) | \ + PIN_AFIO_AF(PJ05, 0) | \ + PIN_AFIO_AF(PJ06, 0) | \ + PIN_AFIO_AF(PJ07, 0)) + +#define VAL_GPIOJ_AFRH (PIN_AFIO_AF(PJ08, 0) | \ + PIN_AFIO_AF(PJ09, 0) | \ + PIN_AFIO_AF(PJ10, 0) | \ + PIN_AFIO_AF(PJ11, 0) | \ + PIN_AFIO_AF(PJ12, 0) | \ + PIN_AFIO_AF(PJ13, 0) | \ + PIN_AFIO_AF(PJ14, 0) | \ + PIN_AFIO_AF(PJ15, 0)) + +#define VAL_GPIOK_MODER (PIN_MODE_INPUT(PK00) | \ + PIN_MODE_INPUT(PK01) | \ + PIN_MODE_INPUT(PK02) | \ + PIN_MODE_INPUT(PK03) | \ + PIN_MODE_INPUT(PK04) | \ + PIN_MODE_INPUT(PK05) | \ + PIN_MODE_INPUT(PK06) | \ + PIN_MODE_INPUT(PK07) | \ + PIN_MODE_INPUT(PK08) | \ + PIN_MODE_INPUT(PK09) | \ + PIN_MODE_INPUT(PK10) | \ + PIN_MODE_INPUT(PK11) | \ + PIN_MODE_INPUT(PK12) | \ + PIN_MODE_INPUT(PK13) | \ + PIN_MODE_INPUT(PK14) | \ + PIN_MODE_INPUT(PK15)) + +#define VAL_GPIOK_OTYPER (PIN_OTYPE_PUSHPULL(PK00) | \ + PIN_OTYPE_PUSHPULL(PK01) | \ + PIN_OTYPE_PUSHPULL(PK02) | \ + PIN_OTYPE_PUSHPULL(PK03) | \ + PIN_OTYPE_PUSHPULL(PK04) | \ + PIN_OTYPE_PUSHPULL(PK05) | \ + PIN_OTYPE_PUSHPULL(PK06) | \ + PIN_OTYPE_PUSHPULL(PK07) | \ + PIN_OTYPE_PUSHPULL(PK08) | \ + PIN_OTYPE_PUSHPULL(PK09) | \ + PIN_OTYPE_PUSHPULL(PK10) | \ + PIN_OTYPE_PUSHPULL(PK11) | \ + PIN_OTYPE_PUSHPULL(PK12) | \ + PIN_OTYPE_PUSHPULL(PK13) | \ + PIN_OTYPE_PUSHPULL(PK14) | \ + PIN_OTYPE_PUSHPULL(PK15)) + +#define VAL_GPIOK_OSPEEDR (PIN_OSPEED_SPEED_VERYLOW(PK00) | \ + PIN_OSPEED_SPEED_VERYLOW(PK01) | \ + PIN_OSPEED_SPEED_VERYLOW(PK02) | \ + PIN_OSPEED_SPEED_VERYLOW(PK03) | \ + PIN_OSPEED_SPEED_VERYLOW(PK04) | \ + PIN_OSPEED_SPEED_VERYLOW(PK05) | \ + PIN_OSPEED_SPEED_VERYLOW(PK06) | \ + PIN_OSPEED_SPEED_VERYLOW(PK07) | \ + PIN_OSPEED_SPEED_VERYLOW(PK08) | \ + PIN_OSPEED_SPEED_VERYLOW(PK09) | \ + PIN_OSPEED_SPEED_VERYLOW(PK10) | \ + PIN_OSPEED_SPEED_VERYLOW(PK11) | \ + PIN_OSPEED_SPEED_VERYLOW(PK12) | \ + PIN_OSPEED_SPEED_VERYLOW(PK13) | \ + PIN_OSPEED_SPEED_VERYLOW(PK14) | \ + PIN_OSPEED_SPEED_VERYLOW(PK15)) + +#define VAL_GPIOK_PUPDR (PIN_PUPDR_PULLDOWN(PK00) | \ + PIN_PUPDR_PULLDOWN(PK01) | \ + PIN_PUPDR_PULLDOWN(PK02) | \ + PIN_PUPDR_PULLDOWN(PK03) | \ + PIN_PUPDR_PULLDOWN(PK04) | \ + PIN_PUPDR_PULLDOWN(PK05) | \ + PIN_PUPDR_PULLDOWN(PK06) | \ + PIN_PUPDR_PULLDOWN(PK07) | \ + PIN_PUPDR_PULLDOWN(PK08) | \ + PIN_PUPDR_PULLDOWN(PK09) | \ + PIN_PUPDR_PULLDOWN(PK10) | \ + PIN_PUPDR_PULLDOWN(PK11) | \ + PIN_PUPDR_PULLDOWN(PK12) | \ + PIN_PUPDR_PULLDOWN(PK13) | \ + PIN_PUPDR_PULLDOWN(PK14) | \ + PIN_PUPDR_PULLDOWN(PK15)) + +#define VAL_GPIOK_ODR (PIN_ODR_LEVEL_LOW(PK00) | \ + PIN_ODR_LEVEL_LOW(PK01) | \ + PIN_ODR_LEVEL_LOW(PK02) | \ + PIN_ODR_LEVEL_LOW(PK03) | \ + PIN_ODR_LEVEL_LOW(PK04) | \ + PIN_ODR_LEVEL_LOW(PK05) | \ + PIN_ODR_LEVEL_LOW(PK06) | \ + PIN_ODR_LEVEL_LOW(PK07) | \ + PIN_ODR_LEVEL_LOW(PK08) | \ + PIN_ODR_LEVEL_LOW(PK09) | \ + PIN_ODR_LEVEL_LOW(PK10) | \ + PIN_ODR_LEVEL_LOW(PK11) | \ + PIN_ODR_LEVEL_LOW(PK12) | \ + PIN_ODR_LEVEL_LOW(PK13) | \ + PIN_ODR_LEVEL_LOW(PK14) | \ + PIN_ODR_LEVEL_LOW(PK15)) + +#define VAL_GPIOK_AFRL (PIN_AFIO_AF(PK00, 0) | \ + PIN_AFIO_AF(PK01, 0) | \ + PIN_AFIO_AF(PK02, 0) | \ + PIN_AFIO_AF(PK03, 0) | \ + PIN_AFIO_AF(PK04, 0) | \ + PIN_AFIO_AF(PK05, 0) | \ + PIN_AFIO_AF(PK06, 0) | \ + PIN_AFIO_AF(PK07, 0)) + +#define VAL_GPIOK_AFRH (PIN_AFIO_AF(PK08, 0) | \ + PIN_AFIO_AF(PK09, 0) | \ + PIN_AFIO_AF(PK10, 0) | \ + PIN_AFIO_AF(PK11, 0) | \ + PIN_AFIO_AF(PK12, 0) | \ + PIN_AFIO_AF(PK13, 0) | \ + PIN_AFIO_AF(PK14, 0) | \ + PIN_AFIO_AF(PK15, 0)) + +#define AF_PA00_UART4_TX 8U +#define AF_LINE_UART4_TX 8U +#define AF_PA01_UART4_RX 8U +#define AF_LINE_UART4_RX 8U +#define AF_PA05_SPI1_SCK 5U +#define AF_LINE_SPI1_SCK 5U +#define AF_PA06_SPI1_MISO 5U +#define AF_LINE_SPI1_MISO 5U +#define AF_PA07_SPI1_MOSI 5U +#define AF_LINE_SPI1_MOSI 5U +#define AF_PA10_UART1_RX 7U +#define AF_LINE_UART1_RX 7U +#define AF_PA11_USB_DM 10U +#define AF_LINE_USB_DM 10U +#define AF_PA12_USB_DP 10U +#define AF_LINE_USB_DP 10U +#define AF_PA13_SWDIO 0U +#define AF_LINE_SWDIO 0U +#define AF_PA14_SWCLK 0U +#define AF_LINE_SWCLK 0U +#define AF_PB06_CAN2_TX 9U +#define AF_LINE_CAN2_TX 9U +#define AF_PB08_I2C1_SCL 4U +#define AF_LINE_I2C1_SCL 4U +#define AF_PB09_I2C1_SDA 4U +#define AF_LINE_I2C1_SDA 4U +#define AF_PB10_I2C2_SCL 4U +#define AF_LINE_I2C2_SCL 4U +#define AF_PB11_I2C2_SDA 4U +#define AF_LINE_I2C2_SDA 4U +#define AF_PB12_CAN2_RX 9U +#define AF_LINE_CAN2_RX 9U +#define AF_PB13_SPI2_SCK 5U +#define AF_LINE_SPI2_SCK 5U +#define AF_PB14_SPI2_MISO 5U +#define AF_LINE_SPI2_MISO 5U +#define AF_PB15_SPI2_MOSI 5U +#define AF_LINE_SPI2_MOSI 5U +#define AF_PC06_UART6_TX 7U +#define AF_LINE_UART6_TX 7U +#define AF_PC07_UART6_RX 7U +#define AF_LINE_UART6_RX 7U +#define AF_PC08_SDIO_D0 12U +#define AF_LINE_SDIO_D0 12U +#define AF_PC09_SDIO_D1 12U +#define AF_LINE_SDIO_D1 12U +#define AF_PC10_SDIO_D2 12U +#define AF_LINE_SDIO_D2 12U +#define AF_PC11_SDIO_D3 12U +#define AF_LINE_SDIO_D3 12U +#define AF_PC12_SDIO_CK 12U +#define AF_LINE_SDIO_CK 12U +#define AF_PD00_CAN1_RX 9U +#define AF_LINE_CAN1_RX 9U +#define AF_PD01_CAN1_TX 9U +#define AF_LINE_CAN1_TX 9U +#define AF_PD02_SDIO_CMD 12U +#define AF_LINE_SDIO_CMD 12U +#define AF_PD05_UART2_TX 7U +#define AF_LINE_UART2_TX 7U +#define AF_PD06_UART2_RX 7U +#define AF_LINE_UART2_RX 7U +#define AF_PD08_UART3_TX 7U +#define AF_LINE_UART3_TX 7U +#define AF_PD09_UART3_RX 7U +#define AF_LINE_UART3_RX 7U +#define AF_PD13_SERVO5 2U +#define AF_LINE_SERVO5 2U +#define AF_PD14_SERVO6 2U +#define AF_LINE_SERVO6 2U +#define AF_PE00_UART8_RX 8U +#define AF_LINE_UART8_RX 8U +#define AF_PE01_UART8_TX 8U +#define AF_LINE_UART8_TX 8U +#define AF_PE02_SPI4_SCK 5U +#define AF_LINE_SPI4_SCK 5U +#define AF_PE05_SPI4_MISO 5U +#define AF_LINE_SPI4_MISO 5U +#define AF_PE06_SPI4_MOSI 5U +#define AF_LINE_SPI4_MOSI 5U +#define AF_PE07_UART7_RX 7U +#define AF_LINE_UART7_RX 7U +#define AF_PE08_UART7_TX 7U +#define AF_LINE_UART7_TX 7U +#define AF_PE09_SERVO4 1U +#define AF_LINE_SERVO4 1U +#define AF_PE11_SERVO3 1U +#define AF_LINE_SERVO3 1U +#define AF_PE13_SERVO2 1U +#define AF_LINE_SERVO2 1U +#define AF_PE14_SERVO1 1U +#define AF_LINE_SERVO1 1U +#define AF_PH00_OSC_IN 0U +#define AF_LINE_OSC_IN 0U +#define AF_PH01_OSC_OUT 0U +#define AF_LINE_OSC_OUT 0U + + +#define ADC1_ADC 1 +#define ADC1_ADC_FN INP +#define ADC1_ADC_INP 14 +#define ADC2_ADC 1 +#define ADC2_ADC_FN INP +#define ADC2_ADC_INP 15 +#define ADC3_ADC 1 +#define ADC3_ADC_FN INP +#define ADC3_ADC_INP 18 +#define ADC6_ADC 3 +#define ADC6_ADC_FN INP +#define ADC6_ADC_INP 1 +#define ADC4_ADC 1 +#define ADC4_ADC_FN INP +#define ADC4_ADC_INP 4 +#define ADC5_ADC 1 +#define ADC5_ADC_FN INP +#define ADC5_ADC_INP 8 +#define SERVO5_TIM 4 +#define SERVO5_TIM_FN CH +#define SERVO5_TIM_CH 2 +#define SERVO5_TIM_AF 2 +#define SERVO6_TIM 4 +#define SERVO6_TIM_FN CH +#define SERVO6_TIM_CH 3 +#define SERVO6_TIM_AF 2 +#define SERVO4_TIM 1 +#define SERVO4_TIM_FN CH +#define SERVO4_TIM_CH 1 +#define SERVO4_TIM_AF 1 +#define SERVO3_TIM 1 +#define SERVO3_TIM_FN CH +#define SERVO3_TIM_CH 2 +#define SERVO3_TIM_AF 1 +#define SERVO2_TIM 1 +#define SERVO2_TIM_FN CH +#define SERVO2_TIM_CH 3 +#define SERVO2_TIM_AF 1 +#define SERVO1_TIM 1 +#define SERVO1_TIM_FN CH +#define SERVO1_TIM_CH 4 +#define SERVO1_TIM_AF 1 + +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUTS \ + LINE_SPI_SLAVE0, \ + LINE_SPI_SLAVE1, \ + LINE_SPI_SLAVE2, \ + LINE_SPI_SLAVE3, \ + LINE_SPI_SLAVE4, \ + LINE_SPI_SLAVE5, \ + LINE_SPI_SLAVE6, \ + LINE_SPI_SLAVE7, \ + LINE_SERVO5, \ + LINE_SERVO6, \ + LINE_SPI_SLAVE8, \ + LINE_SERVO4, \ + LINE_SERVO3, \ + LINE_LED1, \ + LINE_SERVO2, \ + LINE_SERVO1 +#define ENERGY_SAVE_INPUTS_SIZE 16 + +#define ENERGY_SAVE_LOWS \ + LINE_VDD_5V_PERIPH_EN, \ + LINE_PWM_VOLT_SEL, \ + LINE_VDD_3V3_SENSORS_EN +#define ENERGY_SAVE_LOWS_SIZE 3 + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif + void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + diff --git a/sw/airborne/boards/cube/orange/mcuconf.h b/sw/airborne/boards/cube/orange/mcuconf.h new file mode 100644 index 0000000000..96a2bbfb0e --- /dev/null +++ b/sw/airborne/boards/cube/orange/mcuconf.h @@ -0,0 +1,582 @@ +/* + ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#ifndef MCUCONF_H +#define MCUCONF_H + +/* + * Enforce old versions of the chip + */ +#define STM32_ENFORCE_H7_REV_XY + +/* + * STM32H7xx 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 STM32H7xx_MCUCONF +#define STM32H742_MCUCONF +#define STM32H743_MCUCONF +#define STM32H753_MCUCONF +#define STM32H745_MCUCONF +#define STM32H755_MCUCONF +#define STM32H747_MCUCONF +#define STM32H757_MCUCONF + +/* + * General settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_TARGET_CORE 1 + +/* + * Memory attributes settings. + */ +#define STM32_NOCACHE_ENABLE TRUE +#define STM32_NOCACHE_MPU_REGION MPU_REGION_6 +#define STM32_NOCACHE_RBAR 0x24000000U +#define STM32_NOCACHE_RASR MPU_RASR_SIZE_64K + +/* + * PWR system settings. + * Reading STM32 Reference Manual is required, settings in PWR_CR3 are + * very critical. + * Register constants are taken from the ST header. + */ +#define STM32_VOS STM32_VOS_SCALE1 +#define STM32_PWR_CR1 (PWR_CR1_SVOS_1 | PWR_CR1_SVOS_0) +#define STM32_PWR_CR2 (PWR_CR2_BREN) +#define STM32_PWR_CR3 (PWR_CR3_LDOEN | PWR_CR3_USB33DEN) +#define STM32_PWR_CPUCR 0 + +/* + * Clock tree static settings. + * Reading STM32 Reference Manual is required. + */ +#define STM32_HSI_ENABLED FALSE +#define STM32_LSI_ENABLED FALSE +#define STM32_CSI_ENABLED FALSE +#define STM32_HSI48_ENABLED TRUE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_HSIDIV STM32_HSIDIV_DIV1 + +/* + * PLLs static settings. + * Reading STM32 Reference Manual is required. + */ +#define STM32_PLLSRC STM32_PLLSRC_HSE_CK +#define STM32_PLLCFGR_MASK ~0 +#define STM32_PLL1_ENABLED TRUE +#define STM32_PLL1_P_ENABLED TRUE +#define STM32_PLL1_Q_ENABLED TRUE +#define STM32_PLL1_R_ENABLED TRUE +#define STM32_PLL1_DIVM_VALUE 3 +#define STM32_PLL1_DIVN_VALUE 100 +#define STM32_PLL1_FRACN_VALUE 0 +#define STM32_PLL1_DIVP_VALUE 2 +#define STM32_PLL1_DIVQ_VALUE 10 +#define STM32_PLL1_DIVR_VALUE 2 +#define STM32_PLL2_ENABLED TRUE +#define STM32_PLL2_P_ENABLED TRUE +#define STM32_PLL2_Q_ENABLED TRUE +#define STM32_PLL2_R_ENABLED TRUE +#define STM32_PLL2_DIVM_VALUE 2 +#define STM32_PLL2_DIVN_VALUE 30 +#define STM32_PLL2_FRACN_VALUE 0 +#define STM32_PLL2_DIVP_VALUE 2 +#define STM32_PLL2_DIVQ_VALUE 5 +#define STM32_PLL2_DIVR_VALUE 1 +#define STM32_PLL3_ENABLED TRUE +#define STM32_PLL3_P_ENABLED TRUE +#define STM32_PLL3_Q_ENABLED TRUE +#define STM32_PLL3_R_ENABLED TRUE +#define STM32_PLL3_DIVM_VALUE 6 +#define STM32_PLL3_DIVN_VALUE 72 +#define STM32_PLL3_FRACN_VALUE 0 +#define STM32_PLL3_DIVP_VALUE 2 +#define STM32_PLL3_DIVQ_VALUE 6 +#define STM32_PLL3_DIVR_VALUE 9 + +/* + * Core clocks dynamic settings (can be changed at runtime). + * Reading STM32 Reference Manual is required. + */ +#define STM32_SW STM32_SW_PLL1_P_CK +#define STM32_RTCSEL STM32_RTCSEL_NOCLK +#define STM32_D1CPRE STM32_D1CPRE_DIV1 +#define STM32_D1HPRE STM32_D1HPRE_DIV2 +#define STM32_D1PPRE3 STM32_D1PPRE3_DIV2 +#define STM32_D2PPRE1 STM32_D2PPRE1_DIV2 +#define STM32_D2PPRE2 STM32_D2PPRE2_DIV2 +#define STM32_D3PPRE4 STM32_D3PPRE4_DIV2 + +/* + * Peripherals clocks static settings. + * Reading STM32 Reference Manual is required. + */ +#define STM32_MCO1SEL STM32_MCO1SEL_HSE_CK +#define STM32_MCO1PRE_VALUE 4 +#define STM32_MCO2SEL STM32_MCO2SEL_SYS_CK +#define STM32_MCO2PRE_VALUE 4 +#define STM32_TIMPRE_ENABLE TRUE +#define STM32_HRTIMSEL 0 +#define STM32_STOPKERWUCK 0 +#define STM32_STOPWUCK 0 +#define STM32_RTCPRE_VALUE 8 +#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK +#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK +#define STM32_QSPISEL STM32_QSPISEL_PLL2_R_CK +#define STM32_FMCSEL STM32_FMCSEL_HCLK +#define STM32_SWPSEL STM32_SWPSEL_PCLK1 +#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK +#define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2 +#define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK +#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2 +#define STM32_SPI123SEL STM32_SPI123SEL_PLL1_Q_CK +#define STM32_SAI23SEL STM32_SAI23SEL_PLL1_Q_CK +#define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK +#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1 +#define STM32_CECSEL STM32_CECSEL_DISABLE +#define STM32_USBSEL STM32_USBSEL_PLL3_Q_CK +#define STM32_I2C123SEL STM32_I2C123SEL_PLL3_R_CK +#define STM32_RNGSEL STM32_RNGSEL_HSI48_CK +#define STM32_USART16SEL STM32_USART16SEL_PCLK2 +#define STM32_USART234578SEL STM32_USART234578SEL_PCLK1 +#define STM32_SPI6SEL STM32_SPI6SEL_PCLK4 +#define STM32_SAI4BSEL STM32_SAI4BSEL_PLL1_Q_CK +#define STM32_SAI4ASEL STM32_SAI4ASEL_PLL1_Q_CK +#define STM32_ADCSEL STM32_ADCSEL_PLL3_R_CK +#define STM32_LPTIM345SEL STM32_LPTIM345SEL_PCLK4 +#define STM32_LPTIM2SEL STM32_LPTIM2SEL_PCLK4 +#define STM32_I2C4SEL STM32_I2C4SEL_PLL3_R_CK +#define STM32_LPUART1SEL STM32_LPUART1SEL_PCLK4 + +/* + * IRQ system settings. + */ +#define STM32_IRQ_EXTI0_PRIORITY 6 +#define STM32_IRQ_EXTI1_PRIORITY 6 +#define STM32_IRQ_EXTI2_PRIORITY 6 +#define STM32_IRQ_EXTI3_PRIORITY 6 +#define STM32_IRQ_EXTI4_PRIORITY 6 +#define STM32_IRQ_EXTI5_9_PRIORITY 6 +#define STM32_IRQ_EXTI10_15_PRIORITY 6 +#define STM32_IRQ_EXTI16_PRIORITY 6 +#define STM32_IRQ_EXTI17_PRIORITY 15 //#TODO: is this correct? +#define STM32_IRQ_EXTI18_PRIORITY 6 +#define STM32_IRQ_EXTI19_PRIORITY 6 +#define STM32_IRQ_EXTI20_21_PRIORITY 6 + +#define STM32_IRQ_FDCAN1_PRIORITY 10 +#define STM32_IRQ_FDCAN2_PRIORITY 10 + +#define STM32_IRQ_MDMA_PRIORITY 9 + +#define STM32_IRQ_QUADSPI1_PRIORITY 10 + +#define STM32_IRQ_SDMMC1_PRIORITY 9 +#define STM32_IRQ_SDMMC2_PRIORITY 9 + +#define STM32_IRQ_TIM1_UP_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 +#define STM32_IRQ_TIM15_PRIORITY 7 +#define STM32_IRQ_TIM16_PRIORITY 7 +#define STM32_IRQ_TIM17_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 +#define STM32_IRQ_UART7_PRIORITY 12 +#define STM32_IRQ_UART8_PRIORITY 12 +#define STM32_IRQ_LPUART1_PRIORITY 12 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_DUAL_MODE FALSE +#define STM32_ADC_SAMPLES_SIZE 16 +#define STM32_ADC_USE_ADC12 TRUE +#define STM32_ADC_USE_ADC3 TRUE +#define STM32_ADC_ADC12_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_ADC_ADC3_BDMA_STREAM 7 +#define STM32_ADC_ADC12_DMA_PRIORITY 2 +#define STM32_ADC_ADC3_DMA_PRIORITY 2 +#define STM32_ADC_ADC12_IRQ_PRIORITY 5 +#define STM32_ADC_ADC3_IRQ_PRIORITY 5 +#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_ADCCK +#define STM32_ADC_ADC3_CLOCK_MODE ADC_CCR_CKMODE_ADCCK + +/* + * CAN driver system settings. + */ +#if USE_CAN1 +#define STM32_CAN_USE_FDCAN1 TRUE +#else +#define STM32_CAN_USE_FDCAN1 FALSE +#endif +#if USE_CAN2 +#define STM32_CAN_USE_FDCAN2 TRUE +#else +#define STM32_CAN_USE_FDCAN2 FALSE +#endif +#define STM32_CAN_USE_FDCAN3 FALSE + +/* + * DAC driver system settings. + */ +#define STM32_DAC_DUAL_MODE FALSE +#define STM32_DAC_USE_DAC1_CH1 FALSE +#define STM32_DAC_USE_DAC1_CH2 FALSE +#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10 +#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10 +#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2 +#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2 +#define STM32_DAC_DAC1_CH1_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_DAC_DAC1_CH2_DMA_STREAM STM32_DMA_STREAM_ID_ANY + +/* + * 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_TIM6 FALSE +#define STM32_GPT_USE_TIM7 FALSE +#define STM32_GPT_USE_TIM8 FALSE +#define STM32_GPT_USE_TIM12 FALSE +#define STM32_GPT_USE_TIM13 FALSE +#define STM32_GPT_USE_TIM14 FALSE +#define STM32_GPT_USE_TIM15 FALSE +#define STM32_GPT_USE_TIM16 FALSE +#define STM32_GPT_USE_TIM17 FALSE + +/* + * I2C driver system settings. + */ +#if USE_I2C1 +#define STM32_I2C_USE_I2C1 TRUE +#else +#define STM32_I2C_USE_I2C1 FALSE +#endif +#if USE_I2C2 +#define STM32_I2C_USE_I2C2 TRUE +#else +#define STM32_I2C_USE_I2C2 FALSE +#endif +#if USE_I2C3 +#define STM32_I2C_USE_I2C3 TRUE +#else +#define STM32_I2C_USE_I2C3 FALSE +#endif +#if USE_I2C4 +#define STM32_I2C_USE_I2C4 TRUE +#else +#define STM32_I2C_USE_I2C4 FALSE +#endif +#define STM32_I2C_BUSY_TIMEOUT 50 +#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C2_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C4_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C4_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_I2C_I2C4_RX_BDMA_STREAM 1 +#define STM32_I2C_I2C4_TX_BDMA_STREAM 2 +#define STM32_I2C_I2C1_IRQ_PRIORITY 5 +#define STM32_I2C_I2C2_IRQ_PRIORITY 5 +#define STM32_I2C_I2C3_IRQ_PRIORITY 5 +#define STM32_I2C_I2C4_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_I2C4_DMA_PRIORITY 3 +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") + +/* + * 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_USE_TIM12 FALSE +#define STM32_ICU_USE_TIM13 FALSE +#define STM32_ICU_USE_TIM14 FALSE +#define STM32_ICU_USE_TIM15 FALSE +#define STM32_ICU_USE_TIM16 FALSE +#define STM32_ICU_USE_TIM17 FALSE + +/* + * MAC driver system settings. + */ +#define STM32_MAC_TRANSMIT_BUFFERS 2 +#define STM32_MAC_RECEIVE_BUFFERS 4 +#define STM32_MAC_BUFFERS_SIZE 1522 +#define STM32_MAC_PHY_TIMEOUT 100 +#define STM32_MAC_ETH1_CHANGE_PHY_STATE TRUE +#define STM32_MAC_ETH1_IRQ_PRIORITY 13 +#define STM32_MAC_IP_CHECKSUM_OFFLOAD 0 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_ADVANCED FALSE +#define STM32_PWM_USE_TIM1 TRUE +#define STM32_PWM_USE_TIM2 FALSE +#define STM32_PWM_USE_TIM3 FALSE +#define STM32_PWM_USE_TIM4 TRUE +#define STM32_PWM_USE_TIM5 FALSE +#define STM32_PWM_USE_TIM8 FALSE +#define STM32_PWM_USE_TIM9 FALSE +#define STM32_PWM_USE_TIM10 FALSE +#define STM32_PWM_USE_TIM11 FALSE +#define STM32_PWM_USE_TIM12 FALSE +#define STM32_PWM_USE_TIM13 FALSE +#define STM32_PWM_USE_TIM14 FALSE +#define STM32_PWM_USE_TIM15 FALSE +#define STM32_PWM_USE_TIM16 FALSE +#define STM32_PWM_USE_TIM17 FALSE + +/* + * RTC driver system settings. + */ +#define STM32_RTC_PRESA_VALUE 32 +#define STM32_RTC_PRESS_VALUE 1024 +#define STM32_RTC_CR_INIT 0 +#define STM32_RTC_TAMPCR_INIT 0 + +/* + * SDC driver system settings. + */ +#define STM32_SDMMC_MAXCLK 200000000 +#define STM32_SDC_USE_SDMMC1 TRUE +#define STM32_SDC_USE_SDMMC2 FALSE +#define STM32_SDC_SDMMC_UNALIGNED_SUPPORT TRUE +#define STM32_SDC_SDMMC_WRITE_TIMEOUT 6000000 +#define STM32_SDC_SDMMC_READ_TIMEOUT 6000000 +#define STM32_SDC_SDMMC_CLOCK_DELAY 20 +#define STM32_SDC_SDMMC_PWRSAV TRUE +#define STM32_SDC_FORCE_25MHZ TRUE + +/* + * SERIAL driver system settings. + */ +#if USE_UART1 +#define STM32_SERIAL_USE_USART1 TRUE +#else +#define STM32_SERIAL_USE_USART1 FALSE +#endif +#if USE_UART2 +#define STM32_SERIAL_USE_USART2 TRUE +#else +#define STM32_SERIAL_USE_USART2 FALSE +#endif +#if USE_UART3 +#define STM32_SERIAL_USE_USART3 TRUE +#else +#define STM32_SERIAL_USE_USART3 FALSE +#endif +#if USE_UART4 +#define STM32_SERIAL_USE_UART4 TRUE +#else +#define STM32_SERIAL_USE_UART4 FALSE +#endif +#if USE_UART5 +#define STM32_SERIAL_USE_UART5 TRUE +#else +#define STM32_SERIAL_USE_UART5 FALSE +#endif +#if USE_UART6 +#define STM32_SERIAL_USE_USART6 TRUE +#else +#define STM32_SERIAL_USE_USART6 FALSE +#endif +#if USE_UART7 +#define STM32_SERIAL_USE_UART7 TRUE +#else +#define STM32_SERIAL_USE_UART7 FALSE +#endif +#if USE_UART8 +#define STM32_SERIAL_USE_UART8 TRUE +#else +#define STM32_SERIAL_USE_UART8 FALSE +#endif +#define STM32_SERIAL_USE_LPUART1 FALSE + +/* + * SPI driver system settings. + */ +#if USE_SPI1 +#define STM32_SPI_USE_SPI1 TRUE +#else +#define STM32_SPI_USE_SPI1 FALSE +#endif +#if USE_SPI2 +#define STM32_SPI_USE_SPI2 TRUE +#else +#define STM32_SPI_USE_SPI2 FALSE +#endif +#if USE_SPI3 +#define STM32_SPI_USE_SPI3 TRUE +#else +#define STM32_SPI_USE_SPI3 FALSE +#endif +#if USE_SPI4 +#define STM32_SPI_USE_SPI4 TRUE +#else +#define STM32_SPI_USE_SPI4 FALSE +#endif +#define STM32_SPI_USE_SPI5 FALSE +#define STM32_SPI_USE_SPI6 FALSE +#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI3_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI3_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI4_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI4_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI5_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI5_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI6_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI6_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI4_DMA_PRIORITY 1 +#define STM32_SPI_SPI5_DMA_PRIORITY 1 +#define STM32_SPI_SPI6_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_SPI4_IRQ_PRIORITY 10 +#define STM32_SPI_SPI5_IRQ_PRIORITY 10 +#define STM32_SPI_SPI6_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") + +/* + * ST driver system settings. + */ +#define STM32_ST_IRQ_PRIORITY 8 +#ifndef STM32_ST_USE_TIMER +#define STM32_ST_USE_TIMER 5 +#endif + +/* + * TRNG driver system settings. + */ +#define STM32_TRNG_USE_RNG1 FALSE + +/* + * 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_UART4 FALSE +#define STM32_UART_USE_UART5 FALSE +#define STM32_UART_USE_USART6 FALSE +#define STM32_UART_USE_UART7 FALSE +#define STM32_UART_USE_UART8 FALSE +#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART2_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART2_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART4_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART4_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART5_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART5_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART7_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART7_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART8_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_UART8_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY +#define STM32_UART_USART1_DMA_PRIORITY 1 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_UART4_DMA_PRIORITY 0 +#define STM32_UART_UART5_DMA_PRIORITY 0 +#define STM32_UART_USART6_DMA_PRIORITY 0 +#define STM32_UART_UART7_DMA_PRIORITY 0 +#define STM32_UART_UART8_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_OTG1 TRUE // 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_HOST_WAKEUP_DURATION 2 + +/* + * WDG driver system settings. + */ +#define STM32_WDG_USE_IWDG FALSE + +/* + * WSPI driver system settings. + */ +#define STM32_WSPI_USE_QUADSPI1 FALSE +#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE ((STM32_QSPICLK / HAL_QSPI1_CLK) - 1) +#define STM32_WSPI_QUADSPI1_MDMA_CHANNEL STM32_MDMA_CHANNEL_ID_ANY +#define STM32_WSPI_QUADSPI1_MDMA_PRIORITY 1 +#define STM32_WSPI_MDMA_ERROR_HOOK(wspip) osalSysHalt("MDMA failure") + +/* + sdlog message buffer and queue configuration + */ +#define SDLOG_QUEUE_BUCKETS 1024 +#define SDLOG_MAX_MESSAGE_LEN 300 +#define SDLOG_NUM_FILES 2 +#define SDLOG_ALL_BUFFERS_SIZE (SDLOG_NUM_FILES*16*1024) + +#endif /* MCUCONF_H */ diff --git a/sw/airborne/boards/holybro/kakute_f7/Makefile b/sw/airborne/boards/holybro/kakute_f7/Makefile new file mode 100644 index 0000000000..bfb3ea8d58 --- /dev/null +++ b/sw/airborne/boards/holybro/kakute_f7/Makefile @@ -0,0 +1,9 @@ +# file board.h is generated from file board.cfg by a script which is hosted here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/boardGen.pl + +# documentation is here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/DOC/boardGen.pdf + +board.h: board.cfg Makefile + boardGen.pl --no-pp-pin --no-pp-line $< $@ + diff --git a/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.cfg b/sw/airborne/boards/holybro/kakute_f7/board.cfg similarity index 98% rename from sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.cfg rename to sw/airborne/boards/holybro/kakute_f7/board.cfg index b28c8d40ee..7183a924d4 100644 --- a/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.cfg +++ b/sw/airborne/boards/holybro/kakute_f7/board.cfg @@ -114,3 +114,6 @@ PE07 UART7_RX UART AF:UART7_RX PE08 UART7_TX UART AF:UART7_TX PE09 S2 PWM AF:TIM1_CH1 () PE11 S3 PWM AF:TIM1_CH2 () + +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^S[0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/boards/holybro/kakute_f7/board.h b/sw/airborne/boards/holybro/kakute_f7/board.h index 4246d4432f..5168dc9f9e 100644 --- a/sw/airborne/boards/holybro/kakute_f7/board.h +++ b/sw/airborne/boards/holybro/kakute_f7/board.h @@ -1572,6 +1572,34 @@ #define S3_TIM_CH 2 #define S3_TIM_AF 1 +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_LED1, \ + LINE_S6, \ + LINE_SDCARD_CS, \ + LINE_S4, \ + LINE_S1, \ + LINE_OSD_CS, \ + LINE_S5, \ + LINE_IMU_CS, \ + LINE_S2, \ + LINE_S3 +#define ENERGY_SAVE_INPUT_SIZE 10 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/holybro/kakute_f7/board.mk b/sw/airborne/boards/holybro/kakute_f7/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/holybro/kakute_f7/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.h b/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.h index 4ef2c6f451..b6d6912265 100644 --- a/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.h +++ b/sw/airborne/boards/holybro/kakute_f7/holybro_kakute_f7.h @@ -98,9 +98,7 @@ #define PWM_SERVO_1_AF AF_S1 #define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, S1_TIM) #define PWM_SERVO_1_CHANNEL (S1_TIM_CH-1) -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, S1_TIM) #endif #ifndef USE_PWM2 @@ -113,9 +111,7 @@ #define PWM_SERVO_2_AF AF_S2 #define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, S2_TIM) #define PWM_SERVO_2_CHANNEL (S2_TIM_CH-1) -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, S2_TIM) #endif #ifndef USE_PWM3 @@ -128,9 +124,7 @@ #define PWM_SERVO_3_AF AF_S3 #define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, S3_TIM) #define PWM_SERVO_3_CHANNEL (S3_TIM_CH-1) -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, S3_TIM) #endif #ifndef USE_PWM4 @@ -143,9 +137,7 @@ #define PWM_SERVO_4_AF AF_S4 #define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, S4_TIM) #define PWM_SERVO_4_CHANNEL (S4_TIM_CH-1) -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, S4_TIM) #endif #ifndef USE_PWM5 @@ -158,9 +150,7 @@ #define PWM_SERVO_5_AF AF_S5 #define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, S5_TIM) #define PWM_SERVO_5_CHANNEL (S5_TIM_CH-1) -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, S5_TIM) #endif #ifndef USE_PWM6 @@ -173,73 +163,13 @@ #define PWM_SERVO_6_AF AF_S6 #define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, S6_TIM) #define PWM_SERVO_6_CHANNEL (S6_TIM_CH-1) -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, S6_TIM) #endif // servo index starting at 1 + regular servos // so NB = 1+6 #define ACTUATORS_PWM_NB 7 - -#ifdef STM32_PWM_USE_TIM1 -#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1 -#else -#define PWM_CONF_TIM1 1 -#endif -#define PWM_CONF1_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM1_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 -#endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM5 -#define PWM_CONF_TIM5 STM32_PWM_USE_TIM5 -#else -#define PWM_CONF_TIM5 1 -#endif -#define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * DSHOT */ diff --git a/sw/airborne/boards/lia/chibios/v1.1/board.c b/sw/airborne/boards/lia/chibios/v1.1/board.c deleted file mode 100644 index c5b331915e..0000000000 --- a/sw/airborne/boards/lia/chibios/v1.1/board.c +++ /dev/null @@ -1,269 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - static bool last_status = false; - - (void)sdcp; - return !palReadLine(LINE_SDIO_DETECT); -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - /* - * Several I/O pins are re-mapped: - * JTAG TRST to LED - */ - AFIO->MAPR |= AFIO_MAPR_USART3_REMAP_PARTIALREMAP | AFIO_MAPR_SWJ_CFG_NOJNTRST | AFIO_MAPR_TIM3_REMAP_FULLREMAP; -} diff --git a/sw/airborne/boards/lia/chibios/v1.1/board.h b/sw/airborne/boards/lia/chibios/v1.1/board.h index 763e20ebfc..44a29f9b71 100644 --- a/sw/airborne/boards/lia/chibios/v1.1/board.h +++ b/sw/airborne/boards/lia/chibios/v1.1/board.h @@ -179,6 +179,10 @@ #define VAL_GPIOECRH 0x88888888 /* PE15...PE8 */ #define VAL_GPIOEODR 0xFFFFFFFF +/** + * Remap several IO pins + */ +#define AFIO_MAPR_VAL (AFIO_MAPR_USART3_REMAP_PARTIALREMAP | AFIO_MAPR_SWJ_CFG_NOJNTRST | AFIO_MAPR_TIM3_REMAP_FULLREMAP) /* * AHB_CLK @@ -306,9 +310,7 @@ #define PWM_SERVO_0_AF GPIO_AF2 #define PWM_SERVO_0_DRIVER PWMD3 #define PWM_SERVO_0_CHANNEL 0 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_CONF pwmcfg3 #endif #ifndef USE_PWM1 @@ -321,9 +323,7 @@ #define PWM_SERVO_1_AF GPIO_AF1 #define PWM_SERVO_1_DRIVER PWMD3 #define PWM_SERVO_1_CHANNEL 1 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF pwmcfg3 #endif #ifndef USE_PWM2 @@ -336,9 +336,7 @@ #define PWM_SERVO_2_AF GPIO_AF2 #define PWM_SERVO_2_DRIVER PWMD3 #define PWM_SERVO_2_CHANNEL 2 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF pwmcfg3 #endif #ifndef USE_PWM3 @@ -351,9 +349,7 @@ #define PWM_SERVO_3_AF GPIO_AF2 #define PWM_SERVO_3_DRIVER PWMD3 #define PWM_SERVO_3_CHANNEL 3 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF pwmcfg3 #endif #ifndef USE_PWM4 @@ -366,9 +362,7 @@ #define PWM_SERVO_4_AF GPIO_AF2 #define PWM_SERVO_4_DRIVER PWMD5 #define PWM_SERVO_4_CHANNEL 0 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO4_CONF pwmcfg5 #endif #ifndef USE_PWM5 @@ -381,9 +375,7 @@ #define PWM_SERVO_5_AF GPIO_AF2 #define PWM_SERVO_5_DRIVER PWMD5 #define PWM_SERVO_5_CHANNEL 1 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF pwmcfg5 #endif @@ -398,9 +390,7 @@ #define PWM_SERVO_6_AF GPIO_AF2 #define PWM_SERVO_6_DRIVER PWMD4 #define PWM_SERVO_6_CHANNEL 0 - #define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH - #else - #define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED + #define PWM_SERVO_6_CONF pwmcfg4 #endif #if USE_PWM7 @@ -410,83 +400,9 @@ #define PWM_SERVO_7_AF GPIO_AF2 #define PWM_SERVO_7_DRIVER PWMD4 #define PWM_SERVO_7_CHANNEL 1 - #define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH - #else - #define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED + #define PWM_SERVO_7_CONF pwmcfg4 #endif - - #define PWM_CONF_TIM3 1 - #define PWM_CONF_TIM4 1 - #define PWM_CONF_TIM5 1 - #define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_0_ACTIVE, NULL}, \ - {PWM_SERVO_1_ACTIVE, NULL}, \ - {PWM_SERVO_2_ACTIVE, NULL}, \ - {PWM_SERVO_3_ACTIVE, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_6_ACTIVE, NULL}, \ - {PWM_SERVO_7_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_4_ACTIVE, NULL}, \ - {PWM_SERVO_5_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } #endif /* USE_I2C1 */ -#else /* !USE_SERVOS_7AND8 */ - #define PWM_CONF_TIM3 1 - #define PWM_CONF_TIM5 1 - #define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_0_ACTIVE, NULL}, \ - {PWM_SERVO_1_ACTIVE, NULL}, \ - {PWM_SERVO_2_ACTIVE, NULL}, \ - {PWM_SERVO_3_ACTIVE, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_4_ACTIVE, NULL}, \ - {PWM_SERVO_5_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } #endif /* USE_SERVOS_7AND8 */ diff --git a/sw/airborne/boards/lia/chibios/v1.1/board.mk b/sw/airborne/boards/lia/chibios/v1.1/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/lia/chibios/v1.1/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.c b/sw/airborne/boards/lisa_mx/chibios/v2.1/board.c deleted file mode 100644 index 711b23e5a7..0000000000 --- a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.c +++ /dev/null @@ -1,264 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - - (void)sdcp; - return !palReadPad(GPIOB, GPIOB_SDIO_DETECT); -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} diff --git a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.h b/sw/airborne/boards/lisa_mx/chibios/v2.1/board.h index 38a3eb4927..efa4041c99 100644 --- a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.h +++ b/sw/airborne/boards/lisa_mx/chibios/v2.1/board.h @@ -1176,9 +1176,7 @@ #define PWM_SERVO_0_AF GPIO_AF2 #define PWM_SERVO_0_DRIVER PWMD3 #define PWM_SERVO_0_CHANNEL 0 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_CONF pwmcfg3 #endif #ifndef USE_PWM1 @@ -1191,9 +1189,7 @@ #define PWM_SERVO_1_AF GPIO_AF2 #define PWM_SERVO_1_DRIVER PWMD3 #define PWM_SERVO_1_CHANNEL 1 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF pwmcfg3 #endif #ifndef USE_PWM2 @@ -1206,9 +1202,7 @@ #define PWM_SERVO_2_AF GPIO_AF2 #define PWM_SERVO_2_DRIVER PWMD3 #define PWM_SERVO_2_CHANNEL 2 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF pwmcfg3 #endif #ifndef USE_PWM3 @@ -1221,9 +1215,7 @@ #define PWM_SERVO_3_AF GPIO_AF2 #define PWM_SERVO_3_DRIVER PWMD3 #define PWM_SERVO_3_CHANNEL 3 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF pwmcfg3 #endif #ifndef USE_PWM4 @@ -1236,9 +1228,7 @@ #define PWM_SERVO_4_AF GPIO_AF2 #define PWM_SERVO_4_DRIVER PWMD5 #define PWM_SERVO_4_CHANNEL 0 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF pwmcfg5 #endif #ifndef USE_PWM5 @@ -1251,9 +1241,7 @@ #define PWM_SERVO_5_AF GPIO_AF2 #define PWM_SERVO_5_DRIVER PWMD5 #define PWM_SERVO_5_CHANNEL 1 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF pwmcfg5 #endif @@ -1268,9 +1256,7 @@ #define PWM_SERVO_6_AF GPIO_AF2 #define PWM_SERVO_6_DRIVER PWMD4 #define PWM_SERVO_6_CHANNEL 0 - #define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH - #else - #define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED + #define PWM_SERVO_6_CONF pwmcfg4 #endif #if USE_PWM7 @@ -1280,83 +1266,9 @@ #define PWM_SERVO_7_AF GPIO_AF2 #define PWM_SERVO_7_DRIVER PWMD4 #define PWM_SERVO_7_CHANNEL 1 - #define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH - #else - #define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED + #define PWM_SERVO_7_CONF pwmcfg4 #endif - - #define PWM_CONF_TIM3 1 - #define PWM_CONF_TIM4 1 - #define PWM_CONF_TIM5 1 - #define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_0_ACTIVE, NULL}, \ - {PWM_SERVO_1_ACTIVE, NULL}, \ - {PWM_SERVO_2_ACTIVE, NULL}, \ - {PWM_SERVO_3_ACTIVE, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_6_ACTIVE, NULL}, \ - {PWM_SERVO_7_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_4_ACTIVE, NULL}, \ - {PWM_SERVO_5_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } #endif /* USE_I2C1 */ -#else /* !USE_SERVOS_7AND8 */ - #define PWM_CONF_TIM3 1 - #define PWM_CONF_TIM5 1 - #define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_0_ACTIVE, NULL}, \ - {PWM_SERVO_1_ACTIVE, NULL}, \ - {PWM_SERVO_2_ACTIVE, NULL}, \ - {PWM_SERVO_3_ACTIVE, NULL} \ - }, \ - 0, \ - 0 \ - } - #define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - {PWM_SERVO_4_ACTIVE, NULL}, \ - {PWM_SERVO_5_ACTIVE, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL}, \ - {PWM_OUTPUT_DISABLED, NULL} \ - }, \ - 0, \ - 0 \ - } #endif /* USE_SERVOS_7AND8 */ diff --git a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.mk b/sw/airborne/boards/lisa_mx/chibios/v2.1/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/lisa_mx/chibios/v2.1/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/lisa_mx/chibios/v2.1/mcuconf.h b/sw/airborne/boards/lisa_mx/chibios/v2.1/mcuconf.h index 7ecc6d6bbb..f5a7c28a0e 100644 --- a/sw/airborne/boards/lisa_mx/chibios/v2.1/mcuconf.h +++ b/sw/airborne/boards/lisa_mx/chibios/v2.1/mcuconf.h @@ -86,6 +86,28 @@ #define STM32_IRQ_EXTI21_PRIORITY 15 #define STM32_IRQ_EXTI22_PRIORITY 15 +#define STM32_IRQ_TIM1_BRK_TIM9_PRIORITY 7 +#define STM32_IRQ_TIM1_UP_TIM10_PRIORITY 7 +#define STM32_IRQ_TIM1_TRGCO_TIM11_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 + /* * ADC driver system settings. */ diff --git a/sw/airborne/boards/mateksys/F765-WING/Makefile b/sw/airborne/boards/mateksys/F765-WING/Makefile new file mode 100644 index 0000000000..e4a940fa7c --- /dev/null +++ b/sw/airborne/boards/mateksys/F765-WING/Makefile @@ -0,0 +1,9 @@ +# file board.h is generated from file board.cfg by a script which is hosted here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/boardGen.pl + +# documentation is here : +# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/DOC/boardGen.pdf + +board.h: matekF765-WING.cfg Makefile + boardGen.pl --no-pp-pin --no-pp-line $< $@ + diff --git a/sw/airborne/boards/mateksys/F765-WING/board.c b/sw/airborne/boards/mateksys/F765-WING/board.c deleted file mode 100644 index 610de86244..0000000000 --- a/sw/airborne/boards/mateksys/F765-WING/board.c +++ /dev/null @@ -1,278 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - /* assume card is inserted as there is no SD_DETECT pin - * actual detection will be done by the software - */ - return true; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} - -/** Energy saving procedure for SD log closing - */ -void mcu_periph_energy_save(void) -{ - palSetLineMode(LINE_LED1, PAL_MODE_INPUT); - palSetLineMode(LINE_LED2, PAL_MODE_INPUT); - palSetLineMode(LINE_OSD_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_IMU1_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_IMU2_CS, PAL_MODE_INPUT); -} - diff --git a/sw/airborne/boards/mateksys/F765-WING/board.h b/sw/airborne/boards/mateksys/F765-WING/board.h index 12ffdf4bf2..3386570894 100644 --- a/sw/airborne/boards/mateksys/F765-WING/board.h +++ b/sw/airborne/boards/mateksys/F765-WING/board.h @@ -1681,6 +1681,42 @@ #define S12_TIM_CH 2 #define S12_TIM_AF 3 +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_S1, \ + LINE_S2, \ + LINE_S3, \ + LINE_S4, \ + LINE_S5, \ + LINE_S6, \ + LINE_OSD_CS, \ + LINE_IMU1_CS, \ + LINE_IMU2_CS, \ + LINE_LED1, \ + LINE_LED2, \ + LINE_S7, \ + LINE_S8, \ + LINE_S9, \ + LINE_S10, \ + LINE_S11, \ + LINE_S12, \ + LINE_SPI4_CS +#define ENERGY_SAVE_INPUT_SIZE 18 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/mateksys/F765-WING/board.mk b/sw/airborne/boards/mateksys/F765-WING/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/mateksys/F765-WING/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.cfg b/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.cfg index f569945035..2bd0cf5893 100644 --- a/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.cfg +++ b/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.cfg @@ -142,3 +142,6 @@ PE12 SPI4_CLK SPI AF:SPI4_SCK PE13 SPI4_MISO SPI AF:SPI4_MISO PE14 SPI4_MOSI SPI AF:SPI4_MOSI #PE15 PINIO2 Where is this pin ? + +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^S[0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.h b/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.h index b5aa8ae306..c68ae6eef7 100644 --- a/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.h +++ b/sw/airborne/boards/mateksys/F765-WING/matekF765-WING.h @@ -115,9 +115,7 @@ #define PWM_SERVO_1_AF AF_S1 #define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, S1_TIM) #define PWM_SERVO_1_CHANNEL (S1_TIM_CH-1) -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, S1_TIM) #endif #ifndef USE_PWM2 @@ -130,9 +128,7 @@ #define PWM_SERVO_2_AF AF_S2 #define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, S2_TIM) #define PWM_SERVO_2_CHANNEL (S2_TIM_CH-1) -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, S2_TIM) #endif #ifndef USE_PWM3 @@ -145,9 +141,7 @@ #define PWM_SERVO_3_AF AF_S3 #define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, S3_TIM) #define PWM_SERVO_3_CHANNEL (S3_TIM_CH-1) -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, S3_TIM) #endif #ifndef USE_PWM4 @@ -160,9 +154,7 @@ #define PWM_SERVO_4_AF AF_S4 #define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, S4_TIM) #define PWM_SERVO_4_CHANNEL (S4_TIM_CH-1) -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, S4_TIM) #endif #ifndef USE_PWM5 @@ -175,9 +167,7 @@ #define PWM_SERVO_5_AF AF_S5 #define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, S5_TIM) #define PWM_SERVO_5_CHANNEL (S5_TIM_CH-1) -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, S5_TIM) #endif #ifndef USE_PWM6 @@ -190,9 +180,7 @@ #define PWM_SERVO_6_AF AF_S6 #define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, S6_TIM) #define PWM_SERVO_6_CHANNEL (S6_TIM_CH-1) -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, S6_TIM) #endif #ifndef USE_PWM7 @@ -205,9 +193,7 @@ #define PWM_SERVO_7_AF AF_S7 #define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, S7_TIM) #define PWM_SERVO_7_CHANNEL (S7_TIM_CH-1) -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, S7_TIM) #endif #ifndef USE_PWM8 @@ -220,9 +206,7 @@ #define PWM_SERVO_8_AF AF_S8 #define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, S8_TIM) #define PWM_SERVO_8_CHANNEL (S8_TIM_CH-1) -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, S8_TIM) #endif #ifndef USE_PWM9 @@ -235,9 +219,7 @@ #define PWM_SERVO_9_AF AF_S9 #define PWM_SERVO_9_DRIVER CONCAT_BOARD_PARAM(PWMD, S9_TIM) #define PWM_SERVO_9_CHANNEL (S9_TIM_CH-1) -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_9_CONF CONCAT_BOARD_PARAM(pwmcfg, S9_TIM) #endif #ifndef USE_PWM10 @@ -250,9 +232,7 @@ #define PWM_SERVO_10_AF AF_S10 #define PWM_SERVO_10_DRIVER CONCAT_BOARD_PARAM(PWMD, S10_TIM) #define PWM_SERVO_10_CHANNEL (S10_TIM_CH-1) -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_10_CONF CONCAT_BOARD_PARAM(pwmcfg, S10_TIM) #endif #ifndef USE_PWM11 @@ -265,9 +245,7 @@ #define PWM_SERVO_11_AF AF_S11 #define PWM_SERVO_11_DRIVER CONCAT_BOARD_PARAM(PWMD, S11_TIM) #define PWM_SERVO_11_CHANNEL (S11_TIM_CH-1) -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_11_CONF CONCAT_BOARD_PARAM(pwmcfg, S11_TIM) #endif #ifndef USE_PWM12 @@ -280,9 +258,7 @@ #define PWM_SERVO_12_AF AF_12 #define PWM_SERVO_12_DRIVER CONCAT_BOARD_PARAM(PWMD, S12_TIM) #define PWM_SERVO_12_CHANNEL (S12_TIM_CH-1) -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_12_CONF CONCAT_BOARD_PARAM(pwmcfg, S12_TIM) #endif // servo index starting at 1 + regular servos + aux servos @@ -290,101 +266,6 @@ #define ACTUATORS_PWM_NB 13 -#ifdef STM32_PWM_USE_TIM2 -#define PWM_CONF_TIM2 STM32_PWM_USE_TIM2 -#else -#define PWM_CONF_TIM2 1 -#endif -#define PWM_CONF2_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM2_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 -#endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_7_ACTIVE, NULL }, \ - { PWM_SERVO_8_ACTIVE, NULL }, \ - { PWM_SERVO_9_ACTIVE, NULL }, \ - { PWM_SERVO_10_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM5 -#define PWM_CONF_TIM5 STM32_PWM_USE_TIM5 -#else -#define PWM_CONF_TIM5 1 -#endif -#define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM8 -#define PWM_CONF_TIM8 STM32_PWM_USE_TIM8 -#else -#define PWM_CONF_TIM8 1 -#endif -#define PWM_CONF8_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM8_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM9 -#define PWM_CONF_TIM9 STM32_PWM_USE_TIM9 -#else -#define PWM_CONF_TIM9 1 -#endif -#define PWM_CONF9_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM9_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_11_ACTIVE, NULL }, \ - { PWM_SERVO_12_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * DSHOT */ diff --git a/sw/airborne/boards/navstik/baro_board.c b/sw/airborne/boards/navstik/baro_board.c deleted file mode 100644 index df311bc6c9..0000000000 --- a/sw/airborne/boards/navstik/baro_board.c +++ /dev/null @@ -1,72 +0,0 @@ -/* - * Copyright (C) 2014 Freek van Tienen - * - * 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 boards/navstik/baro_board.c - * Baro board interface for Bosch BMP185 on Navstik I2C3 without EOC check. - */ - -#include "std.h" - -#include "modules/sensors/baro.h" -#include "peripherals/bmp085.h" -#include "peripherals/bmp085_regs.h" -#include -#include "modules/core/abi.h" - -#include "led.h" - - -struct Bmp085 baro_bmp085; - -void baro_init(void) -{ - bmp085_init(&baro_bmp085, &i2c3, BMP085_SLAVE_ADDR); - -#ifdef BARO_LED - LED_OFF(BARO_LED); -#endif -} - -void baro_periodic(void) -{ - if (baro_bmp085.initialized) { - bmp085_periodic(&baro_bmp085); - } else { - bmp085_read_eeprom_calib(&baro_bmp085); - } -} - -void baro_event(void) -{ - bmp085_event(&baro_bmp085); - - if (baro_bmp085.data_available) { - uint32_t now_ts = get_sys_time_usec(); - float pressure = (float)baro_bmp085.pressure; - AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, now_ts, pressure); - float temp = baro_bmp085.temperature / 10.0f; - AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - baro_bmp085.data_available = false; -#ifdef BARO_LED - RunOnceEvery(10, LED_TOGGLE(BARO_LED)); -#endif - } -} diff --git a/sw/airborne/boards/navstik/baro_board.h b/sw/airborne/boards/navstik/baro_board.h deleted file mode 100644 index b213ea597d..0000000000 --- a/sw/airborne/boards/navstik/baro_board.h +++ /dev/null @@ -1,37 +0,0 @@ -/* - * Copyright (C) 2014 Freek van Tienen - * - * 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. - */ - -/* - * board specific functions for the navstik board - */ - -#ifndef BOARDS_NAVSTIK_BARO_H -#define BOARDS_NAVSTIK_BARO_H - -// only for printing the baro type during compilation -#ifndef BARO_BOARD -#define BARO_BOARD BARO_BOARD_BMP085 -#endif - -extern void baro_event(void); -#define BaroEvent baro_event - -#endif /* BOARDS_NAVSTIK_BARO_H */ diff --git a/sw/airborne/boards/nucleo/144_f767zi/board.c b/sw/airborne/boards/nucleo/144_f767zi/board.c deleted file mode 100644 index 90cbc4ba84..0000000000 --- a/sw/airborne/boards/nucleo/144_f767zi/board.c +++ /dev/null @@ -1,262 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return false; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - return false; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool mmc_lld_is_write_protected(MMCDriver *mmcp) { - - (void)mmcp; - return false; -} -#endif - -/** - * @brief Board-specific initialization code. - * @todo Add your board-specific code, if any. - */ -void boardInit(void) { - -} - diff --git a/sw/airborne/boards/nucleo/144_f767zi/board.mk b/sw/airborne/boards/nucleo/144_f767zi/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/nucleo/144_f767zi/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/nucleo/144_f767zi/nucleo144_f767zi.h b/sw/airborne/boards/nucleo/144_f767zi/nucleo144_f767zi.h index e529079a9d..1047424183 100644 --- a/sw/airborne/boards/nucleo/144_f767zi/nucleo144_f767zi.h +++ b/sw/airborne/boards/nucleo/144_f767zi/nucleo144_f767zi.h @@ -165,9 +165,7 @@ #define PWM_SERVO_1_AF AF_SRVA1 #define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA1_TIM) #define PWM_SERVO_1_CHANNEL (SRVA1_TIM_CH-1) -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA1_TIM) #endif #ifndef USE_PWM2 @@ -180,9 +178,7 @@ #define PWM_SERVO_2_AF AF_SRVA2 #define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA2_TIM) #define PWM_SERVO_2_CHANNEL (SRVA2_TIM_CH-1) -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA2_TIM) #endif #ifndef USE_PWM3 @@ -195,9 +191,7 @@ #define PWM_SERVO_3_AF AF_SRVA3 #define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA3_TIM) #define PWM_SERVO_3_CHANNEL (SRVA3_TIM_CH-1) -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA3_TIM) #endif #ifndef USE_PWM4 @@ -210,9 +204,7 @@ #define PWM_SERVO_4_AF AF_SRVA4 #define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA4_TIM) #define PWM_SERVO_4_CHANNEL (SRVA4_TIM_CH-1) -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA4_TIM) #endif // SRVb connector, PWM mode disabled by default (DShot is enabled by default) @@ -227,9 +219,7 @@ #define PWM_SERVO_5_AF AF_SRVB1 #define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB1_TIM) #define PWM_SERVO_5_CHANNEL (SRVB1_TIM_CH-1) -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB1_TIM) #endif #ifndef USE_PWM6 @@ -242,9 +232,7 @@ #define PWM_SERVO_6_AF AF_SRVB2 #define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB2_TIM) #define PWM_SERVO_6_CHANNEL (SRVB2_TIM_CH-1) -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB2_TIM) #endif #ifndef USE_PWM7 @@ -257,9 +245,7 @@ #define PWM_SERVO_7_AF AF_SRVB3 #define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB3_TIM) #define PWM_SERVO_7_CHANNEL (SRVB3_TIM_CH-1) -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB3_TIM) #endif #ifndef USE_PWM8 @@ -272,9 +258,7 @@ #define PWM_SERVO_8_AF AF_SRVB4 #define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB4_TIM) #define PWM_SERVO_8_CHANNEL (SRVB4_TIM_CH-1) -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB4_TIM) #endif #ifndef USE_PWM9 @@ -287,9 +271,7 @@ #define PWM_SERVO_9_AF GPIO_AF2 #define PWM_SERVO_9_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A1_TIM) #define PWM_SERVO_9_CHANNEL (AUX_A1_TIM_CH-1) -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_9_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A1_TIM) #endif #ifndef USE_PWM10 @@ -302,9 +284,7 @@ #define PWM_SERVO_10_AF GPIO_AF2 #define PWM_SERVO_10_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A2_TIM) #define PWM_SERVO_10_CHANNEL (AUX_A2_TIM_CH-1) -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_10_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A2_TIM) #endif #ifndef USE_PWM11 @@ -317,9 +297,7 @@ #define PWM_SERVO_11_AF GPIO_AF2 #define PWM_SERVO_11_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A3_TIM) #define PWM_SERVO_11_CHANNEL (AUX_A3_TIM_CH-1) -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_11_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A3_TIM) #endif #ifndef USE_PWM12 @@ -332,9 +310,7 @@ #define PWM_SERVO_12_AF GPIO_AF2 #define PWM_SERVO_12_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A4_TIM) #define PWM_SERVO_12_CHANNEL (AUX_A4_TIM_CH-1) -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_12_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A4_TIM) #endif #ifndef USE_PWM13 @@ -347,9 +323,7 @@ #define PWM_SERVO_13_AF GPIO_AF2 #define PWM_SERVO_13_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B1_TIM) #define PWM_SERVO_13_CHANNEL (AUX_B1_TIM_CH-1) -#define PWM_SERVO_13_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_13_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_13_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B1_TIM) #endif #ifndef USE_PWM14 @@ -362,9 +336,7 @@ #define PWM_SERVO_14_AF GPIO_AF2 #define PWM_SERVO_14_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B2_TIM) #define PWM_SERVO_14_CHANNEL (AUX_B2_TIM_CH-1) -#define PWM_SERVO_14_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_14_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_14_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B2_TIM) #endif //#ifndef USE_PWM15 @@ -377,9 +349,7 @@ //#define PWM_SERVO_15_AF GPIO_AF2 //#define PWM_SERVO_15_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B3_TIM) //#define PWM_SERVO_15_CHANNEL (AUX_B3_TIM_CH-1) -//#define PWM_SERVO_15_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -//#else -//#define PWM_SERVO_15_ACTIVE PWM_OUTPUT_DISABLED +//#define PWM_SERVO_15_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B3_TIM) //#endif #ifndef USE_PWM16 @@ -392,9 +362,7 @@ #define PWM_SERVO_16_AF GPIO_AF2 #define PWM_SERVO_16_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B4_TIM) #define PWM_SERVO_16_CHANNEL (AUX_B4_TIM_CH-1) -#define PWM_SERVO_16_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_16_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_16_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B4_TIM) #endif // servo index starting at 1 + regular servos + aux servos @@ -402,82 +370,6 @@ #define ACTUATORS_PWM_NB 17 -#ifdef STM32_PWM_USE_TIM1 -#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1 -#else -#define PWM_CONF_TIM1 1 -#endif -#define PWM_CONF1_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM1_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 -#endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_12_ACTIVE, NULL }, \ - { PWM_SERVO_14_ACTIVE, NULL }, \ - { PWM_SERVO_15_ACTIVE, NULL }, \ - { PWM_SERVO_16_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 -#endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - { PWM_SERVO_7_ACTIVE, NULL }, \ - { PWM_SERVO_8_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM5 -#define PWM_CONF_TIM5 STM32_PWM_USE_TIM5 -#else -#define PWM_CONF_TIM5 1 -#endif -#define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_9_ACTIVE, NULL }, \ - { PWM_SERVO_10_ACTIVE, NULL }, \ - { PWM_SERVO_11_ACTIVE, NULL }, \ - { PWM_SERVO_13_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * DSHOT */ diff --git a/sw/airborne/boards/px4fmu/chibios/v2.4/board.c b/sw/airborne/boards/px4fmu/chibios/v2.4/board.c deleted file mode 100644 index d9f568dd48..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v2.4/board.c +++ /dev/null @@ -1,266 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - * PX4FMU_2.4 doesn't have a sense line for card insertion - * it is assumed always present. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - static bool last_status = false; - - (void)sdcp; - return true; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { -} diff --git a/sw/airborne/boards/px4fmu/chibios/v2.4/board.h b/sw/airborne/boards/px4fmu/chibios/v2.4/board.h index 03125f7cf1..41383f6153 100644 --- a/sw/airborne/boards/px4fmu/chibios/v2.4/board.h +++ b/sw/airborne/boards/px4fmu/chibios/v2.4/board.h @@ -705,9 +705,10 @@ /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* * Onboard LEDs @@ -780,9 +781,7 @@ #define PWM_SERVO_0_AF GPIO_AF2 #define PWM_SERVO_0_DRIVER PWMD3 #define PWM_SERVO_0_CHANNEL 2 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_0_CONF pwmcfg3 #endif #ifndef USE_PWM1 @@ -795,9 +794,7 @@ #define PWM_SERVO_1_AF GPIO_AF1 #define PWM_SERVO_1_DRIVER PWMD2 #define PWM_SERVO_1_CHANNEL 2 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF pwmcfg2 #endif #ifndef USE_PWM2 @@ -810,9 +807,7 @@ #define PWM_SERVO_2_AF GPIO_AF2 #define PWM_SERVO_2_DRIVER PWMD3 #define PWM_SERVO_2_CHANNEL 1 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF pwmcfg3 #endif #ifndef USE_PWM3 @@ -825,9 +820,7 @@ #define PWM_SERVO_3_AF GPIO_AF2 #define PWM_SERVO_3_DRIVER PWMD3 #define PWM_SERVO_3_CHANNEL 0 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF pwmcfg3 #endif #ifndef USE_PWM4 @@ -840,9 +833,7 @@ #define PWM_SERVO_4_AF GPIO_AF1 #define PWM_SERVO_4_DRIVER PWMD2 #define PWM_SERVO_4_CHANNEL 1 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF pwmcfg2 #endif #ifndef USE_PWM5 @@ -855,9 +846,7 @@ #define PWM_SERVO_5_AF GPIO_AF1 #define PWM_SERVO_5_DRIVER PWMD2 #define PWM_SERVO_5_CHANNEL 0 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF pwmcfg2 #endif #if USE_PWM6 @@ -867,50 +856,9 @@ #define PWM_SERVO_6_AF GPIO_AF2 #define PWM_SERVO_6_DRIVER PWMD3 #define PWM_SERVO_6_CHANNEL 3 -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_CONF pwmcfg3 #endif - -#ifdef STM32_PWM_USE_TIM2 -#define PWM_CONF_TIM2 STM32_PWM_USE_TIM2 -#else -#define PWM_CONF_TIM2 1 -#endif -#define PWM_CONF2_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM2_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 -#endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_0_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * PPM radio defines TODO */ diff --git a/sw/airborne/boards/px4fmu/chibios/v2.4/board.mk b/sw/airborne/boards/px4fmu/chibios/v2.4/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v2.4/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/px4fmu/chibios/v2.4/mcuconf.h b/sw/airborne/boards/px4fmu/chibios/v2.4/mcuconf.h index f894a9e04f..4c88ec3b58 100644 --- a/sw/airborne/boards/px4fmu/chibios/v2.4/mcuconf.h +++ b/sw/airborne/boards/px4fmu/chibios/v2.4/mcuconf.h @@ -86,6 +86,28 @@ #define STM32_IRQ_EXTI21_PRIORITY 15 #define STM32_IRQ_EXTI22_PRIORITY 15 +#define STM32_IRQ_TIM1_BRK_TIM9_PRIORITY 7 +#define STM32_IRQ_TIM1_UP_TIM10_PRIORITY 7 +#define STM32_IRQ_TIM1_TRGCO_TIM11_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 + /* * ADC driver system settings. */ diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/board.c b/sw/airborne/boards/px4fmu/chibios/v4.0/board.c deleted file mode 100644 index fa40f422e2..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/board.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return true; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/board.cfg b/sw/airborne/boards/px4fmu/chibios/v4.0/board.cfg index 3f2d9b3ccc..c12eca6055 100644 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/board.cfg +++ b/sw/airborne/boards/px4fmu/chibios/v4.0/board.cfg @@ -65,93 +65,86 @@ H01 OSC_OUT SYS AF0 #DEFAULT DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0 - -# Afficheur : -# DISg = PE2 (old PE5) - - - - # ACTIVE PINS -PA00 USART4_TX UART AF:UART4_TX -PA01 USART4_RX UART AF:UART4_RX -PA02 VOLT_SENS ADC ADC1_IN2 -PA03 CURRENT_SENS ADC ADC1_IN3 -PA04 VDD_5V_SENS ADC ADC1_IN4 -PA05 MPU9250_SCK SPI AF:SPI1_SCK -PA06 MPU9250_MISO SPI AF:SPI1_MISO -PA07 MPU9250_MOSI SPI AF:SPI1_MOSI -PA08 _8266_RTS PASSIVE -PA09 USB_VBUS INPUT PULLDOWN -PA10 FRSKY_INV OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM -PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP -PA15 ALARM OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PA00 USART4_TX UART AF:UART4_TX +PA01 USART4_RX UART AF:UART4_RX +PA02 VOLT_SENS ADC ADC1_IN2 +PA03 CURRENT_SENS ADC ADC1_IN3 +PA04 VDD_5V_SENS ADC ADC1_IN4 +PA05 MPU9250_SCK SPI AF:SPI1_SCK +PA06 MPU9250_MISO SPI AF:SPI1_MISO +PA07 MPU9250_MOSI SPI AF:SPI1_MOSI +PA08 _8266_RTS PASSIVE +PA09 USB_VBUS INPUT PULLDOWN +PA10 FRSKY_INV OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PA11 OTG_FS_DM OTG AF:USB_OTG_FS_DM +PA12 OTG_FS_DP OTG AF:USB_OTG_FS_DP +PA15 ALARM OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PB00 _RC_INPUT PASSIVE -PB01 LED_GREEN LED -PB02 BOOT1 PASSIVE -PB03 LED_BLUE LED -PB04 _8266_GPIO2 PASSIVE -PB05 VDD_BRICK_VALID PASSIVE -PB06 USART1_TX UART AF:USART1_TX -PB07 USART1_RX UART AF:USART1_RX -PB08 I2C1_SCL I2C AF:I2C1_SCL -PB09 I2C1_SDA I2C AF:I2C1_SDA -PB10 FRAM_SCK SPI AF:SPI2_SCK -PB11 LED_RED LED -PB12 CAN2_RX CAN AF:CAN2_RX -PB13 CAN2_TX CAN AF:CAN2_TX -PB14 FRAM_MISO SPI AF:SPI2_MISO -PB15 FRAM_MOSI SPI AF:SPI2_MOSI +PB00 _RC_INPUT PASSIVE +PB01 LED_GREEN LED +PB02 BOOT1 PASSIVE +PB03 LED_BLUE LED +PB04 _8266_GPIO2 PASSIVE +PB05 VDD_BRICK_VALID PASSIVE +PB06 USART1_TX UART AF:USART1_TX +PB07 USART1_RX UART AF:USART1_RX +PB08 I2C1_SCL I2C AF:I2C1_SCL +PB09 I2C1_SDA I2C AF:I2C1_SDA +PB10 FRAM_SCK SPI AF:SPI2_SCK +PB11 LED_RED LED +PB12 CAN2_RX CAN AF:CAN2_RX +PB13 CAN2_TX CAN AF:CAN2_TX +PB14 FRAM_MISO SPI AF:SPI2_MISO +PB15 FRAM_MOSI SPI AF:SPI2_MOSI -PC00 VBUS_VALID PASSIVE -PC01 RSSI_IN PASSIVE -PC02 MPU9250_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH -PC03 LED_SAFETY LED -PC04 SAFETY_SW_IN INPUT FLOATING -PC05 VDD_3V3_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PC06 RC_OUTPUT PASSIVE -PC07 RC_INPUT UART AF:USART6_RX -PC08 SDMMC1_D0 SDIO AF:SDIO_D0 -PC09 SDMMC1_D1 SDIO AF:SDIO_D1 -PC10 SDMMC1_D2 SDIO AF:SDIO_D2 -PC11 SDMMC1_D3 SDIO AF:SDIO_D3 -PC12 SDMMC1_CK SDIO AF:SDIO_CK -PC13 SBUS_INV OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PC14 _20608_DRDY PASSIVE -PC15 _20608_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PC00 VBUS_VALID PASSIVE +PC01 RSSI_IN PASSIVE +PC02 MPU9250_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PC03 LED_SAFETY LED +PC04 SAFETY_SW_IN INPUT FLOATING +PC05 VDD_3V3_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PC06 RC_OUTPUT PASSIVE +PC07 RC_INPUT UART AF:USART6_RX +PC08 SDMMC1_D0 SDIO AF:SDIO_D0 +PC09 SDMMC1_D1 SDIO AF:SDIO_D1 +PC10 SDMMC1_D2 SDIO AF:SDIO_D2 +PC11 SDMMC1_D3 SDIO AF:SDIO_D3 +PC12 SDMMC1_CK SDIO AF:SDIO_CK +PC13 SBUS_INV OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PC14 _20608_DRDY PASSIVE +PC15 _20608_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH -PD00 CAN1_RX CAN AF:CAN1_RX -PD01 CAN1_TX CAN AF:CAN1_TX -PD02 SDMMC1_CMD SDIO AF:SDIO_CMD -PD03 USART2_CTS PASSIVE -PD04 USART2_RTS PASSIVE -PD05 USART2_TX UART AF:USART2_TX -PD06 USART2_RX UART AF:USART2_RX -PD07 BARO_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH -PD08 USART3_TX UART AF:USART3_TX -PD09 USART3_RX UART AF:USART3_RX -PD10 FRAM_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH -PD11 USART3_CTS PASSIVE -PD12 USART3_RTS PASSIVE -PD13 SRV5_TIM4_CH2 PASSIVE -PD14 SRV6_TIM4_CH3 PASSIVE -PD15 MPU9250_DRDY INPUT FLOATING +PD00 CAN1_RX CAN AF:CAN1_RX +PD01 CAN1_TX CAN AF:CAN1_TX +PD02 SDMMC1_CMD SDIO AF:SDIO_CMD +PD03 USART2_CTS PASSIVE +PD04 USART2_RTS PASSIVE +PD05 USART2_TX UART AF:USART2_TX +PD06 USART2_RX UART AF:USART2_RX +PD07 BARO_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PD08 USART3_TX UART AF:USART3_TX +PD09 USART3_RX UART AF:USART3_RX +PD10 FRAM_CS OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PD11 USART3_CTS PASSIVE +PD12 USART3_RTS PASSIVE +PD13 SERVO5 PWM AF:TIM4_CH2 () +PD14 SERVO6 PWM AF:TIM4_CH3 () +PD15 MPU9250_DRDY INPUT FLOATING -PE00 UART8_RX UART AF:UART8_RX -PE01 UART8_TX UART AF:UART8_TX -PE02 _8266_GPIO0 PASSIVE -PE03 VDD_3V3_SENS_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PE04 SPEKTRUM_POWER OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH -PE05 _8266_PD PASSIVE -PE06 _8266_RST PASSIVE -PE07 UART7_RX UART AF:UART7_RX -PE08 UART7_TX UART AF:UART7_TX -PE09 SRV4_TIM1_CH1 PASSIVE -PE10 _8266_CTS PASSIVE -PE11 SRV3_TIM1_CH2 PASSIVE -PE12 HMC5983_DRDY INPUT FLOATING -PE13 SRV2_TIM1_CH3 PASSIVE -PE14 SRV1_TIM1_CH4 PASSIVE -PE15 HMC_5983 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH +PE00 UART8_RX UART AF:UART8_RX +PE01 UART8_TX UART AF:UART8_TX +PE02 _8266_GPIO0 PASSIVE +PE03 VDD_3V3_SENS_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PE04 SPEKTRUM_POWER OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH +PE05 _8266_PD PASSIVE +PE06 _8266_RST PASSIVE +PE07 UART7_RX UART AF:UART7_RX +PE08 UART7_TX UART AF:UART7_TX +PE09 SERVO4 PWM AF:TIM1_CH1 () +PE10 _8266_CTS PASSIVE +PE11 SERVO3 PWM AF:TIM1_CH2 () +PE12 HMC5983_DRDY INPUT FLOATING +PE13 SERVO2 PWM AF:TIM1_CH3 () +PE14 SERVO1 PWM AF:TIM1_CH4 () +PE15 HMC_5983 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/board.h b/sw/airborne/boards/px4fmu/chibios/v4.0/board.h index de83510a75..7294bbff1f 100644 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/board.h +++ b/sw/airborne/boards/px4fmu/chibios/v4.0/board.h @@ -111,8 +111,8 @@ #define FRAM_CS 10U #define USART3_CTS 11U #define USART3_RTS 12U -#define SRV5_TIM4_CH2 13U -#define SRV6_TIM4_CH3 14U +#define SERVO5 13U +#define SERVO6 14U #define MPU9250_DRDY 15U #define UART8_RX 0U @@ -124,12 +124,12 @@ #define _8266_RST 6U #define UART7_RX 7U #define UART7_TX 8U -#define SRV4_TIM1_CH1 9U +#define SERVO4 9U #define _8266_CTS 10U -#define SRV3_TIM1_CH2 11U +#define SERVO3 11U #define HMC5983_DRDY 12U -#define SRV2_TIM1_CH3 13U -#define SRV1_TIM1_CH4 14U +#define SERVO2 13U +#define SERVO1 14U #define HMC_5983 15U #define PF00 0U @@ -301,8 +301,8 @@ #define LINE_FRAM_CS PAL_LINE(GPIOD, 10U) #define LINE_USART3_CTS PAL_LINE(GPIOD, 11U) #define LINE_USART3_RTS PAL_LINE(GPIOD, 12U) -#define LINE_SRV5_TIM4_CH2 PAL_LINE(GPIOD, 13U) -#define LINE_SRV6_TIM4_CH3 PAL_LINE(GPIOD, 14U) +#define LINE_SERVO5 PAL_LINE(GPIOD, 13U) +#define LINE_SERVO6 PAL_LINE(GPIOD, 14U) #define LINE_MPU9250_DRDY PAL_LINE(GPIOD, 15U) #define LINE_UART8_RX PAL_LINE(GPIOE, 0U) @@ -314,12 +314,12 @@ #define LINE__8266_RST PAL_LINE(GPIOE, 6U) #define LINE_UART7_RX PAL_LINE(GPIOE, 7U) #define LINE_UART7_TX PAL_LINE(GPIOE, 8U) -#define LINE_SRV4_TIM1_CH1 PAL_LINE(GPIOE, 9U) +#define LINE_SERVO4 PAL_LINE(GPIOE, 9U) #define LINE__8266_CTS PAL_LINE(GPIOE, 10U) -#define LINE_SRV3_TIM1_CH2 PAL_LINE(GPIOE, 11U) +#define LINE_SERVO3 PAL_LINE(GPIOE, 11U) #define LINE_HMC5983_DRDY PAL_LINE(GPIOE, 12U) -#define LINE_SRV2_TIM1_CH3 PAL_LINE(GPIOE, 13U) -#define LINE_SRV1_TIM1_CH4 PAL_LINE(GPIOE, 14U) +#define LINE_SERVO2 PAL_LINE(GPIOE, 13U) +#define LINE_SERVO1 PAL_LINE(GPIOE, 14U) #define LINE_HMC_5983 PAL_LINE(GPIOE, 15U) #define LINE_OSC_IN PAL_LINE(GPIOH, 0U) @@ -670,8 +670,8 @@ PIN_MODE_OUTPUT(FRAM_CS) | \ PIN_MODE_INPUT(USART3_CTS) | \ PIN_MODE_INPUT(USART3_RTS) | \ - PIN_MODE_INPUT(SRV5_TIM4_CH2) | \ - PIN_MODE_INPUT(SRV6_TIM4_CH3) | \ + PIN_MODE_ALTERNATE(SERVO5) | \ + PIN_MODE_ALTERNATE(SERVO6) | \ PIN_MODE_INPUT(MPU9250_DRDY)) #define VAL_GPIOD_OTYPER (PIN_OTYPE_PUSHPULL(CAN1_RX) | \ @@ -687,8 +687,8 @@ PIN_OTYPE_PUSHPULL(FRAM_CS) | \ PIN_OTYPE_OPENDRAIN(USART3_CTS) | \ PIN_OTYPE_OPENDRAIN(USART3_RTS) | \ - PIN_OTYPE_OPENDRAIN(SRV5_TIM4_CH2) | \ - PIN_OTYPE_OPENDRAIN(SRV6_TIM4_CH3) | \ + PIN_OTYPE_PUSHPULL(SERVO5) | \ + PIN_OTYPE_PUSHPULL(SERVO6) | \ PIN_OTYPE_OPENDRAIN(MPU9250_DRDY)) #define VAL_GPIOD_OSPEEDR (PIN_OSPEED_SPEED_HIGH(CAN1_RX) | \ @@ -704,8 +704,8 @@ PIN_OSPEED_SPEED_HIGH(FRAM_CS) | \ PIN_OSPEED_SPEED_VERYLOW(USART3_CTS) | \ PIN_OSPEED_SPEED_VERYLOW(USART3_RTS) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV5_TIM4_CH2) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV6_TIM4_CH3) | \ + PIN_OSPEED_SPEED_HIGH(SERVO5) | \ + PIN_OSPEED_SPEED_HIGH(SERVO6) | \ PIN_OSPEED_SPEED_VERYLOW(MPU9250_DRDY)) #define VAL_GPIOD_PUPDR (PIN_PUPDR_FLOATING(CAN1_RX) | \ @@ -721,8 +721,8 @@ PIN_PUPDR_FLOATING(FRAM_CS) | \ PIN_PUPDR_PULLDOWN(USART3_CTS) | \ PIN_PUPDR_PULLDOWN(USART3_RTS) | \ - PIN_PUPDR_PULLDOWN(SRV5_TIM4_CH2) | \ - PIN_PUPDR_PULLDOWN(SRV6_TIM4_CH3) | \ + PIN_PUPDR_FLOATING(SERVO5) | \ + PIN_PUPDR_FLOATING(SERVO6) | \ PIN_PUPDR_FLOATING(MPU9250_DRDY)) #define VAL_GPIOD_ODR (PIN_ODR_LEVEL_HIGH(CAN1_RX) | \ @@ -738,8 +738,8 @@ PIN_ODR_LEVEL_HIGH(FRAM_CS) | \ PIN_ODR_LEVEL_HIGH(USART3_CTS) | \ PIN_ODR_LEVEL_HIGH(USART3_RTS) | \ - PIN_ODR_LEVEL_HIGH(SRV5_TIM4_CH2) | \ - PIN_ODR_LEVEL_HIGH(SRV6_TIM4_CH3) | \ + PIN_ODR_LEVEL_LOW(SERVO5) | \ + PIN_ODR_LEVEL_LOW(SERVO6) | \ PIN_ODR_LEVEL_LOW(MPU9250_DRDY)) #define VAL_GPIOD_AFRL (PIN_AFIO_AF(CAN1_RX, 9) | \ @@ -756,8 +756,8 @@ PIN_AFIO_AF(FRAM_CS, 0) | \ PIN_AFIO_AF(USART3_CTS, 0) | \ PIN_AFIO_AF(USART3_RTS, 0) | \ - PIN_AFIO_AF(SRV5_TIM4_CH2, 0) | \ - PIN_AFIO_AF(SRV6_TIM4_CH3, 0) | \ + PIN_AFIO_AF(SERVO5, 2) | \ + PIN_AFIO_AF(SERVO6, 2) | \ PIN_AFIO_AF(MPU9250_DRDY, 0)) #define VAL_GPIOE_MODER (PIN_MODE_ALTERNATE(UART8_RX) | \ @@ -769,12 +769,12 @@ PIN_MODE_INPUT(_8266_RST) | \ PIN_MODE_ALTERNATE(UART7_RX) | \ PIN_MODE_ALTERNATE(UART7_TX) | \ - PIN_MODE_INPUT(SRV4_TIM1_CH1) | \ + PIN_MODE_ALTERNATE(SERVO4) | \ PIN_MODE_INPUT(_8266_CTS) | \ - PIN_MODE_INPUT(SRV3_TIM1_CH2) | \ + PIN_MODE_ALTERNATE(SERVO3) | \ PIN_MODE_INPUT(HMC5983_DRDY) | \ - PIN_MODE_INPUT(SRV2_TIM1_CH3) | \ - PIN_MODE_INPUT(SRV1_TIM1_CH4) | \ + PIN_MODE_ALTERNATE(SERVO2) | \ + PIN_MODE_ALTERNATE(SERVO1) | \ PIN_MODE_OUTPUT(HMC_5983)) #define VAL_GPIOE_OTYPER (PIN_OTYPE_PUSHPULL(UART8_RX) | \ @@ -786,12 +786,12 @@ PIN_OTYPE_OPENDRAIN(_8266_RST) | \ PIN_OTYPE_PUSHPULL(UART7_RX) | \ PIN_OTYPE_PUSHPULL(UART7_TX) | \ - PIN_OTYPE_OPENDRAIN(SRV4_TIM1_CH1) | \ + PIN_OTYPE_PUSHPULL(SERVO4) | \ PIN_OTYPE_OPENDRAIN(_8266_CTS) | \ - PIN_OTYPE_OPENDRAIN(SRV3_TIM1_CH2) | \ + PIN_OTYPE_PUSHPULL(SERVO3) | \ PIN_OTYPE_OPENDRAIN(HMC5983_DRDY) | \ - PIN_OTYPE_OPENDRAIN(SRV2_TIM1_CH3) | \ - PIN_OTYPE_OPENDRAIN(SRV1_TIM1_CH4) | \ + PIN_OTYPE_PUSHPULL(SERVO2) | \ + PIN_OTYPE_PUSHPULL(SERVO1) | \ PIN_OTYPE_PUSHPULL(HMC_5983)) #define VAL_GPIOE_OSPEEDR (PIN_OSPEED_SPEED_HIGH(UART8_RX) | \ @@ -803,12 +803,12 @@ PIN_OSPEED_SPEED_VERYLOW(_8266_RST) | \ PIN_OSPEED_SPEED_HIGH(UART7_RX) | \ PIN_OSPEED_SPEED_HIGH(UART7_TX) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV4_TIM1_CH1) | \ + PIN_OSPEED_SPEED_HIGH(SERVO4) | \ PIN_OSPEED_SPEED_VERYLOW(_8266_CTS) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV3_TIM1_CH2) | \ + PIN_OSPEED_SPEED_HIGH(SERVO3) | \ PIN_OSPEED_SPEED_VERYLOW(HMC5983_DRDY) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV2_TIM1_CH3) | \ - PIN_OSPEED_SPEED_VERYLOW(SRV1_TIM1_CH4) | \ + PIN_OSPEED_SPEED_HIGH(SERVO2) | \ + PIN_OSPEED_SPEED_HIGH(SERVO1) | \ PIN_OSPEED_SPEED_HIGH(HMC_5983)) #define VAL_GPIOE_PUPDR (PIN_PUPDR_FLOATING(UART8_RX) | \ @@ -820,12 +820,12 @@ PIN_PUPDR_PULLDOWN(_8266_RST) | \ PIN_PUPDR_FLOATING(UART7_RX) | \ PIN_PUPDR_FLOATING(UART7_TX) | \ - PIN_PUPDR_PULLDOWN(SRV4_TIM1_CH1) | \ + PIN_PUPDR_FLOATING(SERVO4) | \ PIN_PUPDR_PULLDOWN(_8266_CTS) | \ - PIN_PUPDR_PULLDOWN(SRV3_TIM1_CH2) | \ + PIN_PUPDR_FLOATING(SERVO3) | \ PIN_PUPDR_FLOATING(HMC5983_DRDY) | \ - PIN_PUPDR_PULLDOWN(SRV2_TIM1_CH3) | \ - PIN_PUPDR_PULLDOWN(SRV1_TIM1_CH4) | \ + PIN_PUPDR_FLOATING(SERVO2) | \ + PIN_PUPDR_FLOATING(SERVO1) | \ PIN_PUPDR_FLOATING(HMC_5983)) #define VAL_GPIOE_ODR (PIN_ODR_LEVEL_HIGH(UART8_RX) | \ @@ -837,12 +837,12 @@ PIN_ODR_LEVEL_HIGH(_8266_RST) | \ PIN_ODR_LEVEL_HIGH(UART7_RX) | \ PIN_ODR_LEVEL_HIGH(UART7_TX) | \ - PIN_ODR_LEVEL_HIGH(SRV4_TIM1_CH1) | \ + PIN_ODR_LEVEL_LOW(SERVO4) | \ PIN_ODR_LEVEL_HIGH(_8266_CTS) | \ - PIN_ODR_LEVEL_HIGH(SRV3_TIM1_CH2) | \ + PIN_ODR_LEVEL_LOW(SERVO3) | \ PIN_ODR_LEVEL_LOW(HMC5983_DRDY) | \ - PIN_ODR_LEVEL_HIGH(SRV2_TIM1_CH3) | \ - PIN_ODR_LEVEL_HIGH(SRV1_TIM1_CH4) | \ + PIN_ODR_LEVEL_LOW(SERVO2) | \ + PIN_ODR_LEVEL_LOW(SERVO1) | \ PIN_ODR_LEVEL_HIGH(HMC_5983)) #define VAL_GPIOE_AFRL (PIN_AFIO_AF(UART8_RX, 8) | \ @@ -855,12 +855,12 @@ PIN_AFIO_AF(UART7_RX, 8)) #define VAL_GPIOE_AFRH (PIN_AFIO_AF(UART7_TX, 8) | \ - PIN_AFIO_AF(SRV4_TIM1_CH1, 0) | \ + PIN_AFIO_AF(SERVO4, 1) | \ PIN_AFIO_AF(_8266_CTS, 0) | \ - PIN_AFIO_AF(SRV3_TIM1_CH2, 0) | \ + PIN_AFIO_AF(SERVO3, 1) | \ PIN_AFIO_AF(HMC5983_DRDY, 0) | \ - PIN_AFIO_AF(SRV2_TIM1_CH3, 0) | \ - PIN_AFIO_AF(SRV1_TIM1_CH4, 0) | \ + PIN_AFIO_AF(SERVO2, 1) | \ + PIN_AFIO_AF(SERVO1, 1) | \ PIN_AFIO_AF(HMC_5983, 0)) #define VAL_GPIOF_MODER (PIN_MODE_INPUT(PF00) | \ @@ -1543,6 +1543,10 @@ #define AF_LINE_USART3_TX 7U #define AF_USART3_RX 7U #define AF_LINE_USART3_RX 7U +#define AF_SERVO5 2U +#define AF_LINE_SERVO5 2U +#define AF_SERVO6 2U +#define AF_LINE_SERVO6 2U #define AF_UART8_RX 8U #define AF_LINE_UART8_RX 8U #define AF_UART8_TX 8U @@ -1551,12 +1555,60 @@ #define AF_LINE_UART7_RX 8U #define AF_UART7_TX 8U #define AF_LINE_UART7_TX 8U +#define AF_SERVO4 1U +#define AF_LINE_SERVO4 1U +#define AF_SERVO3 1U +#define AF_LINE_SERVO3 1U +#define AF_SERVO2 1U +#define AF_LINE_SERVO2 1U +#define AF_SERVO1 1U +#define AF_LINE_SERVO1 1U #define AF_OSC_IN 0U #define AF_LINE_OSC_IN 0U #define AF_OSC_OUT 0U #define AF_LINE_OSC_OUT 0U +#define SERVO5_TIM 4 +#define SERVO5_TIM_FN CH +#define SERVO5_TIM_CH 2 +#define SERVO5_TIM_AF 2 +#define SERVO6_TIM 4 +#define SERVO6_TIM_FN CH +#define SERVO6_TIM_CH 3 +#define SERVO6_TIM_AF 2 +#define SERVO4_TIM 1 +#define SERVO4_TIM_FN CH +#define SERVO4_TIM_CH 1 +#define SERVO4_TIM_AF 1 +#define SERVO3_TIM 1 +#define SERVO3_TIM_FN CH +#define SERVO3_TIM_CH 2 +#define SERVO3_TIM_AF 1 +#define SERVO2_TIM 1 +#define SERVO2_TIM_FN CH +#define SERVO2_TIM_CH 3 +#define SERVO2_TIM_AF 1 +#define SERVO1_TIM 1 +#define SERVO1_TIM_FN CH +#define SERVO1_TIM_CH 4 +#define SERVO1_TIM_AF 1 + +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/board.mk b/sw/airborne/boards/px4fmu/chibios/v4.0/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/mcuconf.h b/sw/airborne/boards/px4fmu/chibios/v4.0/mcuconf.h index cb006c6dd2..006da6cc3b 100644 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/mcuconf.h +++ b/sw/airborne/boards/px4fmu/chibios/v4.0/mcuconf.h @@ -32,10 +32,10 @@ */ #define STM32F4xx_MCUCONF -#define STM32F405_MCUCONF -#define STM32F415_MCUCONF -#define STM32F407_MCUCONF -#define STM32F417_MCUCONF +#define STM32F427_MCUCONF +#define STM32F429_MCUCONF +#define STM32F437_MCUCONF +#define STM32F439_MCUCONF /* * HAL driver system settings. @@ -86,6 +86,30 @@ #define STM32_IRQ_EXTI21_PRIORITY 15 #define STM32_IRQ_EXTI22_PRIORITY 15 +#define STM32_IRQ_TIM1_BRK_TIM9_PRIORITY 7 +#define STM32_IRQ_TIM1_UP_TIM10_PRIORITY 7 +#define STM32_IRQ_TIM1_TRGCO_TIM11_PRIORITY 7 +#define STM32_IRQ_TIM1_CC_PRIORITY 7 +#define STM32_IRQ_TIM2_PRIORITY 7 +#define STM32_IRQ_TIM3_PRIORITY 7 +#define STM32_IRQ_TIM4_PRIORITY 7 +#define STM32_IRQ_TIM5_PRIORITY 7 +#define STM32_IRQ_TIM6_PRIORITY 7 +#define STM32_IRQ_TIM7_PRIORITY 7 +#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7 +#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7 +#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7 +#define STM32_IRQ_TIM8_CC_PRIORITY 7 + +#define STM32_IRQ_USART1_PRIORITY 12 +#define STM32_IRQ_USART2_PRIORITY 12 +#define STM32_IRQ_USART3_PRIORITY 12 +#define STM32_IRQ_UART4_PRIORITY 12 +#define STM32_IRQ_UART5_PRIORITY 12 +#define STM32_IRQ_USART6_PRIORITY 12 +#define STM32_IRQ_UART7_PRIORITY 12 +#define STM32_IRQ_UART8_PRIORITY 12 + /* * ADC driver system settings. */ diff --git a/sw/airborne/boards/px4fmu/chibios/v4.0/px4fmu.h b/sw/airborne/boards/px4fmu/chibios/v4.0/px4fmu.h index e746005cf4..91a5c87782 100644 --- a/sw/airborne/boards/px4fmu/chibios/v4.0/px4fmu.h +++ b/sw/airborne/boards/px4fmu/chibios/v4.0/px4fmu.h @@ -13,9 +13,10 @@ */ /* - * AHB_CLK + * Concat macro */ -#define AHB_CLK STM32_HCLK +#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2 +#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2) /* * Onboard LEDs @@ -98,136 +99,127 @@ #define MilliAmpereOfAdc(adc) ((3.3f/4096.0f) * 36367.51556f * adc) /* - * PWM defines TODO + * PWM defines */ -#ifndef USE_PWM0 -#define USE_PWM0 1 -#endif -#if USE_PWM0 -#define PWM_SERVO_0 0 -#define PWM_SERVO_0_GPIO GPIOE -#define PWM_SERVO_0_PIN GPIO14 -#define PWM_SERVO_0_AF GPIO_AF1 -#define PWM_SERVO_0_DRIVER PWMD1 -#define PWM_SERVO_0_CHANNEL 3 -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_0_ACTIVE PWM_OUTPUT_DISABLED -#endif - +#if defined(LINE_SERVO1) #ifndef USE_PWM1 #define USE_PWM1 1 #endif #if USE_PWM1 -#define PWM_SERVO_1 1 -#define PWM_SERVO_1_GPIO GPIOE -#define PWM_SERVO_1_PIN GPIO13 -#define PWM_SERVO_1_AF GPIO_AF1 -#define PWM_SERVO_1_DRIVER PWMD1 -#define PWM_SERVO_1_CHANNEL 2 -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1 0 +#define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1) +#define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1) +#define PWM_SERVO_1_AF AF_LINE_SERVO1 +#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM) +#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1) +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM) +#endif #endif +#if defined(LINE_SERVO2) #ifndef USE_PWM2 #define USE_PWM2 1 #endif #if USE_PWM2 -#define PWM_SERVO_2 2 -#define PWM_SERVO_2_GPIO GPIOE -#define PWM_SERVO_2_PIN GPIO11 -#define PWM_SERVO_2_AF GPIO_AF1 -#define PWM_SERVO_2_DRIVER PWMD1 -#define PWM_SERVO_2_CHANNEL 1 -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2 1 +#define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2) +#define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2) +#define PWM_SERVO_2_AF AF_LINE_SERVO2 +#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM) +#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1) +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM) +#endif #endif +#if defined(LINE_SERVO3) #ifndef USE_PWM3 #define USE_PWM3 1 #endif #if USE_PWM3 -#define PWM_SERVO_3 3 -#define PWM_SERVO_3_GPIO GPIOE -#define PWM_SERVO_3_PIN GPIO9 -#define PWM_SERVO_3_AF GPIO_AF1 -#define PWM_SERVO_3_DRIVER PWMD1 -#define PWM_SERVO_3_CHANNEL 0 -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3 2 +#define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3) +#define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3) +#define PWM_SERVO_3_AF AF_LINE_SERVO3 +#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM) +#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1) +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM) +#endif #endif +#if defined(LINE_SERVO4) #ifndef USE_PWM4 #define USE_PWM4 1 #endif #if USE_PWM4 -#define PWM_SERVO_4 4 -#define PWM_SERVO_4_GPIO GPIOD -#define PWM_SERVO_4_PIN GPIO13 -#define PWM_SERVO_4_AF GPIO_AF2 -#define PWM_SERVO_4_DRIVER PWMD4 -#define PWM_SERVO_4_CHANNEL 1 -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4 3 +#define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4) +#define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4) +#define PWM_SERVO_4_AF AF_LINE_SERVO4 +#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM) +#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1) +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM) +#endif #endif +#if defined(LINE_SERVO5) #ifndef USE_PWM5 #define USE_PWM5 1 #endif #if USE_PWM5 -#define PWM_SERVO_5 5 -#define PWM_SERVO_5_GPIO GPIOD -#define PWM_SERVO_5_PIN GPIO14 -#define PWM_SERVO_5_AF GPIO_AF2 -#define PWM_SERVO_5_DRIVER PWMD4 -#define PWM_SERVO_5_CHANNEL 2 -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5 4 +#define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5) +#define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5) +#define PWM_SERVO_5_AF AF_LINE_SERVO5 +#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM) +#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1) +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM) +#endif #endif - -#ifdef STM32_PWM_USE_TIM1 -#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1 -#else -#define PWM_CONF_TIM1 1 +#if defined(LINE_SERVO6) +#ifndef USE_PWM6 +#define USE_PWM6 1 +#endif +#if USE_PWM6 +#define PWM_SERVO_6 5 +#define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6) +#define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6) +#define PWM_SERVO_6_AF AF_LINE_SERVO6 +#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM) +#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1) +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM) +#endif +#endif + +#if defined(LINE_SERVO7) +#ifndef USE_PWM7 +#define USE_PWM7 1 +#endif +#if USE_PWM7 +#define PWM_SERVO_7 6 +#define PWM_SERVO_7_GPIO PAL_PORT(LINE_SERVO7) +#define PWM_SERVO_7_PIN PAL_PAD(LINE_SERVO7) +#define PWM_SERVO_7_AF AF_LINE_SERVO7 +#define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO7_TIM) +#define PWM_SERVO_7_CHANNEL (SERVO7_TIM_CH-1) +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO7_TIM) +#endif +#endif + +#if defined(LINE_SERVO8) +#ifndef USE_PWM8 +#define USE_PWM8 1 +#endif +#if USE_PWM8 +#define PWM_SERVO_8 7 +#define PWM_SERVO_8_GPIO PAL_PORT(LINE_SERVO8) +#define PWM_SERVO_8_PIN PAL_PAD(LINE_SERVO8) +#define PWM_SERVO_8_AF AF_LINE_SERVO8 +#define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO8_TIM) +#define PWM_SERVO_8_CHANNEL (SERVO8_TIM_CH-1) +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO8_TIM) #endif -#define PWM_CONF1_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM1_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_SERVO_0_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 #endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_OUTPUT_DISABLED, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_OUTPUT_DISABLED, NULL }, \ - }, \ - 0, \ - 0 \ -} /** * UART defines diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/board.c b/sw/airborne/boards/px4fmu/chibios/v5.0/board.c deleted file mode 100644 index fa40f422e2..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/board.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - return true; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/board.cfg b/sw/airborne/boards/px4fmu/chibios/v5.0/board.cfg index bb70e4b43e..d9cacc9ecf 100644 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/board.cfg +++ b/sw/airborne/boards/px4fmu/chibios/v5.0/board.cfg @@ -32,6 +32,25 @@ HEADER */ #define STM32F767xx +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_1 +#endif + +/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/ +#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE +#define ADC_CHANNEL_CURRENT ADC_2 +#endif + +/* Default powerbrick values */ +#define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 10.3208191126f * adc) +#define MilliAmpereOfAdc(adc) ((3.3f/4096.0f) * 24000.0f * adc) + +/* Battery monitoring for file closing */ +#define SDLOG_BAT_ADC ADCD1 +#define SDLOG_BAT_CHAN AD1_1_CHANNEL +#define SDLOG_USB_LED 3 + CONFIG @@ -66,33 +85,26 @@ C15 OSC32_OUT SYS AF0 H00 OSC_IN SYS AF0 H01 OSC_OUT SYS AF0 -#DEFAULT +# DEFAULT DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0 - -# Afficheur : -# DISg = PE2 (old PE5) - - - - # ACTIVE PINS -PA00 ADC1 ADC ADC1_IN0 # BAT1_V -PA01 ADC2 ADC ADC1_IN1 # BAT1_I -PA02 ADC3 ADC ADC1_IN2 # BAT2_V -PA03 ADC4 ADC ADC1_IN3 # BAT2_I -PA04 ADC5 ADC ADC1_IN4 # ADC1_SPARE2 +PA00 ADC1 ADC ADC1_IN0 () # BAT1_V +PA01 ADC2 ADC ADC1_IN1 () # BAT1_I +PA02 ADC3 ADC ADC1_IN2 () # BAT2_V +PA03 ADC4 ADC ADC1_IN3 () # BAT2_I +PA04 ADC5 ADC ADC1_IN4 () # ADC1_SPARE2 PA05 FMU_CAP1 PASSIVE PA06 SPI1_MISO SPI AF:SPI1_MISO PA07 HEATER PASSIVE PA08 CAN3_RX CAN AF:CAN3_RX PA09 USB_VBUS INPUT PULLDOWN -PA10 SERVO2 PWM AF:TIM1_CH3 +PA10 SERVO2 PWM AF:TIM1_CH3 () PA11 USB_DM OTG AF:USB_OTG_FS_DM PA12 USB_DP OTG AF:USB_OTG_FS_DP PA15 CAN3_TX CAN AF:CAN3_TX -PB00 RSSI_IN ADC ADC1_IN8 +PB00 RSSI_IN ADC ADC1_IN8 () PB01 LED1 LED # LED_RED PB03 FMU_CAP2 PASSIVE PB04 DRDY1_ICM20689 PASSIVE @@ -108,40 +120,40 @@ PB13 CAN2_TX CAN AF:CAN2_TX PB14 DRDY2_BMI055_GYRO PASSIVE PB15 DRDY2_BMI055_ACC PASSIVE -PC00 SCALED_V5 ADC ADC1_IN10 -PC01 SCALED_3V3_SENSORS ADC ADC1_IN11 -PC02 HW_VER_SENSE ADC ADC1_IN12 -PC03 HW_REV_SENSE ADC ADC1_IN13 -PC04 ADC6 ADC ADC1_IN14 +PC00 SCALED_V5 ADC ADC1_IN10 () +PC01 SCALED_3V3_SENSORS ADC ADC1_IN11 () +PC02 HW_VER_SENSE ADC ADC1_IN12 () +PC03 HW_REV_SENSE ADC ADC1_IN13 () +PC04 ADC6 ADC ADC1_IN14 () PC05 DRDY4_ICM20602 PASSIVE PC06 LED2 LED # LED_GREEN PC07 LED3 LED # LED_BLUE -PC08 SDIO_D0 SDIO AF:SDMMC1_D0 -PC09 SDIO_D1 SDIO AF:SDMMC1_D1 -PC10 SDIO_D2 SDIO AF:SDMMC1_D2 -PC11 SDIO_D3 SDIO AF:SDMMC1_D3 -PC12 SDIO_CK SDIO AF:SDMMC1_CK +PC08 SDIO_D0 SDIO AF:SDMMC1_D0 +PC09 SDIO_D1 SDIO AF:SDMMC1_D1 +PC10 SDIO_D2 SDIO AF:SDMMC1_D2 +PC11 SDIO_D3 SDIO AF:SDMMC1_D3 +PC12 SDIO_CK SDIO AF:SDMMC1_CK PC13 DRDY5_BMI055_GYRO PASSIVE PD00 UART4_RX UART AF:UART4_RX PD01 UART4_TX UART AF:UART4_TX -PD02 SDIO_CMD SDIO AF:SDMMC1_CMD -PD03 UART2_CTS PASSIVE -PD04 UART2_RTS PASSIVE -PD05 UART2_TX UART AF:USART2_TX -PD06 UART2_RX UART AF:USART2_RX +PD02 SDIO_CMD SDIO AF:SDMMC1_CMD +PD03 UART2_CTS PASSIVE +PD04 UART2_RTS PASSIVE +PD05 UART2_TX UART AF:USART2_TX +PD06 UART2_RX UART AF:USART2_RX PD07 SPI1_MOSI SPI AF:SPI1_MOSI -PD08 UART3_TX UART AF:USART3_TX -PD09 UART3_RX UART AF:USART3_RX +PD08 UART3_TX UART AF:USART3_TX +PD09 UART3_RX UART AF:USART3_RX PD10 DRDY6_BMI055_ACC PASSIVE -PD11 UART3_CTS PASSIVE -PD12 UART3_RTS PASSIVE -PD13 SERVO5 PWM AF:TIM4_CH2 -PD14 SERVO6 PWM AF:TIM4_CH3 +PD11 UART3_CTS PASSIVE +PD12 UART3_RTS PASSIVE +PD13 SERVO5 PWM AF:TIM4_CH2 () +PD14 SERVO6 PWM AF:TIM4_CH3 () PD15 DRDY7_EXTERNAL1 PASSIVE -PE00 UART8_RX UART AF:UART8_RX -PE01 UART8_TX UART AF:UART8_TX +PE00 UART8_RX UART AF:UART8_RX +PE01 UART8_TX UART AF:UART8_TX PE02 SPI4_SCK SPI AF:SPI4_SCK PE03 V3V3_SENSORS_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH PE04 V3V3_SPEKTRUM_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH @@ -149,26 +161,26 @@ PE05 BUZZER PASSIVE PE06 SPI4_MOSI SPI AF:SPI4_MOSI PE07 DRDY8 PASSIVE PE08 UART7_TX UART AF:UART7_TX -PE09 SERVO4 PWM AF:TIM1_CH1 +PE09 SERVO4 PWM AF:TIM1_CH1 () PE10 SAFETY_SWITCH_IN INPUT PULLDOWN -PE11 SERVO3 PWM AF:TIM1_CH2 +PE11 SERVO3 PWM AF:TIM1_CH2 () PE12 LED4 LED # SAFTEY_SWITCH_LED PE13 SPI4_MISO SPI AF:SPI4_MISO -PE14 SERVO1 PWM AF:TIM1_CH4 +PE14 SERVO1 PWM AF:TIM1_CH4 () PE15 V5V_PERIPH_OC PASSIVE PF00 I2C2_SDA I2C AF:I2C2_SDA PF01 I2C2_SCL I2C AF:I2C2_SCL -PF02 SPI_SLAVE0 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS1_ICM20689 -PF03 SPI_SLAVE1 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS2_ICM20602 -PF04 SPI_SLAVE2 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS3_BMI055_GYRO -PF05 SPI_SLAVE3 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI2_CS4_FRAM +PF02 SPI_SLAVE0 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS1_ICM20689 +PF03 SPI_SLAVE1 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS2_ICM20602 +PF04 SPI_SLAVE2 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS3_BMI055_GYRO +PF05 SPI_SLAVE3 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI2_CS4_FRAM PF06 UART7_RX UART AF:UART7_RX PF07 SPI5_SCK SPI AF:SPI5_SCK PF08 SPI5_MISO SPI AF:SPI5_MISO PF09 SPI5_MOSI SPI AF:SPI5_MOSI -PF10 SPI_SLAVE4 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI4_CS1_MS5611 -PF11 SPI_SLAVE5 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI4_CS2 +PF10 SPI_SLAVE4 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI4_CS1_MS5611 +PF11 SPI_SLAVE5 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI4_CS2 PF12 V5V_HIPOWER_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW PF13 V5V_HIPOWER_OC PASSIVE PF14 I2C4_SCL I2C AF:I2C4_SCL @@ -184,7 +196,7 @@ PG06 V5V_WIFI_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH PG07 V3V3_SD_CARD_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH PG08 USART6_RTS PASSIVE PG09 USART6_RX UART AF:USART6_RX -PG10 SPI_SLAVE6 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS4_BMI055_ACC +PG10 SPI_SLAVE6 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS4_BMI055_ACC PG11 SPI1_SCK SPI AF:SPI1_SCK PG12 SPI6_MISO SPI AF:SPI6_MISO PG13 SPI6_SCK SPI AF:SPI6_SCK @@ -194,11 +206,11 @@ PG15 USART6_CTS PASSIVE PH02 CAN1_SILENT_S0 OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW PH03 CAN2_SILENT_S1 OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW PH04 CAN3_SILENT_S2 OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW -PH05 SPI_SLAVE7 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS5_AUX_MEM -PH06 SERVO7 PWM AF:TIM12_CH1 +PH05 SPI_SLAVE7 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI1_CS5_AUX_MEM +PH06 SERVO7 PWM AF:TIM12_CH1 () PH07 I2C3_SCL I2C AF:I2C3_SCL PH08 I2C3_SDA I2C AF:I2C3_SDA -PH09 SERVO8 PWM AF:TIM12_CH2 +PH09 SERVO8 PWM AF:TIM12_CH2 () PH10 LED5 LED # UI_LED_RED PH11 LED6 LED # UI_LED_GREEN PH12 LED7 LED # UI_LED_BLUE @@ -210,11 +222,15 @@ PI00 ARMED LED PI01 SPI2_SCK SPI AF:SPI2_SCK PI02 SPI2_MISO SPI AF:SPI2_MISO PI03 SPI2_MOSI SPI AF:SPI2_MOSI -PI04 SPI_SLAVE8 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS1 +PI04 SPI_SLAVE8 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS1 PI05 RC_INPUT ICU AF:TIM8_CH1 -PI06 SPI_SLAVE9 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS1 -PI07 SPI_SLAVE10 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS2 -PI08 SPI_SLAVE11 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS3 +PI06 SPI_SLAVE9 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS1 +PI07 SPI_SLAVE10 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS2 +PI08 SPI_SLAVE11 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI6_CS3 PI09 CAN1_RX CAN AF:CAN1_RX -PI10 SPI_SLAVE12 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS2 -PI11 SPI_SLAVE13 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS3 +PI10 SPI_SLAVE12 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS2 +PI11 SPI_SLAVE13 OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_HIGH # SPI5_CS3 + +# GROUPS +GROUP ENERGY_SAVE_INPUTS %NAME=~/^SERVO[0-9]+|LED[0-9]+|SPI_SLAVE[0-9]+$/ +GROUP ENERGY_SAVE_LOWS %NAME=~/^V3V3_SENSORS_EN|V3V3_SPEKTRUM_EN|V5V_HIPOWER_EN|V5V_PERIPH_EN|V5V_RC_EN|V5V_WIFI_EN$/ diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/board.h b/sw/airborne/boards/px4fmu/chibios/v5.0/board.h index c7ca118947..a3592c5401 100644 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/board.h +++ b/sw/airborne/boards/px4fmu/chibios/v5.0/board.h @@ -46,6 +46,25 @@ */ #define STM32F767xx +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_1 +#endif + +/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/ +#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE +#define ADC_CHANNEL_CURRENT ADC_2 +#endif + +/* Default powerbrick values */ +#define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 10.3208191126f * adc) +#define MilliAmpereOfAdc(adc) ((3.3f/4096.0f) * 24000.0f * adc) + +/* Battery monitoring for file closing */ +#define SDLOG_BAT_ADC ADCD1 +#define SDLOG_BAT_CHAN AD1_1_CHANNEL +#define SDLOG_USB_LED 3 + /* * IO pins assignments. */ @@ -1677,6 +1696,128 @@ #define AF_LINE_CAN1_RX 9U +#define ADC1_ADC 1 +#define ADC1_ADC_FN IN +#define ADC1_ADC_IN 0 +#define ADC2_ADC 1 +#define ADC2_ADC_FN IN +#define ADC2_ADC_IN 1 +#define ADC3_ADC 1 +#define ADC3_ADC_FN IN +#define ADC3_ADC_IN 2 +#define ADC4_ADC 1 +#define ADC4_ADC_FN IN +#define ADC4_ADC_IN 3 +#define ADC5_ADC 1 +#define ADC5_ADC_FN IN +#define ADC5_ADC_IN 4 +#define SERVO2_TIM 1 +#define SERVO2_TIM_FN CH +#define SERVO2_TIM_CH 3 +#define SERVO2_TIM_AF 1 +#define RSSI_IN_ADC 1 +#define RSSI_IN_ADC_FN IN +#define RSSI_IN_ADC_IN 8 +#define SCALED_V5_ADC 1 +#define SCALED_V5_ADC_FN IN +#define SCALED_V5_ADC_IN 10 +#define SCALED_3V3_SENSORS_ADC 1 +#define SCALED_3V3_SENSORS_ADC_FN IN +#define SCALED_3V3_SENSORS_ADC_IN 11 +#define HW_VER_SENSE_ADC 1 +#define HW_VER_SENSE_ADC_FN IN +#define HW_VER_SENSE_ADC_IN 12 +#define HW_REV_SENSE_ADC 1 +#define HW_REV_SENSE_ADC_FN IN +#define HW_REV_SENSE_ADC_IN 13 +#define ADC6_ADC 1 +#define ADC6_ADC_FN IN +#define ADC6_ADC_IN 14 +#define SERVO5_TIM 4 +#define SERVO5_TIM_FN CH +#define SERVO5_TIM_CH 2 +#define SERVO5_TIM_AF 2 +#define SERVO6_TIM 4 +#define SERVO6_TIM_FN CH +#define SERVO6_TIM_CH 3 +#define SERVO6_TIM_AF 2 +#define SERVO4_TIM 1 +#define SERVO4_TIM_FN CH +#define SERVO4_TIM_CH 1 +#define SERVO4_TIM_AF 1 +#define SERVO3_TIM 1 +#define SERVO3_TIM_FN CH +#define SERVO3_TIM_CH 2 +#define SERVO3_TIM_AF 1 +#define SERVO1_TIM 1 +#define SERVO1_TIM_FN CH +#define SERVO1_TIM_CH 4 +#define SERVO1_TIM_AF 1 +#define SERVO7_TIM 12 +#define SERVO7_TIM_FN CH +#define SERVO7_TIM_CH 1 +#define SERVO7_TIM_AF 9 +#define SERVO8_TIM 12 +#define SERVO8_TIM_FN CH +#define SERVO8_TIM_CH 2 +#define SERVO8_TIM_AF 9 + +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_LOWS \ + LINE_V3V3_SENSORS_EN, \ + LINE_V3V3_SPEKTRUM_EN, \ + LINE_V5V_HIPOWER_EN, \ + LINE_V5V_PERIPH_EN, \ + LINE_V5V_RC_EN, \ + LINE_V5V_WIFI_EN +#define ENERGY_SAVE_LOWS_SIZE 6 + +#define ENERGY_SAVE_INPUTS \ + LINE_SERVO2, \ + LINE_LED1, \ + LINE_LED2, \ + LINE_LED3, \ + LINE_SERVO5, \ + LINE_SERVO6, \ + LINE_SERVO4, \ + LINE_SERVO3, \ + LINE_LED4, \ + LINE_SERVO1, \ + LINE_SPI_SLAVE0, \ + LINE_SPI_SLAVE1, \ + LINE_SPI_SLAVE2, \ + LINE_SPI_SLAVE3, \ + LINE_SPI_SLAVE4, \ + LINE_SPI_SLAVE5, \ + LINE_SPI_SLAVE6, \ + LINE_SPI_SLAVE7, \ + LINE_SERVO7, \ + LINE_SERVO8, \ + LINE_LED5, \ + LINE_LED6, \ + LINE_LED7, \ + LINE_SPI_SLAVE8, \ + LINE_SPI_SLAVE9, \ + LINE_SPI_SLAVE10, \ + LINE_SPI_SLAVE11, \ + LINE_SPI_SLAVE12, \ + LINE_SPI_SLAVE13 +#define ENERGY_SAVE_INPUTS_SIZE 29 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/board.mk b/sw/airborne/boards/px4fmu/chibios/v5.0/board.mk deleted file mode 100644 index 8d560f4385..0000000000 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/board.mk +++ /dev/null @@ -1,24 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDINC = $(CHIBIOS_BOARD_DIR) - -# List of all the board related files. -BOARDSRC = ${BOARDINC}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) diff --git a/sw/airborne/boards/px4fmu/chibios/v5.0/mcuconf.h b/sw/airborne/boards/px4fmu/chibios/v5.0/mcuconf.h index d1f524b58c..cf8bebc7c2 100644 --- a/sw/airborne/boards/px4fmu/chibios/v5.0/mcuconf.h +++ b/sw/airborne/boards/px4fmu/chibios/v5.0/mcuconf.h @@ -497,8 +497,8 @@ sdlog message buffer and queue configuration */ #define SDLOG_QUEUE_BUCKETS 1024 -#define SDLOG_MAX_MESSAGE_LEN 252 +#define SDLOG_MAX_MESSAGE_LEN 300 #define SDLOG_NUM_FILES 2 -#define SDLOG_ALL_BUFFERS_SIZE (SDLOG_NUM_FILES*4096*2) +#define SDLOG_ALL_BUFFERS_SIZE (SDLOG_NUM_FILES*16*1024) #endif /* MCUCONF_H */ diff --git a/sw/airborne/boards/tawaki/chibios/common/board.c b/sw/airborne/boards/tawaki/chibios/common/board.c deleted file mode 100644 index bf8d777ca3..0000000000 --- a/sw/airborne/boards/tawaki/chibios/common/board.c +++ /dev/null @@ -1,287 +0,0 @@ -/* - ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. -*/ - -/* - * This file has been automatically generated using ChibiStudio board - * generator plugin. Do not edit manually. - */ - -#include "hal.h" -#include "stm32_gpio.h" - -/*===========================================================================*/ -/* Driver local definitions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables and types. */ -/*===========================================================================*/ - -/** - * @brief Type of STM32 GPIO port setup. - */ -typedef struct { - uint32_t moder; - uint32_t otyper; - uint32_t ospeedr; - uint32_t pupdr; - uint32_t odr; - uint32_t afrl; - uint32_t afrh; -} gpio_setup_t; - -/** - * @brief Type of STM32 GPIO initialization data. - */ -typedef struct { -#if STM32_HAS_GPIOA || defined(__DOXYGEN__) - gpio_setup_t PAData; -#endif -#if STM32_HAS_GPIOB || defined(__DOXYGEN__) - gpio_setup_t PBData; -#endif -#if STM32_HAS_GPIOC || defined(__DOXYGEN__) - gpio_setup_t PCData; -#endif -#if STM32_HAS_GPIOD || defined(__DOXYGEN__) - gpio_setup_t PDData; -#endif -#if STM32_HAS_GPIOE || defined(__DOXYGEN__) - gpio_setup_t PEData; -#endif -#if STM32_HAS_GPIOF || defined(__DOXYGEN__) - gpio_setup_t PFData; -#endif -#if STM32_HAS_GPIOG || defined(__DOXYGEN__) - gpio_setup_t PGData; -#endif -#if STM32_HAS_GPIOH || defined(__DOXYGEN__) - gpio_setup_t PHData; -#endif -#if STM32_HAS_GPIOI || defined(__DOXYGEN__) - gpio_setup_t PIData; -#endif -#if STM32_HAS_GPIOJ || defined(__DOXYGEN__) - gpio_setup_t PJData; -#endif -#if STM32_HAS_GPIOK || defined(__DOXYGEN__) - gpio_setup_t PKData; -#endif -} gpio_config_t; - -/** - * @brief STM32 GPIO static initialization data. - */ -static const gpio_config_t gpio_default_config = { -#if STM32_HAS_GPIOA - {VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, - VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH}, -#endif -#if STM32_HAS_GPIOB - {VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, - VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH}, -#endif -#if STM32_HAS_GPIOC - {VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, - VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH}, -#endif -#if STM32_HAS_GPIOD - {VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, - VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH}, -#endif -#if STM32_HAS_GPIOE - {VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, - VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH}, -#endif -#if STM32_HAS_GPIOF - {VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, - VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH}, -#endif -#if STM32_HAS_GPIOG - {VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, - VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH}, -#endif -#if STM32_HAS_GPIOH - {VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, - VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH}, -#endif -#if STM32_HAS_GPIOI - {VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, - VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}, -#endif -#if STM32_HAS_GPIOJ - {VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR, - VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH}, -#endif -#if STM32_HAS_GPIOK - {VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR, - VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH} -#endif -}; - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) { - - gpiop->OTYPER = config->otyper; - gpiop->OSPEEDR = config->ospeedr; - gpiop->PUPDR = config->pupdr; - gpiop->ODR = config->odr; - gpiop->AFRL = config->afrl; - gpiop->AFRH = config->afrh; - gpiop->MODER = config->moder; -} - -static void stm32_gpio_init(void) { - - /* Enabling GPIO-related clocks, the mask comes from the - registry header file.*/ - rccResetAHB1(STM32_GPIO_EN_MASK); - rccEnableAHB1(STM32_GPIO_EN_MASK, true); - - /* Initializing all the defined GPIO ports.*/ -#if STM32_HAS_GPIOA - gpio_init(GPIOA, &gpio_default_config.PAData); -#endif -#if STM32_HAS_GPIOB - gpio_init(GPIOB, &gpio_default_config.PBData); -#endif -#if STM32_HAS_GPIOC - gpio_init(GPIOC, &gpio_default_config.PCData); -#endif -#if STM32_HAS_GPIOD - gpio_init(GPIOD, &gpio_default_config.PDData); -#endif -#if STM32_HAS_GPIOE - gpio_init(GPIOE, &gpio_default_config.PEData); -#endif -#if STM32_HAS_GPIOF - gpio_init(GPIOF, &gpio_default_config.PFData); -#endif -#if STM32_HAS_GPIOG - gpio_init(GPIOG, &gpio_default_config.PGData); -#endif -#if STM32_HAS_GPIOH - gpio_init(GPIOH, &gpio_default_config.PHData); -#endif -#if STM32_HAS_GPIOI - gpio_init(GPIOI, &gpio_default_config.PIData); -#endif -#if STM32_HAS_GPIOJ - gpio_init(GPIOJ, &gpio_default_config.PJData); -#endif -#if STM32_HAS_GPIOK - gpio_init(GPIOK, &gpio_default_config.PKData); -#endif -} - -/*===========================================================================*/ -/* Driver interrupt handlers. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief Early initialization code. - * @details GPIO ports and system clocks are initialized before everything - * else. - */ -void __early_init(void) { - - stm32_gpio_init(); - stm32_clock_init(); -} - -#if HAL_USE_SDC || defined(__DOXYGEN__) -/** - * @brief SDC card detection. - */ -bool sdc_lld_is_card_inserted(SDCDriver *sdcp) { - (void)sdcp; - /* assume card is inserted as there is no SD_DETECT pin - * actual detection will be done by the software - */ - return true; -} - -/** - * @brief SDC card write protection detection. - */ -bool sdc_lld_is_write_protected(SDCDriver *sdcp) { - - (void)sdcp; - return false; -} -#endif /* HAL_USE_SDC */ - -#if HAL_USE_MMC_SPI || defined(__DOXYGEN__) -/** - * @brief MMC_SPI card detection. - */ -bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { - - (void)mmcp; - /* TODO: Fill the implementation.*/ - return true; -} - -/** - * @brief MMC_SPI card write protection detection. - */ -bool 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) { - -} - -/** Energy saving procedure for SD log closing - */ -void mcu_periph_energy_save(void) -{ - palSetLineMode(LINE_LED1, PAL_MODE_INPUT); - palSetLineMode(LINE_LED2, PAL_MODE_INPUT); - palSetLineMode(LINE_LED3, PAL_MODE_INPUT); - palSetLineMode(LINE_LED4, PAL_MODE_INPUT); - palSetLineMode(LINE_SPI4_INTERNAL_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_SPI2_EXTERNAL_CS, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_A1, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_A2, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_A3, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_A4, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_B1, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_B2, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_B3, PAL_MODE_INPUT); - palSetLineMode(LINE_AUX_B4, PAL_MODE_INPUT); -} - diff --git a/sw/airborne/boards/tawaki/chibios/common/tawaki.h b/sw/airborne/boards/tawaki/chibios/common/tawaki.h index 5eca3d757e..813311171a 100644 --- a/sw/airborne/boards/tawaki/chibios/common/tawaki.h +++ b/sw/airborne/boards/tawaki/chibios/common/tawaki.h @@ -170,9 +170,7 @@ #define PWM_SERVO_1_AF AF_SRVA1 #define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA1_TIM) #define PWM_SERVO_1_CHANNEL (SRVA1_TIM_CH-1) -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA1_TIM) #endif #ifndef USE_PWM2 @@ -185,9 +183,7 @@ #define PWM_SERVO_2_AF AF_SRVA2 #define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA2_TIM) #define PWM_SERVO_2_CHANNEL (SRVA2_TIM_CH-1) -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA2_TIM) #endif #ifndef USE_PWM3 @@ -200,9 +196,7 @@ #define PWM_SERVO_3_AF AF_SRVA3 #define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA3_TIM) #define PWM_SERVO_3_CHANNEL (SRVA3_TIM_CH-1) -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA3_TIM) #endif #ifndef USE_PWM4 @@ -215,9 +209,7 @@ #define PWM_SERVO_4_AF AF_SRVA4 #define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVA4_TIM) #define PWM_SERVO_4_CHANNEL (SRVA4_TIM_CH-1) -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVA4_TIM) #endif // SRVb connector, PWM mode disabled by default (DShot is enabled by default) @@ -232,9 +224,7 @@ #define PWM_SERVO_5_AF AF_SRVB1 #define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB1_TIM) #define PWM_SERVO_5_CHANNEL (SRVB1_TIM_CH-1) -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB1_TIM) #endif #ifndef USE_PWM6 @@ -247,9 +237,7 @@ #define PWM_SERVO_6_AF AF_SRVB2 #define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB2_TIM) #define PWM_SERVO_6_CHANNEL (SRVB2_TIM_CH-1) -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB2_TIM) #endif #ifndef USE_PWM7 @@ -262,9 +250,7 @@ #define PWM_SERVO_7_AF AF_SRVB3 #define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB3_TIM) #define PWM_SERVO_7_CHANNEL (SRVB3_TIM_CH-1) -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB3_TIM) #endif #ifndef USE_PWM8 @@ -277,9 +263,7 @@ #define PWM_SERVO_8_AF AF_SRVB4 #define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SRVB4_TIM) #define PWM_SERVO_8_CHANNEL (SRVB4_TIM_CH-1) -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SRVB4_TIM) #endif #ifndef USE_PWM9 @@ -292,9 +276,7 @@ #define PWM_SERVO_9_AF GPIO_AF2 #define PWM_SERVO_9_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A1_TIM) #define PWM_SERVO_9_CHANNEL (AUX_A1_TIM_CH-1) -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_9_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_9_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A1_TIM) #endif #ifndef USE_PWM10 @@ -307,9 +289,7 @@ #define PWM_SERVO_10_AF GPIO_AF2 #define PWM_SERVO_10_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A2_TIM) #define PWM_SERVO_10_CHANNEL (AUX_A2_TIM_CH-1) -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_10_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_10_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A2_TIM) #endif #ifndef USE_PWM11 @@ -322,9 +302,7 @@ #define PWM_SERVO_11_AF GPIO_AF2 #define PWM_SERVO_11_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A3_TIM) #define PWM_SERVO_11_CHANNEL (AUX_A3_TIM_CH-1) -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_11_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_11_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A3_TIM) #endif #ifndef USE_PWM12 @@ -337,9 +315,7 @@ #define PWM_SERVO_12_AF GPIO_AF2 #define PWM_SERVO_12_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_A4_TIM) #define PWM_SERVO_12_CHANNEL (AUX_A4_TIM_CH-1) -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_12_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_12_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_A4_TIM) #endif #ifndef USE_PWM13 @@ -352,9 +328,7 @@ #define PWM_SERVO_13_AF GPIO_AF2 #define PWM_SERVO_13_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B1_TIM) #define PWM_SERVO_13_CHANNEL (AUX_B1_TIM_CH-1) -#define PWM_SERVO_13_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_13_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_13_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B1_TIM) #endif #ifndef USE_PWM14 @@ -367,9 +341,7 @@ #define PWM_SERVO_14_AF GPIO_AF2 #define PWM_SERVO_14_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B2_TIM) #define PWM_SERVO_14_CHANNEL (AUX_B2_TIM_CH-1) -#define PWM_SERVO_14_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_14_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_14_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B2_TIM) #endif #ifndef USE_PWM15 @@ -382,9 +354,7 @@ #define PWM_SERVO_15_AF GPIO_AF2 #define PWM_SERVO_15_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B3_TIM) #define PWM_SERVO_15_CHANNEL (AUX_B3_TIM_CH-1) -#define PWM_SERVO_15_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_15_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_15_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B3_TIM) #endif #ifndef USE_PWM16 @@ -397,9 +367,7 @@ #define PWM_SERVO_16_AF GPIO_AF2 #define PWM_SERVO_16_DRIVER CONCAT_BOARD_PARAM(PWMD, AUX_B4_TIM) #define PWM_SERVO_16_CHANNEL (AUX_B4_TIM_CH-1) -#define PWM_SERVO_16_ACTIVE PWM_OUTPUT_ACTIVE_HIGH -#else -#define PWM_SERVO_16_ACTIVE PWM_OUTPUT_DISABLED +#define PWM_SERVO_16_CONF CONCAT_BOARD_PARAM(pwmcfg, AUX_B4_TIM) #endif // servo index starting at 1 + regular servos + aux servos @@ -407,82 +375,6 @@ #define ACTUATORS_PWM_NB 17 -#ifdef STM32_PWM_USE_TIM1 -#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1 -#else -#define PWM_CONF_TIM1 1 -#endif -#define PWM_CONF1_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM1_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_1_ACTIVE, NULL }, \ - { PWM_SERVO_2_ACTIVE, NULL }, \ - { PWM_SERVO_3_ACTIVE, NULL }, \ - { PWM_SERVO_4_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM3 -#define PWM_CONF_TIM3 STM32_PWM_USE_TIM3 -#else -#define PWM_CONF_TIM3 1 -#endif -#define PWM_CONF3_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM3_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_12_ACTIVE, NULL }, \ - { PWM_SERVO_14_ACTIVE, NULL }, \ - { PWM_SERVO_15_ACTIVE, NULL }, \ - { PWM_SERVO_16_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM4 -#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4 -#else -#define PWM_CONF_TIM4 1 -#endif -#define PWM_CONF4_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM4_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_5_ACTIVE, NULL }, \ - { PWM_SERVO_6_ACTIVE, NULL }, \ - { PWM_SERVO_7_ACTIVE, NULL }, \ - { PWM_SERVO_8_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - -#ifdef STM32_PWM_USE_TIM5 -#define PWM_CONF_TIM5 STM32_PWM_USE_TIM5 -#else -#define PWM_CONF_TIM5 1 -#endif -#define PWM_CONF5_DEF { \ - PWM_FREQUENCY, \ - PWM_FREQUENCY/TIM5_SERVO_HZ, \ - NULL, \ - { \ - { PWM_SERVO_9_ACTIVE, NULL }, \ - { PWM_SERVO_10_ACTIVE, NULL }, \ - { PWM_SERVO_11_ACTIVE, NULL }, \ - { PWM_SERVO_13_ACTIVE, NULL }, \ - }, \ - 0, \ - 0 \ -} - /** * DSHOT */ diff --git a/sw/airborne/boards/tawaki/chibios/v1.0/board.h b/sw/airborne/boards/tawaki/chibios/v1.0/board.h index cf142bc292..b024f1d067 100644 --- a/sw/airborne/boards/tawaki/chibios/v1.0/board.h +++ b/sw/airborne/boards/tawaki/chibios/v1.0/board.h @@ -1661,6 +1661,38 @@ #define SRVA4_TIM_CH 4 #define SRVA4_TIM_AF 1 +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_AUX_A1, \ + LINE_AUX_A2, \ + LINE_AUX_A3, \ + LINE_AUX_B1, \ + LINE_AUX_A4, \ + LINE_AUX_B2, \ + LINE_LED2, \ + LINE_AUX_B3, \ + LINE_AUX_B4, \ + LINE_SPI2_EXTERNAL_CS, \ + LINE_LED3, \ + LINE_LED4, \ + LINE_LED1, \ + LINE_SPI4_INTERNAL_CS +#define ENERGY_SAVE_INPUT_SIZE 14 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/tawaki/chibios/v1.0/board.mk b/sw/airborne/boards/tawaki/chibios/v1.0/board.mk deleted file mode 100644 index 8323530b71..0000000000 --- a/sw/airborne/boards/tawaki/chibios/v1.0/board.mk +++ /dev/null @@ -1,26 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDCOMMON = $(CHIBIOS_BOARD_DIR)/../common -BOARDINC = $(CHIBIOS_BOARD_DIR) $(BOARDCOMMON) - -# List of all the board related files. -BOARDSRC = ${BOARDCOMMON}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) - diff --git a/sw/airborne/boards/tawaki/chibios/v1.0/tawaki_1.0.cfg b/sw/airborne/boards/tawaki/chibios/v1.0/tawaki_1.0.cfg index c2ca0ad0cc..bc9f6da347 100644 --- a/sw/airborne/boards/tawaki/chibios/v1.0/tawaki_1.0.cfg +++ b/sw/airborne/boards/tawaki/chibios/v1.0/tawaki_1.0.cfg @@ -135,5 +135,5 @@ PE11 SRVA2 PWM AF:TIM1_CH2 () PE13 SRVA3 PWM AF:TIM1_CH3 () PE14 SRVA4 PWM AF:TIM1_CH4 () - - +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^AUX_[A-B][0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/boards/tawaki/chibios/v1.1/Makefile b/sw/airborne/boards/tawaki/chibios/v1.1/Makefile index 4dda49f34b..b4b48dcde7 100644 --- a/sw/airborne/boards/tawaki/chibios/v1.1/Makefile +++ b/sw/airborne/boards/tawaki/chibios/v1.1/Makefile @@ -4,6 +4,6 @@ # documentation is here : # https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/DOC/boardGen.pdf -board.h: tawaki_v1.1.cfg Makefile +board.h: tawaki_1.1.cfg Makefile boardGen.pl --no-pp-pin --no-pp-line $< $@ diff --git a/sw/airborne/boards/tawaki/chibios/v1.1/board.h b/sw/airborne/boards/tawaki/chibios/v1.1/board.h index 28f96e713a..be6a1d7385 100644 --- a/sw/airborne/boards/tawaki/chibios/v1.1/board.h +++ b/sw/airborne/boards/tawaki/chibios/v1.1/board.h @@ -1661,6 +1661,38 @@ #define SRVA4_TIM_CH 4 #define SRVA4_TIM_AF 1 +#define BOARD_GROUP_DECLFOREACH(line, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + +#define BOARD_GROUP_FOREACH(line, group) \ + for (ioline_t i=0, line = group ## _ARRAY[i]; (i < group ## _SIZE) && (line = group ## _ARRAY[i]); i++) + + +#define BOARD_GROUP_DECLFOR(array, index, group) \ + static const ioline_t group ## _ARRAY[] = {group}; \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define BOARD_GROUP_FOR(array, index, group) \ + for (ioline_t index=0, *array = (ioline_t *) group ## _ARRAY; index < group ## _SIZE; index++) + +#define ENERGY_SAVE_INPUT \ + LINE_AUX_A1, \ + LINE_AUX_A2, \ + LINE_AUX_A3, \ + LINE_AUX_A4, \ + LINE_AUX_B1, \ + LINE_AUX_B2, \ + LINE_LED2, \ + LINE_AUX_B3, \ + LINE_AUX_B4, \ + LINE_SPI2_EXTERNAL_CS, \ + LINE_LED3, \ + LINE_LED4, \ + LINE_LED1, \ + LINE_SPI4_INTERNAL_CS +#define ENERGY_SAVE_INPUT_SIZE 14 + #if !defined(_FROM_ASM_) #ifdef __cplusplus extern "C" { diff --git a/sw/airborne/boards/tawaki/chibios/v1.1/board.mk b/sw/airborne/boards/tawaki/chibios/v1.1/board.mk deleted file mode 100644 index 8323530b71..0000000000 --- a/sw/airborne/boards/tawaki/chibios/v1.1/board.mk +++ /dev/null @@ -1,26 +0,0 @@ -# -# ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Required include directories -BOARDCOMMON = $(CHIBIOS_BOARD_DIR)/../common -BOARDINC = $(CHIBIOS_BOARD_DIR) $(BOARDCOMMON) - -# List of all the board related files. -BOARDSRC = ${BOARDCOMMON}/board.c - -# Shared variables -ALLCSRC += $(BOARDSRC) -ALLINC += $(BOARDINC) - diff --git a/sw/airborne/boards/tawaki/chibios/v1.1/tawaki_1.1.cfg b/sw/airborne/boards/tawaki/chibios/v1.1/tawaki_1.1.cfg index 6c5b6bc90b..6a475b66dd 100644 --- a/sw/airborne/boards/tawaki/chibios/v1.1/tawaki_1.1.cfg +++ b/sw/airborne/boards/tawaki/chibios/v1.1/tawaki_1.1.cfg @@ -135,5 +135,5 @@ PE11 SRVA2 PWM AF:TIM1_CH2 () PE13 SRVA3 PWM AF:TIM1_CH3 () PE14 SRVA4 PWM AF:TIM1_CH4 () - - +# GROUPS +GROUP ENERGY_SAVE_INPUT %NAME=~/^AUX_[A-B][0-9]+|LED[0-9]+|.*_CS$/ diff --git a/sw/airborne/mcu.c b/sw/airborne/mcu.c index 3aaef67264..ebd9b9db28 100644 --- a/sw/airborne/mcu.c +++ b/sw/airborne/mcu.c @@ -103,13 +103,11 @@ void mcu_init(void) #if defined BTN_ON gpio_setup_input(BTN_ON, BTN_ON_PIN); - if(gpio_get(BTN_ON, BTN_ON_PIN)) - { + if (gpio_get(BTN_ON, BTN_ON_PIN)) { MCU_PWR_ON(MCU_PWR, MCU_PWR_PIN); - } - else { + } else { // Turn off and stop: wait until all power is off - while(true) { + while (true) { MCU_PWR_OFF(MCU_PWR, MCU_PWR_PIN); } } diff --git a/sw/airborne/mcu_periph/spi.h b/sw/airborne/mcu_periph/spi.h index abd3c7d02b..329ce9da8e 100644 --- a/sw/airborne/mcu_periph/spi.h +++ b/sw/airborne/mcu_periph/spi.h @@ -195,6 +195,9 @@ struct spi_periph { #define SPI_SLAVE3 3 #define SPI_SLAVE4 4 #define SPI_SLAVE5 5 +#define SPI_SLAVE6 6 +#define SPI_SLAVE7 7 +#define SPI_SLAVE8 8 /// @todo SPI error struct //extern uint8_t spi_nb_ovrn; diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h index 05e7787e16..87b6542c21 100644 --- a/sw/airborne/mcu_periph/uart.h +++ b/sw/airborne/mcu_periph/uart.h @@ -33,18 +33,20 @@ #include "std.h" #ifndef UART_RX_BUFFER_SIZE -#if defined STM32F4 || defined STM32F7 //the F4 and F7 have enough memory -#define UART_RX_BUFFER_SIZE 256 -#else +// Only for the STM32F1 less buffer +#if defined(STM32F1) #define UART_RX_BUFFER_SIZE 128 +#else +#define UART_RX_BUFFER_SIZE 256 #endif #endif #ifndef UART_TX_BUFFER_SIZE -#if defined STM32F4 || defined STM32F7 //the F4 and F7 have enough memory, and the PX4 bootloader needs more then 128 -#define UART_TX_BUFFER_SIZE 256 -#else +// Only for the STM32F1 less buffer +#if defined(STM32F1) #define UART_TX_BUFFER_SIZE 128 +#else +#define UART_TX_BUFFER_SIZE 256 #endif #endif diff --git a/sw/airborne/modules/imu/imu_navstik.c b/sw/airborne/modules/imu/imu_navstik.c deleted file mode 100644 index 9e2b857b50..0000000000 --- a/sw/airborne/modules/imu/imu_navstik.c +++ /dev/null @@ -1,131 +0,0 @@ -/* - * Copyright (C) 2014 Freek van Tienen - * - * 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 modules/imu/imu_navstik.c - * Driver for the Navstik magnetometer, accelerometer and gyroscope - */ - -#include "modules/imu/imu.h" -#include "modules/core/abi.h" -#include "mcu_periph/i2c.h" - - -/* defaults suitable for Navstik */ -#ifndef NAVSTIK_MAG_I2C_DEV -#define NAVSTIK_MAG_I2C_DEV i2c3 -#endif -PRINT_CONFIG_VAR(NAVSTIK_MAG_I2C_DEV) - -#ifndef NAVSTIK_MPU_I2C_DEV -#define NAVSTIK_MPU_I2C_DEV i2c1 -#endif -PRINT_CONFIG_VAR(NAVSTIK_MPU_I2C_DEV) - -#if !defined NAVSTIK_LOWPASS_FILTER && !defined NAVSTIK_SMPLRT_DIV -#if (PERIODIC_FREQUENCY == 60) || (PERIODIC_FREQUENCY == 120) -/* Accelerometer: Bandwidth 44Hz, Delay 4.9ms - * Gyroscope: Bandwidth 42Hz, Delay 4.8ms sampling 1kHz - */ -#define NAVSTIK_LOWPASS_FILTER MPU60X0_DLPF_42HZ -#define NAVSTIK_SMPLRT_DIV 9 -PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") -#elif PERIODIC_FREQUENCY == 512 -/* Accelerometer: Bandwidth 260Hz, Delay 0ms - * Gyroscope: Bandwidth 256Hz, Delay 0.98ms sampling 8kHz - */ -#define NAVSTIK_LOWPASS_FILTER MPU60X0_DLPF_256HZ -#define NAVSTIK_SMPLRT_DIV 3 -PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") -#endif -#endif -PRINT_CONFIG_VAR(NAVSTIK_SMPLRT_DIV) -PRINT_CONFIG_VAR(NAVSTIK_LOWPASS_FILTER) - -PRINT_CONFIG_VAR(NAVSTIK_GYRO_RANGE) -PRINT_CONFIG_VAR(NAVSTIK_ACCEL_RANGE) - -/** Basic Navstik IMU data */ -struct ImuNavstik imu_navstik; - -/** - * Navstik IMU initializtion of the MPU-60x0 and HMC58xx - */ -void imu_navstik_init(void) -{ - /* MPU-60X0 */ - mpu60x0_i2c_init(&imu_navstik.mpu, &(NAVSTIK_MPU_I2C_DEV), MPU60X0_ADDR_ALT); - imu_navstik.mpu.config.smplrt_div = NAVSTIK_SMPLRT_DIV; - imu_navstik.mpu.config.dlpf_cfg = NAVSTIK_LOWPASS_FILTER; - imu_navstik.mpu.config.gyro_range = NAVSTIK_GYRO_RANGE; - imu_navstik.mpu.config.accel_range = NAVSTIK_ACCEL_RANGE; - - /* HMC58XX */ - hmc58xx_init(&imu_navstik.hmc, &(NAVSTIK_MAG_I2C_DEV), HMC58XX_ADDR); -} - -/** - * Handle all the periodic tasks of the Navstik IMU components. - * Read the MPU60x0 every periodic call and the HMC58XX every 10th call. - */ -void imu_navstik_periodic(void) -{ - // Start reading the latest gyroscope data - mpu60x0_i2c_periodic(&imu_navstik.mpu); - - // Read HMC58XX at 50Hz (main loop for rotorcraft: 512Hz) - RunOnceEvery(10, hmc58xx_periodic(&imu_navstik.hmc)); -} - -/** - * Handle all the events of the Navstik IMU components. - * When there is data available convert it to the correct axis and save it in the imu structure. - */ -void imu_navstik_event(void) -{ - uint32_t now_ts = get_sys_time_usec(); - - /* MPU-60x0 event taks */ - mpu60x0_i2c_event(&imu_navstik.mpu); - - if (imu_navstik.mpu.data_available) { - /* default orientation as should be printed on the pcb, z-down, ICs down */ - RATES_COPY(imu.gyro_unscaled, imu_navstik.mpu.data_rates.rates); - VECT3_COPY(imu.accel_unscaled, imu_navstik.mpu.data_accel.vect); - - imu_navstik.mpu.data_available = false; - imu_scale_gyro(&imu); - imu_scale_accel(&imu); - AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); - AbiSendMsgIMU_ACCEL_INT32(IMU_BOARD_ID, now_ts, &imu.accel); - } - - /* HMC58XX event task */ - hmc58xx_event(&imu_navstik.hmc); - if (imu_navstik.hmc.data_available) { - imu.mag_unscaled.x = imu_navstik.hmc.data.vect.y; - imu.mag_unscaled.y = -imu_navstik.hmc.data.vect.x; - imu.mag_unscaled.z = imu_navstik.hmc.data.vect.z; - imu_navstik.hmc.data_available = false; - imu_scale_mag(&imu); - AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); - } -} diff --git a/sw/airborne/modules/imu/imu_navstik.h b/sw/airborne/modules/imu/imu_navstik.h deleted file mode 100644 index b466133cde..0000000000 --- a/sw/airborne/modules/imu/imu_navstik.h +++ /dev/null @@ -1,83 +0,0 @@ -/* - * Copyright (C) 2014 Freek van Tienen - * - * 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 modules/imu/imu_navstik.h - * Interface for the Navstik magnetometer, accelerometer and gyroscope - */ - - -#ifndef IMU_NAVSTIK_H -#define IMU_NAVSTIK_H - -#include "generated/airframe.h" -#include "modules/imu/imu.h" - -#include "peripherals/hmc58xx.h" -#include "peripherals/mpu60x0_i2c.h" - -#ifndef NAVSTIK_GYRO_RANGE -#define NAVSTIK_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif - -#ifndef NAVSTIK_ACCEL_RANGE -#define NAVSTIK_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif - -// Set default sensitivity based on range if needed -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] -#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] -#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] -#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] -#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] -#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] -#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] -#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] -#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] -#endif - -// Set default sensitivity based on range if needed -#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] -#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] -#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] -#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] -#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] -#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] -#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] -#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] -#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] -#endif - - -struct ImuNavstik { - struct Mpu60x0_I2c mpu; - struct Hmc58xx hmc; -}; - -extern struct ImuNavstik imu_navstik; - -extern void imu_navstik_init(void); -extern void imu_navstik_periodic(void); -extern void imu_navstik_event(void); - -#endif /* IMU_NAVSTIK_H */ diff --git a/sw/airborne/modules/loggers/sdlog_chibios.c b/sw/airborne/modules/loggers/sdlog_chibios.c index d92524b598..3f83d814d6 100644 --- a/sw/airborne/modules/loggers/sdlog_chibios.c +++ b/sw/airborne/modules/loggers/sdlog_chibios.c @@ -246,16 +246,16 @@ static void thd_startlog(void *arg) } else { removeEmptyLogs(PPRZ_LOG_DIR, PPRZ_LOG_NAME, 50); if (sdLogOpenLog(&pprzLogFile, PPRZ_LOG_DIR, - PPRZ_LOG_NAME, SDLOG_AUTO_FLUSH_PERIOD, LOG_APPEND_TAG_AT_CLOSE_DISABLED, - SDLOG_CONTIGUOUS_STORAGE_MEM, LOG_PREALLOCATION_DISABLED, tmpFilename, sizeof(tmpFilename)) != SDLOG_OK) { + PPRZ_LOG_NAME, SDLOG_AUTO_FLUSH_PERIOD, LOG_APPEND_TAG_AT_CLOSE_DISABLED, + SDLOG_CONTIGUOUS_STORAGE_MEM, LOG_PREALLOCATION_DISABLED, tmpFilename, sizeof(tmpFilename)) != SDLOG_OK) { sdOk = false; } chsnprintf(chibios_sdlog_filenames, sizeof(chibios_sdlog_filenames), "%s", tmpFilename); #if FLIGHTRECORDER_SDLOG removeEmptyLogs(FR_LOG_DIR, FLIGHTRECORDER_LOG_NAME, 50); if (sdLogOpenLog(&flightRecorderLogFile, FR_LOG_DIR, FLIGHTRECORDER_LOG_NAME, - SDLOG_AUTO_FLUSH_PERIOD, LOG_APPEND_TAG_AT_CLOSE_DISABLED, - SDLOG_CONTIGUOUS_STORAGE_MEM, LOG_PREALLOCATION_DISABLED, tmpFilename, sizeof(tmpFilename)) != SDLOG_OK) { + SDLOG_AUTO_FLUSH_PERIOD, LOG_APPEND_TAG_AT_CLOSE_DISABLED, + SDLOG_CONTIGUOUS_STORAGE_MEM, LOG_PREALLOCATION_DISABLED, tmpFilename, sizeof(tmpFilename)) != SDLOG_OK) { sdOk = false; } chsnprintf(chibios_sdlog_filenames, sizeof(chibios_sdlog_filenames), "%s,%s", chibios_sdlog_filenames, tmpFilename); @@ -326,8 +326,9 @@ static void thd_bat_survey(void *arg) chThdExit(0); // Only put to deep sleep in case there is no power on the USB - if(palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) + if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) { mcu_deep_sleep(); + } chThdSleep(TIME_INFINITE); while (true); // never goes here, only to avoid compiler warning: 'noreturn' function does return } diff --git a/sw/airborne/modules/loggers/sdlog_chibios/sdLog.c b/sw/airborne/modules/loggers/sdlog_chibios/sdLog.c index 9b1a910bdd..78c8241e01 100644 --- a/sw/airborne/modules/loggers/sdlog_chibios/sdLog.c +++ b/sw/airborne/modules/loggers/sdlog_chibios/sdLog.c @@ -35,9 +35,6 @@ #include "mcu_periph/sdio.h" #include -#define likely(x) __builtin_expect(!!(x), 1) -#define unlikely(x) __builtin_expect(!!(x), 0) - #ifndef MIN #define MIN(x , y) (((x) < (y)) ? (x) : (y)) #endif diff --git a/sw/ext/Makefile b/sw/ext/Makefile index eae05d9973..7e1ff5b9c5 100644 --- a/sw/ext/Makefile +++ b/sw/ext/Makefile @@ -47,6 +47,12 @@ update_submodules: cd $(PAPARAZZI_SRC) && git submodule update --init --recursive sw/ext/$*; \ fi +# sync a specific submodule +%.sync: + $(Q)if [ -d $(PAPARAZZI_SRC)/.git ]; then \ + cd $(PAPARAZZI_SRC) && git submodule sync --recursive sw/ext/$*; \ + fi + # only build currentl checkout of libopencm3 libopencm3.build: $(Q)$(MAKE) -C libopencm3 lib PREFIX=$(PREFIX) TARGETS="stm32/f1" @@ -71,11 +77,11 @@ key_generator: key_generator.update rustlink: rustlink.update -chibios: chibios.update +chibios: chibios.sync chibios.update TRICAL: TRICAL.update -fatfs: fatfs.update +fatfs: fatfs.sync fatfs.update ecl: ecl.update diff --git a/sw/ext/chibios b/sw/ext/chibios index eb5c5ba204..b0ee54fbe8 160000 --- a/sw/ext/chibios +++ b/sw/ext/chibios @@ -1 +1 @@ -Subproject commit eb5c5ba204cc1cb64ff7789748393b74c49aa009 +Subproject commit b0ee54fbe808a570d02f36baa33d5c446806b628 diff --git a/sw/ext/fatfs b/sw/ext/fatfs index af1d02f312..ed7d2c5da0 160000 --- a/sw/ext/fatfs +++ b/sw/ext/fatfs @@ -1 +1 @@ -Subproject commit af1d02f3123f715217ccf9833d7cc2a6a72f8f7d +Subproject commit ed7d2c5da0e906a1410e6680a052c85f0723f51e diff --git a/sw/tools/flash_scripts/bmp_swd_flash.scr b/sw/tools/flash_scripts/bmp_swd_flash.scr index b7da5de76e..6d910ec08f 100644 --- a/sw/tools/flash_scripts/bmp_swd_flash.scr +++ b/sw/tools/flash_scripts/bmp_swd_flash.scr @@ -1,5 +1,7 @@ # Print BMPM version monitor version +# Set higher timeout for large compare-sections +set remotetimeout 30 # To make sure the target is not in a "strange" mode we tell BMPM to reset the # target using the reset pin. mon connect_srst enable diff --git a/sw/tools/flash_scripts/bmp_swd_nopwr_flash.scr b/sw/tools/flash_scripts/bmp_swd_nopwr_flash.scr index 93de7ba563..f1e782672f 100644 --- a/sw/tools/flash_scripts/bmp_swd_nopwr_flash.scr +++ b/sw/tools/flash_scripts/bmp_swd_nopwr_flash.scr @@ -1,5 +1,7 @@ # Print BMPM version monitor version +# Set higher timeout for large compare-sections +set remotetimeout 30 # To make sure the target is not in a "strange" mode we tell BMPM to reset the # target using the reset pin. mon connect_srst enable diff --git a/sw/tools/px4/cube_orange.prototype b/sw/tools/px4/cube_orange.prototype new file mode 100644 index 0000000000..a4544b1d06 --- /dev/null +++ b/sw/tools/px4/cube_orange.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 140, + "magic": "PX4FWv1", + "description": "Firmware for the CubePilot CubeOrange board", + "image": "", + "build_time": 0, + "summary": "CubeOrange", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} \ No newline at end of file diff --git a/sw/tools/px4/px4fmu_5.0.prototype b/sw/tools/px4/px4fmu_5.0.prototype new file mode 100644 index 0000000000..0acd17ea06 --- /dev/null +++ b/sw/tools/px4/px4fmu_5.0.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 50, + "magic": "PX4FWv1", + "description": "Firmware for the PX4FMUv5 board", + "image": "", + "build_time": 0, + "summary": "PX4FMUv5", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2064384, + "git_identity": "", + "board_revision": 0 +} \ No newline at end of file diff --git a/sw/tools/px4/set_target.py b/sw/tools/px4/set_target.py index 01f425eac5..ef57bf4379 100755 --- a/sw/tools/px4/set_target.py +++ b/sw/tools/px4/set_target.py @@ -58,11 +58,14 @@ if mode == 1: if mode == -1: # no pprz cdc was found, look for PX4 ports = glob.glob("/dev/serial/by-id/usb-3D_Robotics*") ports.append(glob.glob("/dev/serial/by-id/pci-3D_Robotics*")) + ports.append(glob.glob("/dev/serial/by-id/usb-Hex_ProfiCNC_Cube*")) for p in ports: - if len(p) > 0: + port = p + if isinstance(p, list) and len(port) > 0: + port = p[0] + if len(port) > 0: try: - ser = serial.Serial(p, timeout=0.5) - port = p + ser = serial.Serial(port, timeout=0.5) mode = 2 print("Original PX4 firmware CDC device found at port: " + port) except serial.serialutil.SerialException: