From 2a6ad556f183875fa9fb8072d774beec7ba55701 Mon Sep 17 00:00:00 2001 From: kevindehecker Date: Fri, 6 Oct 2017 15:53:18 +0200 Subject: [PATCH] F3 and X-Vert support (#2113) * Make mpu9250 compatible with mpu6500, by providing option to disable mag * Upgrade QTC version, add more QTCreator compatibility with chibios * F3 support * Add priliminary support stm32f3 discovery board using chibios * Add support for the stm32f37 xvert board by means of chibios * Give INDI simple full control authority * Motor driver for the vertx * Create define out of required THD_WORKING_AREA space --- .gitignore | 2 +- Makefile.ac | 13 +- conf/airframes/TUDELFT/tudelft_conf.xml | 11 + conf/airframes/TUDELFT/tudelft_xvert.xml | 226 +++ .../stm32f3_discovery_1.0_chibios.makefile | 76 + conf/boards/xvert_1.0.makefile | 71 + .../subsystems/shared/baro_board.makefile | 9 + conf/modules/actuators_xvert.xml | 25 + conf/modules/stabilization_indi_simple.xml | 1 + .../arch/chibios/mcu_periph/adc_arch.c | 39 +- .../arch/chibios/mcu_periph/gpio_arch.c | 4 +- .../arch/chibios/mcu_periph/i2c_arch.c | 67 +- .../arch/chibios/mcu_periph/ram_arch.h | 11 +- .../arch/chibios/mcu_periph/spi_arch.c | 23 +- .../arch/chibios/mcu_periph/uart_arch.c | 101 +- .../subsystems/actuators/actuators_xvert.c | 130 ++ .../subsystems/actuators/actuators_xvert.h | 61 + .../stm32f3_discovery/chibios/v1.0/board.c | 153 ++ .../stm32f3_discovery/chibios/v1.0/board.h | 1628 +++++++++++++++++ .../stm32f3_discovery/chibios/v1.0/board.mk | 20 + .../stm32f3_discovery/chibios/v1.0/mcuconf.h | 301 +++ sw/airborne/boards/xvert/baro_board.h | 20 + sw/airborne/boards/xvert/chibios/v1.0/board.c | 153 ++ sw/airborne/boards/xvert/chibios/v1.0/board.h | 1513 +++++++++++++++ .../boards/xvert/chibios/v1.0/board.mk | 20 + .../boards/xvert/chibios/v1.0/mcuconf.h | 270 +++ .../firmwares/rotorcraft/main_chibios.c | 6 +- .../stabilization/stabilization_indi_simple.c | 46 +- sw/airborne/math/pprz_trig_int.c | 12 +- sw/airborne/peripherals/mpu9250_i2c.c | 14 +- sw/airborne/peripherals/mpu9250_i2c.h | 6 + sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c | 4 +- sw/airborne/subsystems/imu/imu_mpu9250_i2c.c | 23 +- sw/tools/find_vpaths.py | 106 +- sw/tools/qt_project.py | 3 +- sw/tools/qtc.creator.user_template | 16 +- 36 files changed, 4981 insertions(+), 203 deletions(-) create mode 100644 conf/airframes/TUDELFT/tudelft_xvert.xml create mode 100644 conf/boards/stm32f3_discovery_1.0_chibios.makefile create mode 100644 conf/boards/xvert_1.0.makefile create mode 100644 conf/modules/actuators_xvert.xml create mode 100644 sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.c create mode 100644 sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.h create mode 100644 sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.c create mode 100644 sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.h create mode 100644 sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.mk create mode 100644 sw/airborne/boards/stm32f3_discovery/chibios/v1.0/mcuconf.h create mode 100644 sw/airborne/boards/xvert/baro_board.h create mode 100644 sw/airborne/boards/xvert/chibios/v1.0/board.c create mode 100644 sw/airborne/boards/xvert/chibios/v1.0/board.h create mode 100644 sw/airborne/boards/xvert/chibios/v1.0/board.mk create mode 100644 sw/airborne/boards/xvert/chibios/v1.0/mcuconf.h diff --git a/.gitignore b/.gitignore index 4883fb4ead..7a4d56bd4e 100644 --- a/.gitignore +++ b/.gitignore @@ -42,7 +42,7 @@ paparazzi.sublime-workspace # QtCreator IDE *.creator -*.creator.user +*.creator.user* *.config *.files *.includes diff --git a/Makefile.ac b/Makefile.ac index 82e9328f94..d2bf035292 100644 --- a/Makefile.ac +++ b/Makefile.ac @@ -56,6 +56,7 @@ RADIO_H=$(AC_GENERATED)/radio.h FLIGHT_PLAN_H=$(AC_GENERATED)/flight_plan.h FLIGHT_PLAN_XML=$(AIRCRAFT_BUILD_DIR)/flight_plan.xml SRCS_LIST=$(AIRCRAFT_BUILD_DIR)/$(TARGET)_srcs.list +TMP_LIST=$(AIRCRAFT_BUILD_DIR)/$(TARGET)_tmp.list SETTINGS_H=$(AC_GENERATED)/settings.h SETTINGS_XMLS=$(patsubst %,$(CONF)/%,$(SETTINGS)) SETTINGS_XMLS_DEP=$(filter-out %~,$(SETTINGS_XMLS)) @@ -155,14 +156,20 @@ all_ac_h: $(SRCS_LIST) qt_project $(SRCS_LIST) : $(CONF_XML) $(AIRFRAME_H) $(MODULES_H) autopilot_h $(SETTINGS_H) $(MAKEFILE_AC) $(PERIODIC_H) @echo "TARGET: " $(TARGET) > $(SRCS_LIST) - @echo "CFLAGS: " $(CFLAGS) >> $(SRCS_LIST) + @echo "CFLAGS: " $(CFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST) @echo "LDFLAGS: " $($(TARGET).LDFLAGS) >> $(SRCS_LIST) @echo "srcs: " $($(TARGET).srcs) >> $(SRCS_LIST) @echo -n "headers: " >> $(SRCS_LIST) + @echo $(VPATH) > $(TMP_LIST) + @echo $($(TARGET).srcs) >> $(TMP_LIST) + @echo $(CFLAGS) >> $(TMP_LIST) + @echo $(IINCDIR) >> $(TMP_LIST) + @echo $(TOPT)>> $(TMP_LIST) + @echo ../../sw/tools/find_vpaths.py $(CC) $(TMP_LIST) $(PAPARAZZI_SRC) ifeq (,$(findstring cpp,$($(TARGET).srcs))) - $(Q)cd $(AIRBORNE) ; ../../sw/tools/find_vpaths.py $(CC) $(VPATH) + $($(TARGET).srcs) + $(CFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST) + $(Q)cd $(PAPARAZZI_SRC) ; ./sw/tools/find_vpaths.py $(CC) $(TMP_LIST) $(PAPARAZZI_SRC) >> $(SRCS_LIST) else - $(Q)cd $(AIRBORNE) ; ../../sw/tools/find_vpaths.py $(CXX) $(VPATH) + $($(TARGET).srcs) + $(CXXFLAGS) $(IINCDIR) $(TOPT) >> $(SRCS_LIST) + $(Q)cd $(PAPARAZZI_SRC) ; ./sw/tools/find_vpaths.py $(CXX) $(TMP_LIST) $(PAPARAZZI_SRC) >> $(SRCS_LIST) endif qt_project : $(SRCS_LIST) diff --git a/conf/airframes/TUDELFT/tudelft_conf.xml b/conf/airframes/TUDELFT/tudelft_conf.xml index 7b6f1ed42f..92b4f4cda2 100644 --- a/conf/airframes/TUDELFT/tudelft_conf.xml +++ b/conf/airframes/TUDELFT/tudelft_conf.xml @@ -527,4 +527,15 @@ settings_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml" gui_color="#b29eb22cffff" /> + diff --git a/conf/airframes/TUDELFT/tudelft_xvert.xml b/conf/airframes/TUDELFT/tudelft_xvert.xml new file mode 100644 index 0000000000..c32e92eba9 --- /dev/null +++ b/conf/airframes/TUDELFT/tudelft_xvert.xml @@ -0,0 +1,226 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+ + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + + + +
+
+ + + + + + + + +
+
+ + +
+
+ + + + + +
+ +
+ + + + + +
+ +
+ + + + + + + + + +
+
diff --git a/conf/boards/stm32f3_discovery_1.0_chibios.makefile b/conf/boards/stm32f3_discovery_1.0_chibios.makefile new file mode 100644 index 0000000000..c04a4773d8 --- /dev/null +++ b/conf/boards/stm32f3_discovery_1.0_chibios.makefile @@ -0,0 +1,76 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# stm32f3_discovery_chibios.makefile +# +# + +BOARD=stm32f3_discovery +BOARD_VERSION=1.0 +BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION) +BOARD_CFG=\"boards/$(BOARD_DIR)/board.h\" + +ARCH=chibios +$(TARGET).ARCHDIR = $(ARCH) + +RTOS=chibios + +## FPU on F3 +USE_FPU=hard + +$(TARGET).CFLAGS += -DSTM32F3 -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 = STM32F3xx/platform.mk +CHIBIOS_BOARD_LINKER = STM32F303xC.ld +CHIBIOS_BOARD_STARTUP = startup_stm32f3xx.mk + +############################################################################## +# Compiler settings +# +MCU = cortex-m4 + + +# default flash mode is via DFU-UTIL +# possibilities: DFU-UTIL, SWD, STLINK +FLASH_MODE ?= DFU-UTIL + +HAS_LUFTBOOT = FALSE + +# +# default LED configuration +# +RADIO_CONTROL_LED ?= 4 +BARO_LED ?= none +AHRS_ALIGNER_LED ?= 5 +GPS_LED ?= 6 +SYS_TIME_LED ?= 3 + +# +# default UART configuration (modem, gps, spektrum) +# + +MODEM_PORT ?= UART1 +MODEM_BAUD ?= B57600 + +GPS_PORT ?= UART2 +GPS_BAUD ?= B38400 + +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART3 +SBUS_PORT ?= UART3 + + +# +# 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/xvert_1.0.makefile b/conf/boards/xvert_1.0.makefile new file mode 100644 index 0000000000..6f61208705 --- /dev/null +++ b/conf/boards/xvert_1.0.makefile @@ -0,0 +1,71 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# stm32f37_vortex_chibios.makefile +# +# + +BOARD=xvert +BOARD_VERSION=1.0 +BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION) +BOARD_CFG=\"boards/$(BOARD_DIR)/board.h\" + +ARCH=chibios +$(TARGET).ARCHDIR = $(ARCH) + +RTOS=chibios + +## FPU on F3 + +##TODO: there is some bug when using the hard FPU unit!! +USE_FPU=no + +$(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 = STM32F37x/platform.mk +CHIBIOS_BOARD_LINKER = STM32F373xC.ld +CHIBIOS_BOARD_STARTUP = startup_stm32f3xx.mk + +############################################################################## +# Compiler settings +# +MCU = cortex-m4 + + +# default flash mode is via DFU-UTIL +# possibilities: DFU-UTIL, SWD, SWD_NOPWR, STLINK +FLASH_MODE ?= SWD_NOPWR + +HAS_LUFTBOOT = FALSE + +# +# default LED configuration +# +SYS_TIME_LED ?= 1 +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= 2 +GPS_LED ?= none + +# +# default UART configuration (modem, gps, spektrum) +# + +MODEM_PORT ?= UART2 +MODEM_BAUD ?= B57600 + +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# e.g. +# +ACTUATORS ?= actuators_xvert diff --git a/conf/firmwares/subsystems/shared/baro_board.makefile b/conf/firmwares/subsystems/shared/baro_board.makefile index f48c2c6c92..6b8251a3c9 100644 --- a/conf/firmwares/subsystems/shared/baro_board.makefile +++ b/conf/firmwares/subsystems/shared/baro_board.makefile @@ -286,6 +286,15 @@ else ifeq ($(BOARD), chimera) BARO_BOARD_SRCS += peripherals/ms5611_i2c.c BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c +else ifeq ($(BOARD), xvert) + BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C + BARO_BOARD_CFLAGS += -DUSE_I2C2 + BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2 + BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_ADDR=MS5611_I2C_SLAVE_ADDR_ALT + BARO_BOARD_SRCS += peripherals/ms5611.c + BARO_BOARD_SRCS += peripherals/ms5611_i2c.c + BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c + else ifeq ($(BOARD), vms_ecu) BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_SPI include $(CFG_SHARED)/spi_master.makefile diff --git a/conf/modules/actuators_xvert.xml b/conf/modules/actuators_xvert.xml new file mode 100644 index 0000000000..5c29c32766 --- /dev/null +++ b/conf/modules/actuators_xvert.xml @@ -0,0 +1,25 @@ + + + + + + Actuators Driver for x-vert vtol escs + + + + +
+ +
+ + + + + + + + + + +
+ diff --git a/conf/modules/stabilization_indi_simple.xml b/conf/modules/stabilization_indi_simple.xml index 558b4ffc29..ea1429b1e4 100644 --- a/conf/modules/stabilization_indi_simple.xml +++ b/conf/modules/stabilization_indi_simple.xml @@ -44,6 +44,7 @@ + diff --git a/sw/airborne/arch/chibios/mcu_periph/adc_arch.c b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c index 3ead555d75..5ad9c742ca 100644 --- a/sw/airborne/arch/chibios/mcu_periph/adc_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/adc_arch.c @@ -75,6 +75,11 @@ // 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) +#define ADC_SAMPLE_RATE ADC_SMPR_SMP_601P5 #endif @@ -246,7 +251,7 @@ void adc1callback(ADCDriver *adcp, adcsample_t *buffer, size_t n) (adc_watchdog.cb != NULL)) { if (adc1_buffers[adc_watchdog.channel]->sum < (adc1_buffers[adc_watchdog.channel]->av_nb_sample * adc_watchdog.vmin)) { - adc_watchdog.cb (); + adc_watchdog.cb(); } } #endif // USE_ADC_WATCHDOG @@ -276,7 +281,7 @@ static void adcerrorcallback(ADCDriver *adcp, adcerror_t err) void adc_buf_channel(uint8_t adc_channel, struct adc_buf *s, uint8_t av_nb_sample) { // check for out-of-bounds access - if (adc_channel >= ADC_NUM_CHANNELS) return; + if (adc_channel >= ADC_NUM_CHANNELS) { return; } adc1_buffers[adc_channel] = s; if (av_nb_sample <= MAX_AV_NB_SAMPLE) { s->av_nb_sample = av_nb_sample; @@ -344,25 +349,45 @@ void adc_init(void) uint32_t smpr1, smpr2; adc_sample_time_on_all_channels(&smpr1, &smpr2, ADC_SAMPLE_RATE); - adcgrpcfg.cr2 = ADC_CR2_CFG; - #if USE_ADC_WATCHDOG adc_watchdog.adc = NULL; adc_watchdog.cb = NULL; adc_watchdog.channel = 0; - adc_watchdog.vmin = (1<<12)-1; // max adc + 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 // Start ADC in continious conversion mode adcStart(&ADCD1, NULL); @@ -371,9 +396,9 @@ void adc_init(void) #if USE_ADC_WATCHDOG void register_adc_watchdog(ADCDriver *adc, adc_channels_num_t channel, adcsample_t vmin, - adc_watchdog_callback cb) + adc_watchdog_callback cb) { - for (int i=0; i< NB_ADC1_CHANNELS; i++) { // FIXME when more than ADC1 will be in use + for (int i = 0; i < NB_ADC1_CHANNELS; i++) { // FIXME when more than ADC1 will be in use if (adc_channel_map[i] == channel) { adc_watchdog.adc = adc; adc_watchdog.channel = i; diff --git a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c index a81ad503d4..1c2f0a1ec4 100644 --- a/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/gpio_arch.c @@ -68,8 +68,8 @@ void gpio_setup_pin_af(ioportid_t port, uint16_t pin, uint8_t af, bool is_output (void)pin; (void)af; (void)is_output; -#elif defined(STM32F4) || defined(STM32F7) -// STM32F4xx and STM32F7xx +#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F7) +// STM32F4xx, STM32F3xx and STM32F7xx 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 2a7426c83e..c70af8f3a9 100644 --- a/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/i2c_arch.c @@ -57,7 +57,7 @@ struct i2c_init { static void handle_i2c_thd(struct i2c_periph *p); // Timeout for I2C transaction -static const systime_t tmo = US2ST(1000000/PERIODIC_FREQUENCY); +static const systime_t tmo = US2ST(10000000 / PERIODIC_FREQUENCY); /** * main thread function @@ -69,7 +69,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; @@ -86,38 +86,38 @@ static void handle_i2c_thd(struct i2c_periph *p) if (t->len_w > 0) { #if defined STM32F7 // 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)); + memcpy(i->dma_buf, (void *)t->buf, (size_t)(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); - memcpy((void*)t->buf, i->dma_buf, (size_t)(t->len_r)); + (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); + memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r)); #else status = i2cMasterTransmitTimeout( - (I2CDriver*)p->reg_addr, - (i2caddr_t)((t->slave_addr)>>1), - (uint8_t*)t->buf, (size_t)(t->len_w), - (uint8_t*)t->buf, (size_t)(t->len_r), - tmo); + (I2CDriver *)p->reg_addr, + (i2caddr_t)((t->slave_addr) >> 1), + (uint8_t *)t->buf, (size_t)(t->len_w), + (uint8_t *)t->buf, (size_t)(t->len_r), + tmo); #endif } else { #if defined STM32F7 // 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)); + memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w)); status = i2cMasterReceiveTimeout( - (I2CDriver*)p->reg_addr, - (i2caddr_t)((t->slave_addr)>>1), - (uint8_t*)i->dma_buf, (size_t)(t->len_r), - tmo); - memcpy((void*)t->buf, i->dma_buf, (size_t)(t->len_r)); + (I2CDriver *)p->reg_addr, + (i2caddr_t)((t->slave_addr) >> 1), + (uint8_t *)i->dma_buf, (size_t)(t->len_r), + tmo); + memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r)); #else status = i2cMasterReceiveTimeout( - (I2CDriver*)p->reg_addr, - (i2caddr_t)((t->slave_addr)>>1), - (uint8_t*)t->buf, (size_t)(t->len_r), - tmo); + (I2CDriver *)p->reg_addr, + (i2caddr_t)((t->slave_addr) >> 1), + (uint8_t *)t->buf, (size_t)(t->len_r), + tmo); #endif } @@ -140,13 +140,13 @@ 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 //be retrieved using @p i2cGetErrors(). t->status = I2CTransFailed; - i2cflags_t errors = i2cGetErrors((I2CDriver*)p->reg_addr); + i2cflags_t errors = i2cGetErrors((I2CDriver *)p->reg_addr); if (errors & I2C_BUS_ERROR) { p->errors->miss_start_stop_cnt++; } @@ -198,7 +198,7 @@ static struct i2c_init i2c1_init_s = { struct i2c_errors i2c1_errors; // Thread static __attribute__((noreturn)) void thd_i2c1(void *arg); -static THD_WORKING_AREA(wa_thd_i2c1, 1024); +static THD_WORKING_AREA(wa_thd_i2c1, 128); /* * I2C1 init @@ -211,7 +211,7 @@ void i2c1_hw_init(void) i2c1.init_struct = &i2c1_init_s; // Create thread chThdCreateStatic(wa_thd_i2c1, sizeof(wa_thd_i2c1), - NORMALPRIO+1, thd_i2c1, NULL); + NORMALPRIO + 1, thd_i2c1, NULL); } /* @@ -252,7 +252,7 @@ static struct i2c_init i2c2_init_s = { struct i2c_errors i2c2_errors; // Thread static __attribute__((noreturn)) void thd_i2c2(void *arg); -static THD_WORKING_AREA(wa_thd_i2c2, 1024); +static THD_WORKING_AREA(wa_thd_i2c2, 128); /* * I2C2 init @@ -261,12 +261,11 @@ void i2c2_hw_init(void) { i2cStart(&I2CD2, &i2cfg2); i2c2.reg_addr = &I2CD2; - i2c2.init_struct = NULL; i2c2.errors = &i2c2_errors; i2c2.init_struct = &i2c2_init_s; // Create thread chThdCreateStatic(wa_thd_i2c2, sizeof(wa_thd_i2c2), - NORMALPRIO+1, thd_i2c2, NULL); + NORMALPRIO + 1, thd_i2c2, NULL); } /* @@ -307,7 +306,7 @@ static struct i2c_init i2c3_init_s = { struct i2c_errors i2c3_errors; // Thread static __attribute__((noreturn)) void thd_i2c3(void *arg); -static THD_WORKING_AREA(wa_thd_i2c3, 1024); +static THD_WORKING_AREA(wa_thd_i2c3, 128); /* * I2C3 init @@ -321,7 +320,7 @@ void i2c3_hw_init(void) i2c3.init_struct = &i2c3_init_s; // Create thread chThdCreateStatic(wa_thd_i2c3, sizeof(wa_thd_i2c3), - NORMALPRIO+1, thd_i2c3, NULL); + NORMALPRIO + 1, thd_i2c3, NULL); } /* @@ -395,7 +394,7 @@ bool i2c_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 f3dc976c5d..14bce33ae9 100644 --- a/sw/airborne/arch/chibios/mcu_periph/ram_arch.h +++ b/sw/airborne/arch/chibios/mcu_periph/ram_arch.h @@ -26,6 +26,11 @@ * F1 * ram0: 64ko std * + * F3 + * ram4: 8ko ccm, fast, no dma + * ram0: 40Ko std + * F37 + * ram0: 32Ko std * F4 * ram4: 64ko ccm, fast, no dma * ram0: 128Ko std @@ -42,6 +47,10 @@ #define STD_SECTION ".ram0" #define FAST_SECTION ".ram0" #define DMA_SECTION ".ram0" +#elif defined STM32F3 +#define STD_SECTION ".ram0" +#define FAST_SECTION ".ram4" +#define DMA_SECTION ".ram0" #elif defined STM32F4 #define STD_SECTION ".ram0" #define FAST_SECTION ".ram4" @@ -57,7 +66,7 @@ #define IN_STD_SECTION_NOINIT(var) var __attribute__ ((section(STD_SECTION), aligned(8))) #define IN_STD_SECTION_CLEAR(var) var __attribute__ ((section(STD_SECTION "_clear"), aligned(8))) #define IN_STD_SECTION(var) var __attribute__ ((section(STD_SECTION "_init"), aligned(8))) - + #define IN_FAST_SECTION_NOINIT(var) var __attribute__ ((section(FAST_SECTION), aligned(8))) #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))) diff --git a/sw/airborne/arch/chibios/mcu_periph/spi_arch.c b/sw/airborne/arch/chibios/mcu_periph/spi_arch.c index 9428052300..95e3832f22 100644 --- a/sw/airborne/arch/chibios/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/spi_arch.c @@ -224,8 +224,7 @@ static inline uint16_t spi_resolve_CR2(struct spi_transaction *t __attribute__(( #if defined(STM32F7) if (t->dss == SPIDss16bit) { CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2 | SPI_CR2_DS_3; - } - else { + } else { CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2; } #endif /* STM32F7 */ @@ -242,7 +241,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; @@ -284,11 +283,11 @@ 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 - memcpy(i->dma_buf_out, (void*)t->output_buf, (size_t)t->output_length); + memcpy(i->dma_buf_out, (void *)t->output_buf, (size_t)t->output_length); spiExchange((SPIDriver *)p->reg_addr, t_length, i->dma_buf_out, i->dma_buf_in); - memcpy((void*)t->input_buf, i->dma_buf_in, (size_t)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); + spiExchange((SPIDriver *)p->reg_addr, t_length, (uint8_t *)t->output_buf, (uint8_t *)t->input_buf); #endif // Unselect the slave @@ -347,7 +346,7 @@ static __attribute__((noreturn)) void thd_spi1(void *arg) } } -static THD_WORKING_AREA(wa_thd_spi1, 1024); +static THD_WORKING_AREA(wa_thd_spi1, 256); void spi1_arch_init(void) { @@ -355,7 +354,7 @@ void spi1_arch_init(void) spi1.init_struct = &spi1_init_s; // Create thread chThdCreateStatic(wa_thd_spi1, sizeof(wa_thd_spi1), - NORMALPRIO+1, thd_spi1, NULL); + NORMALPRIO + 1, thd_spi1, NULL); } #endif @@ -386,7 +385,7 @@ static __attribute__((noreturn)) void thd_spi2(void *arg) } } -static THD_WORKING_AREA(wa_thd_spi2, 1024); +static THD_WORKING_AREA(wa_thd_spi2, 256); void spi2_arch_init(void) { @@ -394,7 +393,7 @@ void spi2_arch_init(void) spi2.init_struct = &spi2_init_s; // Create thread chThdCreateStatic(wa_thd_spi2, sizeof(wa_thd_spi2), - NORMALPRIO+1, thd_spi2, NULL); + NORMALPRIO + 1, thd_spi2, NULL); } #endif @@ -433,7 +432,7 @@ void spi3_arch_init(void) spi3.init_struct = &spi3_init_s; // Create thread chThdCreateStatic(wa_thd_spi3, sizeof(wa_thd_spi3), - NORMALPRIO+1, thd_spi3, NULL); + NORMALPRIO + 1, thd_spi3, NULL); } #endif @@ -477,7 +476,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; } diff --git a/sw/airborne/arch/chibios/mcu_periph/uart_arch.c b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c index 239b4c73ba..f655ed44be 100644 --- a/sw/airborne/arch/chibios/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/chibios/mcu_periph/uart_arch.c @@ -54,9 +54,9 @@ struct SerialInit { static void handle_uart_rx(struct uart_periph *p) { // wait for next incoming byte - uint8_t c = sdGet((SerialDriver*)(p->reg_addr)); + uint8_t c = sdGet((SerialDriver *)(p->reg_addr)); - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); chMtxLock(init_struct->rx_mtx); uint16_t temp = (p->rx_insert_idx + 1) % UART_RX_BUFFER_SIZE;; // insert new byte @@ -75,8 +75,8 @@ static void handle_uart_rx(struct uart_periph *p) static void handle_uart_tx(struct uart_periph *p) { // check if more data to send - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); - chSemWait (init_struct->tx_sem); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); + chSemWait(init_struct->tx_sem); while (p->tx_insert_idx != p->tx_extract_idx) { uint8_t data = p->tx_buf[p->tx_extract_idx]; p->tx_running = true; @@ -128,7 +128,7 @@ static __attribute__((noreturn)) void thd_uart1_rx(void *arg) } } -static THD_WORKING_AREA(wa_thd_uart1_rx, 1024); +static THD_WORKING_AREA(wa_thd_uart1_rx, 256); #endif #if USE_UART1_TX @@ -144,7 +144,7 @@ static __attribute__((noreturn)) void thd_uart1_tx(void *arg) handle_uart_tx(&uart1); } } -static THD_WORKING_AREA(wa_thd_uart1_tx, 1024); +static THD_WORKING_AREA(wa_thd_uart1_tx, 256); #endif void uart1_init(void) @@ -170,13 +170,13 @@ void uart1_init(void) uart1_init_struct.rx_mtx = &uart1_rx_mtx; uart1_init_struct.rx_sem = &uart1_rx_sem; chThdCreateStatic(wa_thd_uart1_rx, sizeof(wa_thd_uart1_rx), - NORMALPRIO+1, thd_uart1_rx, NULL); + NORMALPRIO + 1, thd_uart1_rx, NULL); #endif #if USE_UART1_TX uart1_init_struct.tx_mtx = &uart1_tx_mtx; uart1_init_struct.tx_sem = &uart1_tx_sem; chThdCreateStatic(wa_thd_uart1_tx, sizeof(wa_thd_uart1_tx), - NORMALPRIO+1, thd_uart1_tx, NULL); + NORMALPRIO + 1, thd_uart1_tx, NULL); #endif } @@ -230,7 +230,7 @@ static __attribute__((noreturn)) void thd_uart2_rx(void *arg) } } -static THD_WORKING_AREA(wa_thd_uart2_rx, 1024); +static THD_WORKING_AREA(wa_thd_uart2_rx, 256); #endif #if USE_UART2_TX @@ -246,7 +246,7 @@ static __attribute__((noreturn)) void thd_uart2_tx(void *arg) handle_uart_tx(&uart2); } } -static THD_WORKING_AREA(wa_thd_uart2_tx, 1024); +static THD_WORKING_AREA(wa_thd_uart2_tx, 256); #endif void uart2_init(void) @@ -272,13 +272,13 @@ void uart2_init(void) uart2_init_struct.rx_mtx = &uart2_rx_mtx; uart2_init_struct.rx_sem = &uart2_rx_sem; chThdCreateStatic(wa_thd_uart2_rx, sizeof(wa_thd_uart2_rx), - NORMALPRIO, thd_uart2_rx, NULL); + NORMALPRIO, thd_uart2_rx, NULL); #endif #if USE_UART2_TX uart2_init_struct.tx_mtx = &uart2_tx_mtx; uart2_init_struct.tx_sem = &uart2_tx_sem; chThdCreateStatic(wa_thd_uart2_tx, sizeof(wa_thd_uart2_tx), - NORMALPRIO, thd_uart2_tx, NULL); + NORMALPRIO, thd_uart2_tx, NULL); #endif } @@ -322,7 +322,7 @@ static __attribute__((noreturn)) void thd_uart3_rx(void *arg) } } -static THD_WORKING_AREA(wa_thd_uart3_rx, 1024); +static THD_WORKING_AREA(wa_thd_uart3_rx, 256); #endif #if USE_UART3_TX @@ -338,7 +338,7 @@ static __attribute__((noreturn)) void thd_uart3_tx(void *arg) handle_uart_tx(&uart3); } } -static THD_WORKING_AREA(wa_thd_uart3_tx, 1024); +static THD_WORKING_AREA(wa_thd_uart3_tx, 256); #endif void uart3_init(void) @@ -364,13 +364,13 @@ void uart3_init(void) uart3_init_struct.rx_mtx = &uart3_rx_mtx; uart3_init_struct.rx_sem = &uart3_rx_sem; chThdCreateStatic(wa_thd_uart3_rx, sizeof(wa_thd_uart3_rx), - NORMALPRIO, thd_uart3_rx, NULL); + NORMALPRIO, thd_uart3_rx, NULL); #endif #if USE_UART3_TX uart3_init_struct.tx_mtx = &uart3_tx_mtx; uart3_init_struct.tx_sem = &uart3_tx_sem; chThdCreateStatic(wa_thd_uart3_tx, sizeof(wa_thd_uart3_tx), - NORMALPRIO, thd_uart3_tx, NULL); + NORMALPRIO, thd_uart3_tx, NULL); #endif } @@ -414,7 +414,7 @@ static __attribute__((noreturn)) void thd_uart4_rx(void *arg) } } -static THD_WORKING_AREA(wa_thd_uart4_rx, 1024); +static THD_WORKING_AREA(wa_thd_uart4_rx, 256); #endif #if USE_UART4_TX @@ -430,7 +430,7 @@ static __attribute__((noreturn)) void thd_uart4_tx(void *arg) handle_uart_tx(&uart4); } } -static THD_WORKING_AREA(wa_thd_uart4_tx, 1024); +static THD_WORKING_AREA(wa_thd_uart4_tx, 256); #endif void uart4_init(void) @@ -456,13 +456,13 @@ void uart4_init(void) uart4_init_struct.rx_mtx = &uart4_rx_mtx; uart4_init_struct.rx_sem = &uart4_rx_sem; chThdCreateStatic(wa_thd_uart4_rx, sizeof(wa_thd_uart4_rx), - NORMALPRIO, thd_uart4_rx, NULL); + NORMALPRIO, thd_uart4_rx, NULL); #endif #if USE_UART4_TX uart4_init_struct.tx_mtx = &uart4_tx_mtx; uart4_init_struct.tx_sem = &uart4_tx_sem; chThdCreateStatic(wa_thd_uart4_tx, sizeof(wa_thd_uart4_tx), - NORMALPRIO, thd_uart4_tx, NULL); + NORMALPRIO, thd_uart4_tx, NULL); #endif } @@ -506,7 +506,7 @@ static __attribute__((noreturn)) void thd_uart5_rx(void *arg) } } -static THD_WORKING_AREA(wa_thd_uart5_rx, 1024); +static THD_WORKING_AREA(wa_thd_uart5_rx, 256); #endif #if USE_UART5_TX @@ -522,7 +522,7 @@ static __attribute__((noreturn)) void thd_uart5_tx(void *arg) handle_uart_tx(&uart5); } } -static THD_WORKING_AREA(wa_thd_uart5_tx, 1024); +static THD_WORKING_AREA(wa_thd_uart5_tx, 256); #endif void uart5_init(void) @@ -548,13 +548,13 @@ void uart5_init(void) uart5_init_struct.rx_mtx = &uart5_rx_mtx; uart5_init_struct.rx_sem = &uart5_rx_sem; chThdCreateStatic(wa_thd_uart5_rx, sizeof(wa_thd_uart5_rx), - NORMALPRIO, thd_uart5_rx, NULL); + NORMALPRIO, thd_uart5_rx, NULL); #endif #if USE_UART5_TX uart5_init_struct.tx_mtx = &uart5_tx_mtx; uart5_init_struct.tx_sem = &uart5_tx_sem; chThdCreateStatic(wa_thd_uart5_tx, sizeof(wa_thd_uart5_tx), - NORMALPRIO, thd_uart5_tx, NULL); + NORMALPRIO, thd_uart5_tx, NULL); #endif } @@ -640,13 +640,13 @@ void uart6_init(void) uart6_init_struct.rx_mtx = &uart6_rx_mtx; uart6_init_struct.rx_sem = &uart6_rx_sem; chThdCreateStatic(wa_thd_uart6_rx, sizeof(wa_thd_uart6_rx), - NORMALPRIO, thd_uart6_rx, NULL); + NORMALPRIO, thd_uart6_rx, NULL); #endif #if USE_UART6_TX uart6_init_struct.tx_mtx = &uart6_tx_mtx; uart6_init_struct.tx_sem = &uart6_tx_sem; chThdCreateStatic(wa_thd_uart6_tx, sizeof(wa_thd_uart6_tx), - NORMALPRIO, thd_uart6_tx, NULL); + NORMALPRIO, thd_uart6_tx, NULL); #endif } @@ -732,13 +732,13 @@ void uart7_init(void) uart7_init_struct.rx_mtx = &uart7_rx_mtx; uart7_init_struct.rx_sem = &uart7_rx_sem; chThdCreateStatic(wa_thd_uart7_rx, sizeof(wa_thd_uart7_rx), - NORMALPRIO, thd_uart7_rx, NULL); + NORMALPRIO, thd_uart7_rx, NULL); #endif #if USE_UART7_TX uart7_init_struct.tx_mtx = &uart7_tx_mtx; uart7_init_struct.tx_sem = &uart7_tx_sem; chThdCreateStatic(wa_thd_uart7_tx, sizeof(wa_thd_uart7_tx), - NORMALPRIO, thd_uart7_tx, NULL); + NORMALPRIO, thd_uart7_tx, NULL); #endif } @@ -824,13 +824,13 @@ void uart8_init(void) uart8_init_struct.rx_mtx = &uart8_rx_mtx; uart8_init_struct.rx_sem = &uart8_rx_sem; chThdCreateStatic(wa_thd_uart8_rx, sizeof(wa_thd_uart8_rx), - NORMALPRIO, thd_uart8_rx, NULL); + NORMALPRIO, thd_uart8_rx, NULL); #endif #if USE_UART8_TX uart8_init_struct.tx_mtx = &uart8_tx_mtx; uart8_init_struct.tx_sem = &uart8_tx_sem; chThdCreateStatic(wa_thd_uart8_tx, sizeof(wa_thd_uart8_tx), - NORMALPRIO, thd_uart8_tx, NULL); + NORMALPRIO, thd_uart8_tx, NULL); #endif } @@ -842,7 +842,7 @@ uint8_t uart_getch(struct uart_periph *p) //to keep compatibility with loop oriented paparazzi architecture, read is not blocking //struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); //chSemWait (init_struct->rx_sem); - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); chMtxLock(init_struct->rx_mtx); uint8_t ret = p->rx_buf[p->rx_extract_idx]; p->rx_extract_idx = (p->rx_extract_idx + 1) % UART_RX_BUFFER_SIZE; @@ -853,16 +853,16 @@ uint8_t uart_getch(struct uart_periph *p) /** * Set baudrate */ -void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud ) +void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); SerialConfig *conf = init_struct->conf; // set new baudrate conf->speed = baud; p->baudrate = baud; // restart periph - sdStop((SerialDriver*)(p->reg_addr)); - sdStart((SerialDriver*)(p->reg_addr), conf); + sdStop((SerialDriver *)(p->reg_addr)); + sdStart((SerialDriver *)(p->reg_addr), conf); } /** @@ -873,7 +873,7 @@ void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx #if defined STM32F7 #define __USART_CR1_M USART_CR1_M_0 -#elif defined STM32F1 || defined STM32F4 +#elif defined STM32F1 || defined STM32F4 || defined STM32F3 #define __USART_CR1_M USART_CR1_M #else #error unsupported board @@ -885,7 +885,7 @@ void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx void uart_periph_set_bits_stop_parity(struct uart_periph *p, uint8_t bits, uint8_t stop, uint8_t parity) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); SerialConfig *conf = init_struct->conf; /* Configure USART parity and data bits */ @@ -917,8 +917,8 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p, conf-> cr2 |= USART_CR2_STOP1_BITS; // set bits for 1 stop } - sdStop((SerialDriver*)(p->reg_addr)); - sdStart((SerialDriver*)(p->reg_addr), conf); + sdStop((SerialDriver *)(p->reg_addr)); + sdStart((SerialDriver *)(p->reg_addr), conf); } #ifdef STM32F7 @@ -927,7 +927,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p, */ void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool invert_tx) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); SerialConfig *conf = init_struct->conf; if (invert_rx) { conf->cr2 |= USART_CR2_RXINV; // set rxinv bit @@ -939,8 +939,8 @@ void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool i } else { conf->cr2 &= ~USART_CR2_TXINV; // clear txinv bit } - sdStop((SerialDriver*)(p->reg_addr)); - sdStart((SerialDriver*)(p->reg_addr), conf); + sdStop((SerialDriver *)(p->reg_addr)); + sdStart((SerialDriver *)(p->reg_addr), conf); } #endif @@ -948,7 +948,7 @@ void uart_periph_invert_data_logic(struct uart_periph *p, bool invert_rx, bool i // and lock driver with mutex bool uart_check_free_space(struct uart_periph *p, long *fd, uint16_t len) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); int16_t space = p->tx_extract_idx - p->tx_insert_idx; if (space <= 0) { space += UART_TX_BUFFER_SIZE; @@ -966,7 +966,7 @@ bool uart_check_free_space(struct uart_periph *p, long *fd, uint16_t len) */ void uart_put_byte(struct uart_periph *p, long fd, uint8_t data) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); if (fd == 0) { // if fd is zero, assume the driver is not already locked chMtxLock(init_struct->tx_mtx); @@ -980,9 +980,8 @@ void uart_put_byte(struct uart_periph *p, long fd, uint8_t data) chMtxUnlock(init_struct->tx_mtx); // send signal to start transmission - chSemSignal (init_struct->tx_sem); - } - else { + chSemSignal(init_struct->tx_sem); + } else { // assume driver is locked and available space have been checked p->tx_buf[p->tx_insert_idx] = data; p->tx_insert_idx = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE; @@ -994,7 +993,7 @@ void uart_put_byte(struct uart_periph *p, long fd, uint8_t data) */ void uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16_t len) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); if (fd == 0) { // if fd is zero, assume the driver is not already locked // and available space should be checked @@ -1018,18 +1017,18 @@ void uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16 if (fd == 0) { chMtxUnlock(init_struct->tx_mtx); // send signal to start transmission - chSemSignal (init_struct->tx_sem); + chSemSignal(init_struct->tx_sem); } } void uart_send_message(struct uart_periph *p, long fd) { - struct SerialInit *init_struct = (struct SerialInit*)(p->init_struct); + struct SerialInit *init_struct = (struct SerialInit *)(p->init_struct); // unlock driver in case it is not done (fd > 0) if (fd != 0) { chMtxUnlock(init_struct->tx_mtx); } // send signal to start transmission - chSemSignal (init_struct->tx_sem); + chSemSignal(init_struct->tx_sem); } diff --git a/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.c b/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.c new file mode 100644 index 0000000000..61bfe69b65 --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.c @@ -0,0 +1,130 @@ +/* + * Copyright (C) Kevin van Hecke + * + * 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, see + * . + */ +/** + * @file actuators_xvert.c + * @author Kevin van Hecke + * Actuators driver for X-vert VTOL motor controllers. Contains two + * normal pwm servos, and two custom driven escs through a propriety uart + * protocol. + */ +#include "actuators_xvert.h" +#include "subsystems/actuators/actuators_pwm_arch.h" +#include "subsystems/actuators/actuators_pwm.h" + +#include "mcu_periph/uart.h" + +#define ESCS_PORT (&((ESCS_UART).device)) + + + +int32_t actuators_xvert_values[ACTUATORS_PWM_NB]; + + +#define GP 0x107 /* x^8 + x^2 + x + 1 */ +#define DI 0xE7 + + +static unsigned char crc8_table[256]; /* 8-bit table */ +static int made_table = 0; + +static void init_crc8(void) +/* + * Should be called before any other crc function. + */ +{ + int i, j; + unsigned char crc; + + if (!made_table) { + for (i = 0; i < 256; i++) { + crc = i; + for (j = 0; j < 8; j++) { + crc = (crc << 1) ^ ((crc & 0x80) ? DI : 0); + } + crc8_table[i] = crc & 0xFF; + /* printf("table[%d] = %d (0x%X)\n", i, crc, crc); */ + } + made_table = 1; + } +} + + +void crc8(unsigned char *crc, unsigned char m) +/* + * For a byte array whose accumulated crc value is stored in *crc, computes + * resultant crc obtained by appending m to the byte array + */ +{ + if (!made_table) { + init_crc8(); + } + + *crc = crc8_table[(*crc) ^ m]; + *crc &= 0xFF; +} + + +void actuators_xvert_init(void) +{ + actuators_pwm_arch_init(); +} + + + +void actuators_xvert_commit(void) +{ + if (ESCS_PORT->char_available(ESCS_PORT->periph)) { + //unsigned char b1 = ESCS_PORT->get_byte(ESCS_PORT->periph); + } + + struct EscData package; + package.start = ESCS_START_BYTE; + package.len = 8; + package.id = 2; + + package.d1 = actuators_xvert_values[XVERT_ESC_0]; + package.d2 = actuators_xvert_values[XVERT_ESC_1]; + + //do some package magic: + static bool bitflipper = true; + if (bitflipper) { + package.d1 += ESCS_DATA_FLIPBIT; + } else { + package.d2 += ESCS_DATA_FLIPBIT; + } + package.d1 += ESCS_DATA_MYSTERYBIT; + bitflipper = !bitflipper; + + unsigned char crc = 0; + unsigned char *data = (unsigned char *)&package; + for (unsigned char i = 1 ; i < sizeof(struct EscData) - 1; i++) { + crc8(&crc, data[i]); + } + package.crc = crc; + + ESCS_PORT->put_buffer(ESCS_PORT->periph, 0, (unsigned char *) &package, sizeof(struct EscData)); + + + //send the pwm signals for the two elerons to the pwm driver: + actuators_pwm_values[PWM_SERVO_2] = actuators_xvert_values[PWM_SERVO_2]; + actuators_pwm_values[PWM_SERVO_3] = actuators_xvert_values[PWM_SERVO_3]; + actuators_pwm_commit(); + +} diff --git a/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.h b/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.h new file mode 100644 index 0000000000..8abb91c9a4 --- /dev/null +++ b/sw/airborne/arch/chibios/subsystems/actuators/actuators_xvert.h @@ -0,0 +1,61 @@ +/* + * Copyright (C) Kevin van Hecke + * + * 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, see + * . + */ +/** + * @file actuators_xvert.h + * @author Kevin van Hecke + * Actuators driver for X-vert VTOL motor controllers. Contains two normal pwm servos, and two custom driven escs through a propriety uart protocol. + */ + +#ifndef ACTUATORS_XVERT_H +#define ACTUATORS_XVERT_H + +#include "subsystems/actuators/actuators_pwm_arch.h" + +#define ESCS_START_BYTE 0xFE +#define ESCS_DATA_FLIPBIT 16384 +#define ESCS_DATA_MYSTERYBIT 32768 + +struct EscData { + unsigned char start; //0xfe + unsigned char len; //8 + unsigned char id; //2 + + //1200 - 1800, maybe 1100-1900 + //1160 = off, max ~1880 + //in both data ints, 2e byte toggles the 64 bit (15e bit in total). If on, its the first, if off its the other + //in d2 16e bit always on + + uint32_t d1 ; + uint32_t d2 ; + unsigned char crc; +} __attribute__((__packed__)); + + +extern int32_t actuators_xvert_values[ACTUATORS_PWM_NB]; +extern void actuators_xvert_commit(void); +extern void actuators_xvert_init(void); + +#define ActuatorsXvertInit actuators_xvert_init +#define ActuatorXvertSet(_i, _v) { actuators_xvert_values[_i] = _v; } +#define ActuatorsXvertCommit actuators_xvert_commit + + + +#endif diff --git a/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.c b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.c new file mode 100644 index 0000000000..a4591f31aa --- /dev/null +++ b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.c @@ -0,0 +1,153 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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" + +#if HAL_USE_PAL || defined(__DOXYGEN__) +/** + * @brief PAL setup. + * @details Digital I/O ports static configuration as defined in @p board.h. + * This variable is used by the HAL when initializing the PAL driver. + */ +const PALConfig pal_default_config = { +#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 +}; +#endif + +/** + * @brief Early initialization code. + * @details This initialization must be performed just after stack setup + * and before any other initialization. + */ +void __early_init(void) +{ + + stm32_clock_init(); +} + +#if HAL_USE_SDC || defined(__DOXYGEN__) +/** + * @brief SDC card detection. + */ +bool sdc_lld_is_card_inserted(SDCDriver *sdcp) +{ + + (void)sdcp; + /* TODO: Fill the implementation.*/ + return true; +} + +/** + * @brief SDC card write protection detection. + */ +bool sdc_lld_is_write_protected(SDCDriver *sdcp) +{ + + (void)sdcp; + /* TODO: Fill the implementation.*/ + 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/stm32f3_discovery/chibios/v1.0/board.h b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.h new file mode 100644 index 0000000000..9a573c029c --- /dev/null +++ b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.h @@ -0,0 +1,1628 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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. + */ + +#ifndef BOARD_H +#define BOARD_H + +/* + * Setup for STMicroelectronics STM32F3-Discovery board. + */ + +/* + * Board identifier. + */ +#define BOARD_ST_STM32F3_DISCOVERY +#define BOARD_NAME "STMicroelectronics STM32F3-Discovery" + +/* + * Board oscillators-related settings. + * NOTE: LSE not fitted. + */ +#if !defined(STM32_LSECLK) +#define STM32_LSECLK 0U +#endif + +#define STM32_LSEDRV (3U << 3U) + +#if !defined(STM32_HSECLK) +#define STM32_HSECLK 8000000U +#endif + +#define STM32_HSE_BYPASS + +/* + * MCU type as defined in the ST header. + */ +#define STM32F303xC + +/* + * IO pins assignments. + */ +#define GPIOA_BUTTON 0U +#define GPIOA_PIN1 1U +#define GPIOA_PIN2 2U +#define GPIOA_PIN3 3U +#define GPIOA_PIN4 4U +#define GPIOA_SPI1_SCK 5U +#define GPIOA_L3GD20_SCL 5U +#define GPIOA_SPI1_MISO 6U +#define GPIOA_L3GD20_SDO 6U +#define GPIOA_SPI1_MOSI 7U +#define GPIOA_L3GD20_SDI 7U +#define GPIOA_PIN8 8U +#define GPIOA_PIN9 9U +#define GPIOA_PIN10 10U +#define GPIOA_USB_DM 11U +#define GPIOA_USB_DP 12U +#define GPIOA_SWDIO 13U +#define GPIOA_SWCLK 14U +#define GPIOA_PIN15 15U + +#define GPIOB_PIN0 0U +#define GPIOB_PIN1 1U +#define GPIOB_PIN2 2U +#define GPIOB_SWO 3U +#define GPIOB_PIN4 4U +#define GPIOB_PIN5 5U +#define GPIOB_I2C1_SCL 6U +#define GPIOB_LSM303DLHC_SCL 6U +#define GPIOB_I2C1_SDA 7U +#define GPIOB_LSM303DLHC_SDA 7U +#define GPIOB_PIN8 8U +#define GPIOB_PIN9 9U +#define GPIOB_PIN10 10U +#define GPIOB_PIN11 11U +#define GPIOB_PIN12 12U +#define GPIOB_PIN13 13U +#define GPIOB_PIN14 14U +#define GPIOB_PIN15 15U + +#define GPIOC_PIN0 0U +#define GPIOC_PIN1 1U +#define GPIOC_PIN2 2U +#define GPIOC_PIN3 3U +#define GPIOC_PIN4 4U +#define GPIOC_PIN5 5U +#define GPIOC_PIN6 6U +#define GPIOC_PIN7 7U +#define GPIOC_PIN8 8U +#define GPIOC_PIN9 9U +#define GPIOC_PIN10 10U +#define GPIOC_PIN11 11U +#define GPIOC_PIN12 12U +#define GPIOC_PIN13 13U +#define GPIOC_OSC32_IN 14U +#define GPIOC_OSC32_OUT 15U + +#define GPIOD_PIN0 0U +#define GPIOD_PIN1 1U +#define GPIOD_PIN2 2U +#define GPIOD_PIN3 3U +#define GPIOD_PIN4 4U +#define GPIOD_PIN5 5U +#define GPIOD_PIN6 6U +#define GPIOD_PIN7 7U +#define GPIOD_PIN8 8U +#define GPIOD_PIN9 9U +#define GPIOD_PIN10 10U +#define GPIOD_PIN11 11U +#define GPIOD_PIN12 12U +#define GPIOD_PIN13 13U +#define GPIOD_PIN14 14U +#define GPIOD_PIN15 15U + +#define GPIOE_L3GD20_INT1 0U +#define GPIOE_L3GD20_INT2 1U +#define GPIOE_LSM303DLHC_DRDY 2U +#define GPIOE_SPI1_CS 3U +#define GPIOE_L3GD20_CS 3U +#define GPIOE_LSM303DLHC_INT1 4U +#define GPIOE_LSM303DLHC_INT2 5U +#define GPIOE_PIN6 6U +#define GPIOE_PIN7 7U +#define GPIOE_LED4_BLUE 8U +#define GPIOE_LED3_RED 9U +#define GPIOE_LED5_ORANGE 10U +#define GPIOE_LED7_GREEN 11U +#define GPIOE_LED9_BLUE 12U +#define GPIOE_LED10_RED 13U +#define GPIOE_LED8_ORANGE 14U +#define GPIOE_LED6_GREEN 15U + +#define GPIOF_OSC_IN 0U +#define GPIOF_OSC_OUT 1U +#define GPIOF_PIN2 2U +#define GPIOF_PIN3 3U +#define GPIOF_PIN4 4U +#define GPIOF_PIN5 5U +#define GPIOF_PIN6 6U +#define GPIOF_PIN7 7U +#define GPIOF_PIN8 8U +#define GPIOF_PIN9 9U +#define GPIOF_PIN10 10U +#define GPIOF_PIN11 11U +#define GPIOF_PIN12 12U +#define GPIOF_PIN13 13U +#define GPIOF_PIN14 14U +#define GPIOF_PIN15 15U + +#define GPIOG_PIN0 0U +#define GPIOG_PIN1 1U +#define GPIOG_PIN2 2U +#define GPIOG_PIN3 3U +#define GPIOG_PIN4 4U +#define GPIOG_PIN5 5U +#define GPIOG_PIN6 6U +#define GPIOG_PIN7 7U +#define GPIOG_PIN8 8U +#define GPIOG_PIN9 9U +#define GPIOG_PIN10 10U +#define GPIOG_PIN11 11U +#define GPIOG_PIN12 12U +#define GPIOG_PIN13 13U +#define GPIOG_PIN14 14U +#define GPIOG_PIN15 15U + +#define GPIOH_PIN0 0U +#define GPIOH_PIN1 1U +#define GPIOH_PIN2 2U +#define GPIOH_PIN3 3U +#define GPIOH_PIN4 4U +#define GPIOH_PIN5 5U +#define GPIOH_PIN6 6U +#define GPIOH_PIN7 7U +#define GPIOH_PIN8 8U +#define GPIOH_PIN9 9U +#define GPIOH_PIN10 10U +#define GPIOH_PIN11 11U +#define GPIOH_PIN12 12U +#define GPIOH_PIN13 13U +#define GPIOH_PIN14 14U +#define GPIOH_PIN15 15U + +/* + * IO lines assignments. + */ +#define LINE_BUTTON PAL_LINE(GPIOA, 0U) +#define LINE_SPI1_SCK PAL_LINE(GPIOA, 5U) +#define LINE_L3GD20_SCL PAL_LINE(GPIOA, 5U) +#define LINE_SPI1_MISO PAL_LINE(GPIOA, 6U) +#define LINE_L3GD20_SDO PAL_LINE(GPIOA, 6U) +#define LINE_SPI1_MOSI PAL_LINE(GPIOA, 7U) +#define LINE_L3GD20_SDI PAL_LINE(GPIOA, 7U) +#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_SWO PAL_LINE(GPIOB, 3U) +#define LINE_I2C1_SCL PAL_LINE(GPIOB, 6U) +#define LINE_LSM303DLHC_SCL PAL_LINE(GPIOB, 6U) +#define LINE_I2C1_SDA PAL_LINE(GPIOB, 7U) +#define LINE_LSM303DLHC_SDA PAL_LINE(GPIOB, 7U) + +#define LINE_OSC32_IN PAL_LINE(GPIOC, 14U) +#define LINE_OSC32_OUT PAL_LINE(GPIOC, 15U) + + +#define LINE_L3GD20_INT1 PAL_LINE(GPIOE, 0U) +#define LINE_L3GD20_INT2 PAL_LINE(GPIOE, 1U) +#define LINE_LSM303DLHC_DRDY PAL_LINE(GPIOE, 2U) +#define LINE_SPI1_CS PAL_LINE(GPIOE, 3U) +#define LINE_L3GD20_CS PAL_LINE(GPIOE, 3U) +#define LINE_LSM303DLHC_INT1 PAL_LINE(GPIOE, 4U) +#define LINE_LSM303DLHC_INT2 PAL_LINE(GPIOE, 5U) +#define LINE_LED4_BLUE PAL_LINE(GPIOE, 8U) +#define LINE_LED3_RED PAL_LINE(GPIOE, 9U) +#define LINE_LED5_ORANGE PAL_LINE(GPIOE, 10U) +#define LINE_LED7_GREEN PAL_LINE(GPIOE, 11U) +#define LINE_LED9_BLUE PAL_LINE(GPIOE, 12U) +#define LINE_LED10_RED PAL_LINE(GPIOE, 13U) +#define LINE_LED8_ORANGE PAL_LINE(GPIOE, 14U) +#define LINE_LED6_GREEN PAL_LINE(GPIOE, 15U) + +#define LINE_OSC_IN PAL_LINE(GPIOF, 0U) +#define LINE_OSC_OUT PAL_LINE(GPIOF, 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_LOW(n) (0U << (n)) +#define PIN_ODR_HIGH(n) (1U << (n)) +#define PIN_OTYPE_PUSHPULL(n) (0U << (n)) +#define PIN_OTYPE_OPENDRAIN(n) (1U << (n)) +#define PIN_OSPEED_VERYLOW(n) (0U << ((n) * 2U)) +#define PIN_OSPEED_LOW(n) (1U << ((n) * 2U)) +#define PIN_OSPEED_MEDIUM(n) (2U << ((n) * 2U)) +#define PIN_OSPEED_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)) + +/* + * GPIOA setup: + * + * PA0 - BUTTON (input floating). + * PA1 - PIN1 (input pullup). + * PA2 - PIN2 (input pullup). + * PA3 - PIN3 (input pullup). + * PA4 - PIN4 (input pullup). + * PA5 - SPI1_SCK L3GD20_SCL (alternate 5). + * PA6 - SPI1_MISO L3GD20_SDO (alternate 5). + * PA7 - SPI1_MOSI L3GD20_SDI (alternate 5). + * PA8 - PIN8 (input pullup). + * PA9 - PIN9 (input pullup). + * PA10 - PIN10 (input pullup). + * PA11 - USB_DM (alternate 14). + * PA12 - USB_DP (alternate 14). + * PA13 - SWDIO (alternate 0). + * PA14 - SWCLK (alternate 0). + * PA15 - PIN15 (input pullup). + */ +#define VAL_GPIOA_MODER (PIN_MODE_INPUT(GPIOA_BUTTON) | \ + PIN_MODE_INPUT(GPIOA_PIN1) | \ + PIN_MODE_INPUT(GPIOA_PIN2) | \ + PIN_MODE_INPUT(GPIOA_PIN3) | \ + PIN_MODE_INPUT(GPIOA_PIN4) | \ + PIN_MODE_ALTERNATE(GPIOA_SPI1_SCK) | \ + PIN_MODE_ALTERNATE(GPIOA_SPI1_MISO) | \ + PIN_MODE_ALTERNATE(GPIOA_SPI1_MOSI) | \ + PIN_MODE_INPUT(GPIOA_PIN8) | \ + PIN_MODE_INPUT(GPIOA_PIN9) | \ + PIN_MODE_INPUT(GPIOA_PIN10) | \ + PIN_MODE_ALTERNATE(GPIOA_USB_DM) | \ + PIN_MODE_ALTERNATE(GPIOA_USB_DP) | \ + PIN_MODE_ALTERNATE(GPIOA_SWDIO) | \ + PIN_MODE_ALTERNATE(GPIOA_SWCLK) | \ + PIN_MODE_INPUT(GPIOA_PIN15)) +#define VAL_GPIOA_OTYPER (PIN_OTYPE_PUSHPULL(GPIOA_BUTTON) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SPI1_SCK) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SPI1_MISO) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SPI1_MOSI) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOA_USB_DM) | \ + PIN_OTYPE_PUSHPULL(GPIOA_USB_DP) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SWDIO) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SWCLK) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN15)) +#define VAL_GPIOA_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOA_BUTTON) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN4) | \ + PIN_OSPEED_HIGH(GPIOA_SPI1_SCK) | \ + PIN_OSPEED_HIGH(GPIOA_SPI1_MISO) | \ + PIN_OSPEED_HIGH(GPIOA_SPI1_MOSI) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN10) | \ + PIN_OSPEED_HIGH(GPIOA_USB_DM) | \ + PIN_OSPEED_VERYLOW(GPIOA_USB_DP) | \ + PIN_OSPEED_HIGH(GPIOA_SWDIO) | \ + PIN_OSPEED_HIGH(GPIOA_SWCLK) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN15)) +#define VAL_GPIOA_PUPDR (PIN_PUPDR_FLOATING(GPIOA_BUTTON) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN4) | \ + PIN_PUPDR_FLOATING(GPIOA_SPI1_SCK) | \ + PIN_PUPDR_PULLUP(GPIOA_SPI1_MISO) | \ + PIN_PUPDR_FLOATING(GPIOA_SPI1_MOSI) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN10) | \ + PIN_PUPDR_FLOATING(GPIOA_USB_DM) | \ + PIN_PUPDR_FLOATING(GPIOA_USB_DP) | \ + PIN_PUPDR_PULLUP(GPIOA_SWDIO) | \ + PIN_PUPDR_PULLDOWN(GPIOA_SWCLK) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN15)) +#define VAL_GPIOA_ODR (PIN_ODR_HIGH(GPIOA_BUTTON) | \ + PIN_ODR_HIGH(GPIOA_PIN1) | \ + PIN_ODR_HIGH(GPIOA_PIN2) | \ + PIN_ODR_HIGH(GPIOA_PIN3) | \ + PIN_ODR_HIGH(GPIOA_PIN4) | \ + PIN_ODR_HIGH(GPIOA_SPI1_SCK) | \ + PIN_ODR_HIGH(GPIOA_SPI1_MISO) | \ + PIN_ODR_HIGH(GPIOA_SPI1_MOSI) | \ + PIN_ODR_HIGH(GPIOA_PIN8) | \ + PIN_ODR_HIGH(GPIOA_PIN9) | \ + PIN_ODR_HIGH(GPIOA_PIN10) | \ + PIN_ODR_HIGH(GPIOA_USB_DM) | \ + PIN_ODR_HIGH(GPIOA_USB_DP) | \ + PIN_ODR_HIGH(GPIOA_SWDIO) | \ + PIN_ODR_HIGH(GPIOA_SWCLK) | \ + PIN_ODR_HIGH(GPIOA_PIN15)) +#define VAL_GPIOA_AFRL (PIN_AFIO_AF(GPIOA_BUTTON, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOA_SPI1_SCK, 5U) | \ + PIN_AFIO_AF(GPIOA_SPI1_MISO, 5U) | \ + PIN_AFIO_AF(GPIOA_SPI1_MOSI, 5U)) +#define VAL_GPIOA_AFRH (PIN_AFIO_AF(GPIOA_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOA_USB_DM, 14U) | \ + PIN_AFIO_AF(GPIOA_USB_DP, 14U) | \ + PIN_AFIO_AF(GPIOA_SWDIO, 0U) | \ + PIN_AFIO_AF(GPIOA_SWCLK, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN15, 0U)) + +/* + * GPIOB setup: + * + * PB0 - PIN0 (input pullup). + * PB1 - PIN1 (input pullup). + * PB2 - PIN2 (input pullup). + * PB3 - SWO (alternate 0). + * PB4 - PIN4 (input pullup). + * PB5 - PIN5 (input pullup). + * PB6 - I2C1_SCL LSM303DLHC_SCL (alternate 4). + * PB7 - I2C1_SDA LSM303DLHC_SDA (alternate 4). + * PB8 - PIN8 (input pullup). + * PB9 - PIN9 (input pullup). + * PB10 - PIN10 (input pullup). + * PB11 - PIN11 (input pullup). + * PB12 - PIN12 (input pullup). + * PB13 - PIN13 (input pullup). + * PB14 - PIN14 (input pullup). + * PB15 - PIN15 (input pullup). + */ +#define VAL_GPIOB_MODER (PIN_MODE_INPUT(GPIOB_PIN0) | \ + PIN_MODE_INPUT(GPIOB_PIN1) | \ + PIN_MODE_INPUT(GPIOB_PIN2) | \ + PIN_MODE_ALTERNATE(GPIOB_SWO) | \ + PIN_MODE_INPUT(GPIOB_PIN4) | \ + PIN_MODE_INPUT(GPIOB_PIN5) | \ + PIN_MODE_ALTERNATE(GPIOB_I2C1_SCL) | \ + PIN_MODE_ALTERNATE(GPIOB_I2C1_SDA) | \ + PIN_MODE_INPUT(GPIOB_PIN8) | \ + PIN_MODE_INPUT(GPIOB_PIN9) | \ + PIN_MODE_INPUT(GPIOB_PIN10) | \ + PIN_MODE_INPUT(GPIOB_PIN11) | \ + PIN_MODE_INPUT(GPIOB_PIN12) | \ + PIN_MODE_INPUT(GPIOB_PIN13) | \ + PIN_MODE_INPUT(GPIOB_PIN14) | \ + PIN_MODE_INPUT(GPIOB_PIN15)) +#define VAL_GPIOB_OTYPER (PIN_OTYPE_PUSHPULL(GPIOB_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOB_SWO) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN5) | \ + PIN_OTYPE_OPENDRAIN(GPIOB_I2C1_SCL) | \ + PIN_OTYPE_OPENDRAIN(GPIOB_I2C1_SDA) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN15)) +#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOB_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN2) | \ + PIN_OSPEED_HIGH(GPIOB_SWO) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN5) | \ + PIN_OSPEED_HIGH(GPIOB_I2C1_SCL) | \ + PIN_OSPEED_HIGH(GPIOB_I2C1_SDA) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN15)) +#define VAL_GPIOB_PUPDR (PIN_PUPDR_PULLUP(GPIOB_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN2) | \ + PIN_PUPDR_FLOATING(GPIOB_SWO) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN5) | \ + PIN_PUPDR_FLOATING(GPIOB_I2C1_SCL) | \ + PIN_PUPDR_FLOATING(GPIOB_I2C1_SDA) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN15)) +#define VAL_GPIOB_ODR (PIN_ODR_HIGH(GPIOB_PIN0) | \ + PIN_ODR_HIGH(GPIOB_PIN1) | \ + PIN_ODR_HIGH(GPIOB_PIN2) | \ + PIN_ODR_HIGH(GPIOB_SWO) | \ + PIN_ODR_HIGH(GPIOB_PIN4) | \ + PIN_ODR_HIGH(GPIOB_PIN5) | \ + PIN_ODR_HIGH(GPIOB_I2C1_SCL) | \ + PIN_ODR_HIGH(GPIOB_I2C1_SDA) | \ + PIN_ODR_HIGH(GPIOB_PIN8) | \ + PIN_ODR_HIGH(GPIOB_PIN9) | \ + PIN_ODR_HIGH(GPIOB_PIN10) | \ + PIN_ODR_HIGH(GPIOB_PIN11) | \ + PIN_ODR_HIGH(GPIOB_PIN12) | \ + PIN_ODR_HIGH(GPIOB_PIN13) | \ + PIN_ODR_HIGH(GPIOB_PIN14) | \ + PIN_ODR_HIGH(GPIOB_PIN15)) +#define VAL_GPIOB_AFRL (PIN_AFIO_AF(GPIOB_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOB_SWO, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOB_I2C1_SCL, 4U) | \ + PIN_AFIO_AF(GPIOB_I2C1_SDA, 4U)) +#define VAL_GPIOB_AFRH (PIN_AFIO_AF(GPIOB_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN15, 0U)) + +/* + * GPIOC setup: + * + * PC0 - PIN0 (input pullup). + * PC1 - PIN1 (input pullup). + * PC2 - PIN2 (input pullup). + * PC3 - PIN3 (input pullup). + * PC4 - PIN4 (input pullup). + * PC5 - PIN5 (input pullup). + * PC6 - PIN6 (input pullup). + * PC7 - PIN7 (input pullup). + * PC8 - PIN8 (input pullup). + * PC9 - PIN9 (input pullup). + * PC10 - PIN10 (input pullup). + * PC11 - PIN11 (input pullup). + * PC12 - PIN12 (input pullup). + * PC13 - PIN13 (input pullup). + * PC14 - OSC32_IN (input floating). + * PC15 - OSC32_OUT (input floating). + */ +#define VAL_GPIOC_MODER (PIN_MODE_INPUT(GPIOC_PIN0) | \ + PIN_MODE_INPUT(GPIOC_PIN1) | \ + PIN_MODE_INPUT(GPIOC_PIN2) | \ + PIN_MODE_INPUT(GPIOC_PIN3) | \ + PIN_MODE_INPUT(GPIOC_PIN4) | \ + PIN_MODE_INPUT(GPIOC_PIN5) | \ + PIN_MODE_INPUT(GPIOC_PIN6) | \ + PIN_MODE_INPUT(GPIOC_PIN7) | \ + PIN_MODE_INPUT(GPIOC_PIN8) | \ + PIN_MODE_INPUT(GPIOC_PIN9) | \ + PIN_MODE_INPUT(GPIOC_PIN10) | \ + PIN_MODE_INPUT(GPIOC_PIN11) | \ + PIN_MODE_INPUT(GPIOC_PIN12) | \ + PIN_MODE_INPUT(GPIOC_PIN13) | \ + PIN_MODE_INPUT(GPIOC_OSC32_IN) | \ + PIN_MODE_INPUT(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_OTYPER (PIN_OTYPE_PUSHPULL(GPIOC_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOC_OSC32_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOC_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN13) | \ + PIN_OSPEED_HIGH(GPIOC_OSC32_IN) | \ + PIN_OSPEED_HIGH(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_PUPDR (PIN_PUPDR_PULLUP(GPIOC_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN13) | \ + PIN_PUPDR_FLOATING(GPIOC_OSC32_IN) | \ + PIN_PUPDR_FLOATING(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_ODR (PIN_ODR_HIGH(GPIOC_PIN0) | \ + PIN_ODR_HIGH(GPIOC_PIN1) | \ + PIN_ODR_HIGH(GPIOC_PIN2) | \ + PIN_ODR_HIGH(GPIOC_PIN3) | \ + PIN_ODR_HIGH(GPIOC_PIN4) | \ + PIN_ODR_HIGH(GPIOC_PIN5) | \ + PIN_ODR_HIGH(GPIOC_PIN6) | \ + PIN_ODR_HIGH(GPIOC_PIN7) | \ + PIN_ODR_HIGH(GPIOC_PIN8) | \ + PIN_ODR_HIGH(GPIOC_PIN9) | \ + PIN_ODR_HIGH(GPIOC_PIN10) | \ + PIN_ODR_HIGH(GPIOC_PIN11) | \ + PIN_ODR_HIGH(GPIOC_PIN12) | \ + PIN_ODR_HIGH(GPIOC_PIN13) | \ + PIN_ODR_HIGH(GPIOC_OSC32_IN) | \ + PIN_ODR_HIGH(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_AFRL (PIN_AFIO_AF(GPIOC_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN7, 0U)) +#define VAL_GPIOC_AFRH (PIN_AFIO_AF(GPIOC_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOC_OSC32_IN, 0U) | \ + PIN_AFIO_AF(GPIOC_OSC32_OUT, 0U)) + +/* + * GPIOD setup: + * + * PD0 - PIN0 (input pullup). + * PD1 - PIN1 (input pullup). + * PD2 - PIN2 (input pullup). + * PD3 - PIN3 (input pullup). + * PD4 - PIN4 (input pullup). + * PD5 - PIN5 (input pullup). + * PD6 - PIN6 (input pullup). + * PD7 - PIN7 (input pullup). + * PD8 - PIN8 (input pullup). + * PD9 - PIN9 (input pullup). + * PD10 - PIN10 (input pullup). + * PD11 - PIN11 (input pullup). + * PD12 - PIN12 (input pullup). + * PD13 - PIN13 (input pullup). + * PD14 - PIN14 (input pullup). + * PD15 - PIN15 (input pullup). + */ +#define VAL_GPIOD_MODER (PIN_MODE_INPUT(GPIOD_PIN0) | \ + PIN_MODE_INPUT(GPIOD_PIN1) | \ + PIN_MODE_INPUT(GPIOD_PIN2) | \ + PIN_MODE_INPUT(GPIOD_PIN3) | \ + PIN_MODE_INPUT(GPIOD_PIN4) | \ + PIN_MODE_INPUT(GPIOD_PIN5) | \ + PIN_MODE_INPUT(GPIOD_PIN6) | \ + PIN_MODE_INPUT(GPIOD_PIN7) | \ + PIN_MODE_INPUT(GPIOD_PIN8) | \ + PIN_MODE_INPUT(GPIOD_PIN9) | \ + PIN_MODE_INPUT(GPIOD_PIN10) | \ + PIN_MODE_INPUT(GPIOD_PIN11) | \ + PIN_MODE_INPUT(GPIOD_PIN12) | \ + PIN_MODE_INPUT(GPIOD_PIN13) | \ + PIN_MODE_INPUT(GPIOD_PIN14) | \ + PIN_MODE_INPUT(GPIOD_PIN15)) +#define VAL_GPIOD_OTYPER (PIN_OTYPE_PUSHPULL(GPIOD_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN15)) +#define VAL_GPIOD_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOD_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN15)) +#define VAL_GPIOD_PUPDR (PIN_PUPDR_PULLUP(GPIOD_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN15)) +#define VAL_GPIOD_ODR (PIN_ODR_HIGH(GPIOD_PIN0) | \ + PIN_ODR_HIGH(GPIOD_PIN1) | \ + PIN_ODR_HIGH(GPIOD_PIN2) | \ + PIN_ODR_HIGH(GPIOD_PIN3) | \ + PIN_ODR_HIGH(GPIOD_PIN4) | \ + PIN_ODR_HIGH(GPIOD_PIN5) | \ + PIN_ODR_HIGH(GPIOD_PIN6) | \ + PIN_ODR_HIGH(GPIOD_PIN7) | \ + PIN_ODR_HIGH(GPIOD_PIN8) | \ + PIN_ODR_HIGH(GPIOD_PIN9) | \ + PIN_ODR_HIGH(GPIOD_PIN10) | \ + PIN_ODR_HIGH(GPIOD_PIN11) | \ + PIN_ODR_HIGH(GPIOD_PIN12) | \ + PIN_ODR_HIGH(GPIOD_PIN13) | \ + PIN_ODR_HIGH(GPIOD_PIN14) | \ + PIN_ODR_HIGH(GPIOD_PIN15)) +#define VAL_GPIOD_AFRL (PIN_AFIO_AF(GPIOD_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN7, 0U)) +#define VAL_GPIOD_AFRH (PIN_AFIO_AF(GPIOD_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN15, 0U)) + +/* + * GPIOE setup: + * + * PE0 - L3GD20_INT1 (input pullup). + * PE1 - L3GD20_INT2 (input pullup). + * PE2 - LSM303DLHC_DRDY (input pullup). + * PE3 - SPI1_CS L3GD20_CS (output pushpull maximum). + * PE4 - LSM303DLHC_INT1 (input pullup). + * PE5 - LSM303DLHC_INT2 (input pullup). + * PE6 - PIN6 (input pullup). + * PE7 - PIN7 (input pullup). + * PE8 - LED4_BLUE (output pushpull maximum). + * PE9 - LED3_RED (output pushpull maximum). + * PE10 - LED5_ORANGE (output pushpull maximum). + * PE11 - LED7_GREEN (output pushpull maximum). + * PE12 - LED9_BLUE (output pushpull maximum). + * PE13 - LED10_RED (output pushpull maximum). + * PE14 - LED8_ORANGE (output pushpull maximum). + * PE15 - LED6_GREEN (output pushpull maximum). + */ +#define VAL_GPIOE_MODER (PIN_MODE_INPUT(GPIOE_L3GD20_INT1) | \ + PIN_MODE_INPUT(GPIOE_L3GD20_INT2) | \ + PIN_MODE_INPUT(GPIOE_LSM303DLHC_DRDY) |\ + PIN_MODE_OUTPUT(GPIOE_SPI1_CS) | \ + PIN_MODE_INPUT(GPIOE_LSM303DLHC_INT1) |\ + PIN_MODE_INPUT(GPIOE_LSM303DLHC_INT2) |\ + PIN_MODE_INPUT(GPIOE_PIN6) | \ + PIN_MODE_INPUT(GPIOE_PIN7) | \ + PIN_MODE_OUTPUT(GPIOE_LED4_BLUE) | \ + PIN_MODE_OUTPUT(GPIOE_LED3_RED) | \ + PIN_MODE_OUTPUT(GPIOE_LED5_ORANGE) | \ + PIN_MODE_OUTPUT(GPIOE_LED7_GREEN) | \ + PIN_MODE_OUTPUT(GPIOE_LED9_BLUE) | \ + PIN_MODE_OUTPUT(GPIOE_LED10_RED) | \ + PIN_MODE_OUTPUT(GPIOE_LED8_ORANGE) | \ + PIN_MODE_OUTPUT(GPIOE_LED6_GREEN)) +#define VAL_GPIOE_OTYPER (PIN_OTYPE_PUSHPULL(GPIOE_L3GD20_INT1) |\ + PIN_OTYPE_PUSHPULL(GPIOE_L3GD20_INT2) |\ + PIN_OTYPE_PUSHPULL(GPIOE_LSM303DLHC_DRDY) |\ + PIN_OTYPE_PUSHPULL(GPIOE_SPI1_CS) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LSM303DLHC_INT1) |\ + PIN_OTYPE_PUSHPULL(GPIOE_LSM303DLHC_INT2) |\ + PIN_OTYPE_PUSHPULL(GPIOE_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED4_BLUE) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED3_RED) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED5_ORANGE) |\ + PIN_OTYPE_PUSHPULL(GPIOE_LED7_GREEN) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED9_BLUE) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED10_RED) | \ + PIN_OTYPE_PUSHPULL(GPIOE_LED8_ORANGE) |\ + PIN_OTYPE_PUSHPULL(GPIOE_LED6_GREEN)) +#define VAL_GPIOE_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOE_L3GD20_INT1) |\ + PIN_OSPEED_VERYLOW(GPIOE_L3GD20_INT2) |\ + PIN_OSPEED_VERYLOW(GPIOE_LSM303DLHC_DRDY) |\ + PIN_OSPEED_HIGH(GPIOE_SPI1_CS) | \ + PIN_OSPEED_VERYLOW(GPIOE_LSM303DLHC_INT1) |\ + PIN_OSPEED_VERYLOW(GPIOE_LSM303DLHC_INT2) |\ + PIN_OSPEED_VERYLOW(GPIOE_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN7) | \ + PIN_OSPEED_HIGH(GPIOE_LED4_BLUE) | \ + PIN_OSPEED_HIGH(GPIOE_LED3_RED) | \ + PIN_OSPEED_HIGH(GPIOE_LED5_ORANGE) | \ + PIN_OSPEED_HIGH(GPIOE_LED7_GREEN) | \ + PIN_OSPEED_HIGH(GPIOE_LED9_BLUE) | \ + PIN_OSPEED_HIGH(GPIOE_LED10_RED) | \ + PIN_OSPEED_HIGH(GPIOE_LED8_ORANGE) | \ + PIN_OSPEED_HIGH(GPIOE_LED6_GREEN)) +#define VAL_GPIOE_PUPDR (PIN_PUPDR_PULLUP(GPIOE_L3GD20_INT1) | \ + PIN_PUPDR_PULLUP(GPIOE_L3GD20_INT2) | \ + PIN_PUPDR_PULLUP(GPIOE_LSM303DLHC_DRDY) |\ + PIN_PUPDR_FLOATING(GPIOE_SPI1_CS) | \ + PIN_PUPDR_PULLUP(GPIOE_LSM303DLHC_INT1) |\ + PIN_PUPDR_PULLUP(GPIOE_LSM303DLHC_INT2) |\ + PIN_PUPDR_PULLUP(GPIOE_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOE_LED4_BLUE) | \ + PIN_PUPDR_PULLUP(GPIOE_LED3_RED) | \ + PIN_PUPDR_PULLUP(GPIOE_LED5_ORANGE) | \ + PIN_PUPDR_FLOATING(GPIOE_LED7_GREEN) | \ + PIN_PUPDR_PULLUP(GPIOE_LED9_BLUE) | \ + PIN_PUPDR_FLOATING(GPIOE_LED10_RED) | \ + PIN_PUPDR_FLOATING(GPIOE_LED8_ORANGE) |\ + PIN_PUPDR_FLOATING(GPIOE_LED6_GREEN)) +#define VAL_GPIOE_ODR (PIN_ODR_HIGH(GPIOE_L3GD20_INT1) | \ + PIN_ODR_HIGH(GPIOE_L3GD20_INT2) | \ + PIN_ODR_HIGH(GPIOE_LSM303DLHC_DRDY) | \ + PIN_ODR_HIGH(GPIOE_SPI1_CS) | \ + PIN_ODR_HIGH(GPIOE_LSM303DLHC_INT1) | \ + PIN_ODR_HIGH(GPIOE_LSM303DLHC_INT2) | \ + PIN_ODR_HIGH(GPIOE_PIN6) | \ + PIN_ODR_HIGH(GPIOE_PIN7) | \ + PIN_ODR_LOW(GPIOE_LED4_BLUE) | \ + PIN_ODR_LOW(GPIOE_LED3_RED) | \ + PIN_ODR_LOW(GPIOE_LED5_ORANGE) | \ + PIN_ODR_LOW(GPIOE_LED7_GREEN) | \ + PIN_ODR_LOW(GPIOE_LED9_BLUE) | \ + PIN_ODR_LOW(GPIOE_LED10_RED) | \ + PIN_ODR_LOW(GPIOE_LED8_ORANGE) | \ + PIN_ODR_LOW(GPIOE_LED6_GREEN)) +#define VAL_GPIOE_AFRL (PIN_AFIO_AF(GPIOE_L3GD20_INT1, 0U) | \ + PIN_AFIO_AF(GPIOE_L3GD20_INT2, 0U) | \ + PIN_AFIO_AF(GPIOE_LSM303DLHC_DRDY, 0U) |\ + PIN_AFIO_AF(GPIOE_SPI1_CS, 0U) | \ + PIN_AFIO_AF(GPIOE_LSM303DLHC_INT1, 0U) |\ + PIN_AFIO_AF(GPIOE_LSM303DLHC_INT2, 0U) |\ + PIN_AFIO_AF(GPIOE_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN7, 0U)) +#define VAL_GPIOE_AFRH (PIN_AFIO_AF(GPIOE_LED4_BLUE, 0U) | \ + PIN_AFIO_AF(GPIOE_LED3_RED, 0U) | \ + PIN_AFIO_AF(GPIOE_LED5_ORANGE, 0U) | \ + PIN_AFIO_AF(GPIOE_LED7_GREEN, 0U) | \ + PIN_AFIO_AF(GPIOE_LED9_BLUE, 0U) | \ + PIN_AFIO_AF(GPIOE_LED10_RED, 0U) | \ + PIN_AFIO_AF(GPIOE_LED8_ORANGE, 0U) | \ + PIN_AFIO_AF(GPIOE_LED6_GREEN, 0U)) + +/* + * GPIOF setup: + * + * PF0 - OSC_IN (input floating). + * PF1 - OSC_OUT (input floating). + * PF2 - PIN2 (input pullup). + * PF3 - PIN3 (input pullup). + * PF4 - PIN4 (input pullup). + * PF5 - PIN5 (input pullup). + * PF6 - PIN6 (input pullup). + * PF7 - PIN7 (input pullup). + * PF8 - PIN8 (input pullup). + * PF9 - PIN9 (input pullup). + * PF10 - PIN10 (input pullup). + * PF11 - PIN11 (input pullup). + * PF12 - PIN12 (input pullup). + * PF13 - PIN13 (input pullup). + * PF14 - PIN14 (input pullup). + * PF15 - PIN15 (input pullup). + */ +#define VAL_GPIOF_MODER (PIN_MODE_INPUT(GPIOF_OSC_IN) | \ + PIN_MODE_INPUT(GPIOF_OSC_OUT) | \ + PIN_MODE_INPUT(GPIOF_PIN2) | \ + PIN_MODE_INPUT(GPIOF_PIN3) | \ + PIN_MODE_INPUT(GPIOF_PIN4) | \ + PIN_MODE_INPUT(GPIOF_PIN5) | \ + PIN_MODE_INPUT(GPIOF_PIN6) | \ + PIN_MODE_INPUT(GPIOF_PIN7) | \ + PIN_MODE_INPUT(GPIOF_PIN8) | \ + PIN_MODE_INPUT(GPIOF_PIN9) | \ + PIN_MODE_INPUT(GPIOF_PIN10) | \ + PIN_MODE_INPUT(GPIOF_PIN11) | \ + PIN_MODE_INPUT(GPIOF_PIN12) | \ + PIN_MODE_INPUT(GPIOF_PIN13) | \ + PIN_MODE_INPUT(GPIOF_PIN14) | \ + PIN_MODE_INPUT(GPIOF_PIN15)) +#define VAL_GPIOF_OTYPER (PIN_OTYPE_PUSHPULL(GPIOF_OSC_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOF_OSC_OUT) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN15)) +#define VAL_GPIOF_OSPEEDR (PIN_OSPEED_HIGH(GPIOF_OSC_IN) | \ + PIN_OSPEED_HIGH(GPIOF_OSC_OUT) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN15)) +#define VAL_GPIOF_PUPDR (PIN_PUPDR_FLOATING(GPIOF_OSC_IN) | \ + PIN_PUPDR_FLOATING(GPIOF_OSC_OUT) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN15)) +#define VAL_GPIOF_ODR (PIN_ODR_HIGH(GPIOF_OSC_IN) | \ + PIN_ODR_HIGH(GPIOF_OSC_OUT) | \ + PIN_ODR_HIGH(GPIOF_PIN2) | \ + PIN_ODR_HIGH(GPIOF_PIN3) | \ + PIN_ODR_HIGH(GPIOF_PIN4) | \ + PIN_ODR_HIGH(GPIOF_PIN5) | \ + PIN_ODR_HIGH(GPIOF_PIN6) | \ + PIN_ODR_HIGH(GPIOF_PIN7) | \ + PIN_ODR_HIGH(GPIOF_PIN8) | \ + PIN_ODR_HIGH(GPIOF_PIN9) | \ + PIN_ODR_HIGH(GPIOF_PIN10) | \ + PIN_ODR_HIGH(GPIOF_PIN11) | \ + PIN_ODR_HIGH(GPIOF_PIN12) | \ + PIN_ODR_HIGH(GPIOF_PIN13) | \ + PIN_ODR_HIGH(GPIOF_PIN14) | \ + PIN_ODR_HIGH(GPIOF_PIN15)) +#define VAL_GPIOF_AFRL (PIN_AFIO_AF(GPIOF_OSC_IN, 0U) | \ + PIN_AFIO_AF(GPIOF_OSC_OUT, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN7, 0U)) +#define VAL_GPIOF_AFRH (PIN_AFIO_AF(GPIOF_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN15, 0U)) + +/* + * GPIOG setup: + * + * PG0 - PIN0 (input pullup). + * PG1 - PIN1 (input pullup). + * PG2 - PIN2 (input pullup). + * PG3 - PIN3 (input pullup). + * PG4 - PIN4 (input pullup). + * PG5 - PIN5 (input pullup). + * PG6 - PIN6 (input pullup). + * PG7 - PIN7 (input pullup). + * PG8 - PIN8 (input pullup). + * PG9 - PIN9 (input pullup). + * PG10 - PIN10 (input pullup). + * PG11 - PIN11 (input pullup). + * PG12 - PIN12 (input pullup). + * PG13 - PIN13 (input pullup). + * PG14 - PIN14 (input pullup). + * PG15 - PIN15 (input pullup). + */ +#define VAL_GPIOG_MODER (PIN_MODE_INPUT(GPIOG_PIN0) | \ + PIN_MODE_INPUT(GPIOG_PIN1) | \ + PIN_MODE_INPUT(GPIOG_PIN2) | \ + PIN_MODE_INPUT(GPIOG_PIN3) | \ + PIN_MODE_INPUT(GPIOG_PIN4) | \ + PIN_MODE_INPUT(GPIOG_PIN5) | \ + PIN_MODE_INPUT(GPIOG_PIN6) | \ + PIN_MODE_INPUT(GPIOG_PIN7) | \ + PIN_MODE_INPUT(GPIOG_PIN8) | \ + PIN_MODE_INPUT(GPIOG_PIN9) | \ + PIN_MODE_INPUT(GPIOG_PIN10) | \ + PIN_MODE_INPUT(GPIOG_PIN11) | \ + PIN_MODE_INPUT(GPIOG_PIN12) | \ + PIN_MODE_INPUT(GPIOG_PIN13) | \ + PIN_MODE_INPUT(GPIOG_PIN14) | \ + PIN_MODE_INPUT(GPIOG_PIN15)) +#define VAL_GPIOG_OTYPER (PIN_OTYPE_PUSHPULL(GPIOG_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN15)) +#define VAL_GPIOG_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOG_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN15)) +#define VAL_GPIOG_PUPDR (PIN_PUPDR_PULLUP(GPIOG_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN15)) +#define VAL_GPIOG_ODR (PIN_ODR_HIGH(GPIOG_PIN0) | \ + PIN_ODR_HIGH(GPIOG_PIN1) | \ + PIN_ODR_HIGH(GPIOG_PIN2) | \ + PIN_ODR_HIGH(GPIOG_PIN3) | \ + PIN_ODR_HIGH(GPIOG_PIN4) | \ + PIN_ODR_HIGH(GPIOG_PIN5) | \ + PIN_ODR_HIGH(GPIOG_PIN6) | \ + PIN_ODR_HIGH(GPIOG_PIN7) | \ + PIN_ODR_HIGH(GPIOG_PIN8) | \ + PIN_ODR_HIGH(GPIOG_PIN9) | \ + PIN_ODR_HIGH(GPIOG_PIN10) | \ + PIN_ODR_HIGH(GPIOG_PIN11) | \ + PIN_ODR_HIGH(GPIOG_PIN12) | \ + PIN_ODR_HIGH(GPIOG_PIN13) | \ + PIN_ODR_HIGH(GPIOG_PIN14) | \ + PIN_ODR_HIGH(GPIOG_PIN15)) +#define VAL_GPIOG_AFRL (PIN_AFIO_AF(GPIOG_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN7, 0U)) +#define VAL_GPIOG_AFRH (PIN_AFIO_AF(GPIOG_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN15, 0U)) + +/* + * GPIOH setup: + * + * PH0 - PIN0 (input pullup). + * PH1 - PIN1 (input pullup). + * PH2 - PIN2 (input pullup). + * PH3 - PIN3 (input pullup). + * PH4 - PIN4 (input pullup). + * PH5 - PIN5 (input pullup). + * PH6 - PIN6 (input pullup). + * PH7 - PIN7 (input pullup). + * PH8 - PIN8 (input pullup). + * PH9 - PIN9 (input pullup). + * PH10 - PIN10 (input pullup). + * PH11 - PIN11 (input pullup). + * PH12 - PIN12 (input pullup). + * PH13 - PIN13 (input pullup). + * PH14 - PIN14 (input pullup). + * PH15 - PIN15 (input pullup). + */ +#define VAL_GPIOH_MODER (PIN_MODE_INPUT(GPIOH_PIN0) | \ + PIN_MODE_INPUT(GPIOH_PIN1) | \ + PIN_MODE_INPUT(GPIOH_PIN2) | \ + PIN_MODE_INPUT(GPIOH_PIN3) | \ + PIN_MODE_INPUT(GPIOH_PIN4) | \ + PIN_MODE_INPUT(GPIOH_PIN5) | \ + PIN_MODE_INPUT(GPIOH_PIN6) | \ + PIN_MODE_INPUT(GPIOH_PIN7) | \ + PIN_MODE_INPUT(GPIOH_PIN8) | \ + PIN_MODE_INPUT(GPIOH_PIN9) | \ + PIN_MODE_INPUT(GPIOH_PIN10) | \ + PIN_MODE_INPUT(GPIOH_PIN11) | \ + PIN_MODE_INPUT(GPIOH_PIN12) | \ + PIN_MODE_INPUT(GPIOH_PIN13) | \ + PIN_MODE_INPUT(GPIOH_PIN14) | \ + PIN_MODE_INPUT(GPIOH_PIN15)) +#define VAL_GPIOH_OTYPER (PIN_OTYPE_PUSHPULL(GPIOH_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN15)) +#define VAL_GPIOH_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOH_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN15)) +#define VAL_GPIOH_PUPDR (PIN_PUPDR_PULLUP(GPIOH_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN15)) +#define VAL_GPIOH_ODR (PIN_ODR_HIGH(GPIOH_PIN0) | \ + PIN_ODR_HIGH(GPIOH_PIN1) | \ + PIN_ODR_HIGH(GPIOH_PIN2) | \ + PIN_ODR_HIGH(GPIOH_PIN3) | \ + PIN_ODR_HIGH(GPIOH_PIN4) | \ + PIN_ODR_HIGH(GPIOH_PIN5) | \ + PIN_ODR_HIGH(GPIOH_PIN6) | \ + PIN_ODR_HIGH(GPIOH_PIN7) | \ + PIN_ODR_HIGH(GPIOH_PIN8) | \ + PIN_ODR_HIGH(GPIOH_PIN9) | \ + PIN_ODR_HIGH(GPIOH_PIN10) | \ + PIN_ODR_HIGH(GPIOH_PIN11) | \ + PIN_ODR_HIGH(GPIOH_PIN12) | \ + PIN_ODR_HIGH(GPIOH_PIN13) | \ + PIN_ODR_HIGH(GPIOH_PIN14) | \ + PIN_ODR_HIGH(GPIOH_PIN15)) +#define VAL_GPIOH_AFRL (PIN_AFIO_AF(GPIOH_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN7, 0U)) +#define VAL_GPIOH_AFRH (PIN_AFIO_AF(GPIOH_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN15, 0U)) + +//***************************************************************************** + +/* + * AHB_CLK + */ +#define AHB_CLK STM32_HCLK + +/* + * LEDs + */ +/* red */ +#ifndef USE_LED_1 +#define USE_LED_1 1 +#endif +#define LED_1_GPIO GPIOE +#define LED_1_GPIO_PIN GPIO9 +#define LED_1_GPIO_ON gpio_clear +#define LED_1_GPIO_OFF gpio_set + +/* blue */ +#ifndef USE_LED_2 +#define USE_LED_2 1 +#endif +#define LED_2_GPIO GPIOE +#define LED_2_GPIO_PIN GPIO8 +#define LED_2_GPIO_ON gpio_clear +#define LED_2_GPIO_OFF gpio_set + +/*orange */ +#ifndef USE_LED_3 +#define USE_LED_3 1 +#endif +#define LED_3_GPIO GPIOE +#define LED_3_GPIO_PIN GPIO10 +#define LED_3_GPIO_ON gpio_clear +#define LED_3_GPIO_OFF gpio_set + +/* green */ +#ifndef USE_LED_4 +#define USE_LED_4 1 +#endif +#define LED_4_GPIO GPIOE +#define LED_4_GPIO_PIN GPIO11 +#define LED_4_GPIO_ON gpio_clear +#define LED_4_GPIO_OFF gpio_set + +/* blue*/ +#ifndef USE_LED_5 +#define USE_LED_5 0 +#endif +#define LED_5_GPIO GPIOE +#define LED_5_GPIO_PIN GPIO12 +#define LED_5_GPIO_ON gpio_set +#define LED_5_GPIO_OFF gpio_clear + +/* red*/ +#ifndef USE_LED_6 +#define USE_LED_6 0 +#endif +#define LED_6_GPIO GPIOE +#define LED_6_GPIO_PIN GPIO13 +#define LED_6_GPIO_ON gpio_set +#define LED_6_GPIO_OFF gpio_clear + +/* orange*/ +#ifndef USE_LED_7 +#define USE_LED_7 0 +#endif +#define LED_7_GPIO GPIOE +#define LED_7_GPIO_PIN GPIO13 +#define LED_7_GPIO_ON gpio_set +#define LED_7_GPIO_OFF gpio_clear + +/* green*/ +#ifndef USE_LED_8 +#define USE_LED_8 0 +#endif +#define LED_8_GPIO GPIOE +#define LED_8_GPIO_PIN GPIO15 +#define LED_8_GPIO_ON gpio_set +#define LED_8_GPIO_OFF gpio_clear + + +/* 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 + +/* + * ADCs + */ +// AUX 1 +#if USE_ADC_1 +#define AD1_1_CHANNEL ADC_CHANNEL_IN9 +#define ADC_1 AD1_1 +#define ADC_1_GPIO_PORT GPIOB +#define ADC_1_GPIO_PIN GPIO1 +#endif + +// AUX 2 +#if USE_ADC_2 +#define AD1_2_CHANNEL ADC_CHANNEL_IN15 +#define ADC_2 AD1_2 +#define ADC_2_GPIO_PORT GPIOC +#define ADC_2_GPIO_PIN GPIO5 +#endif + +// AUX 3 +#if USE_ADC_3 +#define AD1_3_CHANNEL ADC_CHANNEL_IN14 +#define ADC_3 AD1_3 +#define ADC_3_GPIO_PORT GPIOC +#define ADC_3_GPIO_PIN GPIO4 +#endif + +// Internal ADC for battery enabled by default +#ifndef USE_ADC_4 +#define USE_ADC_4 1 +#endif +#if USE_ADC_4 +#define AD1_4_CHANNEL ADC_CHANNEL_IN4 +#define ADC_4 AD1_4 +#define ADC_4_GPIO_PORT GPIOA +#define ADC_4_GPIO_PIN GPIO4 +#endif + +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_4 +#endif + +#define DefaultVoltageOfAdc(adc) (0.006185*adc) + +/* + * PWM defines + */ +#ifndef USE_PWM0 +#define USE_PWM0 1 +#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 +#endif + +#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 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 +#endif + +#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 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 +#endif + +#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 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 +#endif + +#ifndef USE_PWM4 +#define USE_PWM4 1 +#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 +#endif + +#ifndef USE_PWM5 +#define USE_PWM5 1 +#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 +#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 +#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 + */ +#define RC_PPM_TICKS_PER_USEC 2 +#define PPM_TIMER_FREQUENCY 2000000 +#define PPM_CHANNEL ICU_CHANNEL_1 +#define PPM_TIMER ICUD1 + +/* + * PWM input + */ +// PWM_INPUT 1 on PA8 (also PPM IN) +#define PWM_INPUT1_ICU ICUD1 +#define PWM_INPUT1_CHANNEL ICU_CHANNEL_1 +// PPM in (aka PA8) is used: not compatible with PPM RC receiver +#define PWM_INPUT1_GPIO_PORT GPIOA +#define PWM_INPUT1_GPIO_PIN GPIO8 +#define PWM_INPUT1_GPIO_AF GPIO_AF1 + +// PWM_INPUT 2 on PA3 (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_GPIO_PORT GPIOA +#define PWM_INPUT2_GPIO_PIN GPIO2 +#define PWM_INPUT2_GPIO_AF GPIO_AF3 + +/** + * I2C defines + */ +#ifndef I2C1_CLOCK_SPEED +#define I2C1_CLOCK_SPEED 400000 +#endif +#if I2C1_CLOCK_SPEED == 400000 +#define I2C1_DUTY_CYCLE FAST_DUTY_CYCLE_2 +#elif I2C1_CLOCK_SPEED == 100000 +#define I2C1_DUTY_CYCLE STD_DUTY_CYCLE +#else +#error Invalid I2C1 clock speed +#endif +#define I2C1_CFG_DEF { \ + OPMODE_I2C, \ + I2C1_CLOCK_SPEED, \ + I2C1_DUTY_CYCLE, \ + } + +#ifndef I2C2_CLOCK_SPEED +#define I2C2_CLOCK_SPEED 400000 +#endif +#if I2C2_CLOCK_SPEED == 400000 +#define I2C2_DUTY_CYCLE FAST_DUTY_CYCLE_2 +#elif I2C2_CLOCK_SPEED == 100000 +#define I2C2_DUTY_CYCLE STD_DUTY_CYCLE +#else +#error Invalid I2C2 clock speed +#endif +#define I2C2_CFG_DEF { \ + OPMODE_I2C, \ + I2C2_CLOCK_SPEED, \ + I2C2_DUTY_CYCLE, \ + } + +/** + * SPI Config + */ +#define SPI1_GPIO_AF GPIO_AF5 +#define SPI1_GPIO_PORT_MISO GPIOA +#define SPI1_GPIO_MISO GPIO6 +#define SPI1_GPIO_PORT_MOSI GPIOA +#define SPI1_GPIO_MOSI GPIO7 +#define SPI1_GPIO_PORT_SCK GPIOA +#define SPI1_GPIO_SCK GPIO5 + +// SLAVE0 on SPI connector +#define SPI_SELECT_SLAVE0_PORT GPIOB +#define SPI_SELECT_SLAVE0_PIN GPIO9 +// SLAVE1 on AUX1 +#define SPI_SELECT_SLAVE1_PORT GPIOB +#define SPI_SELECT_SLAVE1_PIN GPIO1 +// SLAVE2 on AUX2 +#define SPI_SELECT_SLAVE2_PORT GPIOC +#define SPI_SELECT_SLAVE2_PIN GPIO5 +// SLAVE3 on AUX3 +#define SPI_SELECT_SLAVE3_PORT GPIOC +#define SPI_SELECT_SLAVE3_PIN GPIO4 +// SLAVE4 on AUX4 +#define SPI_SELECT_SLAVE4_PORT GPIOB +#define SPI_SELECT_SLAVE4_PIN GPIO15 + +/** + * Baro + * + * Apparently needed for backwards compatibility + * with the ancient onboard baro boards + */ +// #ifndef USE_BARO_BOARD +// #define USE_BARO_BOARD 1 +// #endif + +/* + * Actuators for fixedwing + */ +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + + +/** + * SDIO + */ +#define SDIO_D0_PORT GPIOC +#define SDIO_D0_PIN GPIOC_SDIO_D0 +#define SDIO_D1_PORT GPIOC +#define SDIO_D1_PIN GPIOC_SDIO_D1 +#define SDIO_D2_PORT GPIOC +#define SDIO_D2_PIN GPIOC_SDIO_D2 +#define SDIO_D3_PORT GPIOC +#define SDIO_D3_PIN GPIOC_SDIO_D3 +#define SDIO_CK_PORT GPIOC +#define SDIO_CK_PIN GPIOC_SDIO_CK +#define SDIO_CMD_PORT GPIOD +#define SDIO_CMD_PIN GPIOD_SDIO_CMD +#define SDIO_AF 12 +// bat monitoring for file closing +#define SDLOG_BAT_ADC ADCD1 +#define SDLOG_BAT_CHAN AD1_4_CHANNEL +// usb led status +#define SDLOG_USB_LED 4 +#define SDLOG_USB_VBUS_PORT GPIOA +#define SDLOG_USB_VBUS_PIN GPIO9 + + +//***************************************************************************** +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif +void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* BOARD_H */ diff --git a/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.mk b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.mk new file mode 100644 index 0000000000..5a109515f4 --- /dev/null +++ b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/board.mk @@ -0,0 +1,20 @@ +# +# 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 diff --git a/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/mcuconf.h b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/mcuconf.h new file mode 100644 index 0000000000..2a26642a2f --- /dev/null +++ b/sw/airborne/boards/stm32f3_discovery/chibios/v1.0/mcuconf.h @@ -0,0 +1,301 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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 + +/* + * STM32F3xx 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 STM32F3xx_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 +#define STM32_HSI_ENABLED TRUE +#define STM32_LSI_ENABLED TRUE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PREDIV_VALUE 1 +#define STM32_PLLMUL_VALUE 9 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK +#define STM32_ADC12PRES STM32_ADC12PRES_DIV1 +#define STM32_ADC34PRES STM32_ADC34PRES_DIV1 +#define STM32_USART1SW STM32_USART1SW_PCLK +#define STM32_USART2SW STM32_USART2SW_PCLK +#define STM32_USART3SW STM32_USART3SW_PCLK +#define STM32_UART4SW STM32_UART4SW_PCLK +#define STM32_UART5SW STM32_UART5SW_PCLK +#define STM32_I2C1SW STM32_I2C1SW_SYSCLK +#define STM32_I2C2SW STM32_I2C2SW_SYSCLK +#define STM32_TIM1SW STM32_TIM1SW_PCLK2 +#define STM32_TIM8SW STM32_TIM8SW_PCLK2 +#define STM32_RTCSEL STM32_RTCSEL_LSI +#define STM32_USB_CLOCK_REQUIRED TRUE +#define STM32_USBPRE STM32_USBPRE_DIV1P5 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_DUAL_MODE FALSE +#define STM32_ADC_COMPACT_SAMPLES FALSE +#define STM32_ADC_USE_ADC1 TRUE +#define STM32_ADC_USE_ADC2 FALSE +#define STM32_ADC_USE_ADC3 FALSE +#define STM32_ADC_USE_ADC4 FALSE +#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(1, 1) +#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 1) +#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 5) +#define STM32_ADC_ADC4_DMA_STREAM STM32_DMA_STREAM_ID(2, 2) +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC2_DMA_PRIORITY 2 +#define STM32_ADC_ADC3_DMA_PRIORITY 2 +#define STM32_ADC_ADC4_DMA_PRIORITY 2 +#define STM32_ADC_ADC12_IRQ_PRIORITY 5 +#define STM32_ADC_ADC3_IRQ_PRIORITY 5 +#define STM32_ADC_ADC4_IRQ_PRIORITY 5 +#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_ADC4_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1 +#define STM32_ADC_ADC34_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1 + +/* + * CAN driver system settings. + */ +#if USE_CAN1 +#define STM32_CAN_USE_CAN1 TRUE +#else +#define STM32_CAN_USE_CAN1 FALSE +#endif +#define STM32_CAN_CAN1_IRQ_PRIORITY 11 + +/* + * DAC driver system settings. + */ +#define STM32_DAC_DUAL_MODE FALSE +#define STM32_DAC_USE_DAC1_CH1 TRUE +#define STM32_DAC_USE_DAC1_CH2 TRUE +#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 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI20_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI21_22_29_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI30_32_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI33_IRQ_PRIORITY 6 + +/* + * 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_TIM6 FALSE +#define STM32_GPT_USE_TIM7 FALSE +#define STM32_GPT_USE_TIM8 FALSE +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM6_IRQ_PRIORITY 7 +#define STM32_GPT_TIM7_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 + +/* + * 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 +#define STM32_I2C_BUSY_TIMEOUT 50 +#define STM32_I2C_I2C1_IRQ_PRIORITY 10 +#define STM32_I2C_I2C2_IRQ_PRIORITY 10 +#define STM32_I2C_USE_DMA TRUE +#define STM32_I2C_I2C1_DMA_PRIORITY 1 +#define STM32_I2C_I2C2_DMA_PRIORITY 1 +#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_TIM8 FALSE +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_ADVANCED FALSE +#define STM32_PWM_USE_TIM1 FALSE +#ifndef STM32_PWM_USE_TIM2 +#define STM32_PWM_USE_TIM2 TRUE +#endif +#ifndef STM32_PWM_USE_TIM3 +#define STM32_PWM_USE_TIM3 TRUE +#endif +#define STM32_PWM_USE_TIM4 FALSE +#define STM32_PWM_USE_TIM8 FALSE +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 + +/* + * 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 +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 +#define STM32_SERIAL_UART4_PRIORITY 12 +#define STM32_SERIAL_UART5_PRIORITY 12 + +/* + * 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 +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_SPI3_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") + +/* + * ST driver system settings. + */ +#define STM32_ST_IRQ_PRIORITY 8 +#define STM32_ST_USE_TIMER 2 + +/* + * 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_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_USB1 TRUE +#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE +#define STM32_USB_USB1_HP_IRQ_PRIORITY 13 +#define STM32_USB_USB1_LP_IRQ_PRIORITY 14 + +/* + * WDG driver system settings. + */ +#define STM32_WDG_USE_IWDG FALSE + +#endif /* MCUCONF_H */ diff --git a/sw/airborne/boards/xvert/baro_board.h b/sw/airborne/boards/xvert/baro_board.h new file mode 100644 index 0000000000..ea4c31e05e --- /dev/null +++ b/sw/airborne/boards/xvert/baro_board.h @@ -0,0 +1,20 @@ + +/* + * board specific functions for the chimera board + * + */ + +#ifndef BOARDS_CHIMERA_BARO_H +#define BOARDS_CHIMERA_BARO_H + +// only for printing the baro type during compilation +#ifndef BARO_BOARD +#define BARO_BOARD BARO_MS5611_I2C +#endif + +#define BB_MS5611_TYPE_MS5607 TRUE + +extern void baro_event(void); +#define BaroEvent baro_event + +#endif /* BOARDS_CHIMERA_BARO_H */ diff --git a/sw/airborne/boards/xvert/chibios/v1.0/board.c b/sw/airborne/boards/xvert/chibios/v1.0/board.c new file mode 100644 index 0000000000..a4591f31aa --- /dev/null +++ b/sw/airborne/boards/xvert/chibios/v1.0/board.c @@ -0,0 +1,153 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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" + +#if HAL_USE_PAL || defined(__DOXYGEN__) +/** + * @brief PAL setup. + * @details Digital I/O ports static configuration as defined in @p board.h. + * This variable is used by the HAL when initializing the PAL driver. + */ +const PALConfig pal_default_config = { +#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 +}; +#endif + +/** + * @brief Early initialization code. + * @details This initialization must be performed just after stack setup + * and before any other initialization. + */ +void __early_init(void) +{ + + stm32_clock_init(); +} + +#if HAL_USE_SDC || defined(__DOXYGEN__) +/** + * @brief SDC card detection. + */ +bool sdc_lld_is_card_inserted(SDCDriver *sdcp) +{ + + (void)sdcp; + /* TODO: Fill the implementation.*/ + return true; +} + +/** + * @brief SDC card write protection detection. + */ +bool sdc_lld_is_write_protected(SDCDriver *sdcp) +{ + + (void)sdcp; + /* TODO: Fill the implementation.*/ + 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/xvert/chibios/v1.0/board.h b/sw/airborne/boards/xvert/chibios/v1.0/board.h new file mode 100644 index 0000000000..dc63f6c91a --- /dev/null +++ b/sw/airborne/boards/xvert/chibios/v1.0/board.h @@ -0,0 +1,1513 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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. + */ + +#ifndef BOARD_H +#define BOARD_H + +/* + * Setup for STMicroelectronics STM32373C-vortex board. + */ + +/* + * Board identifier. + */ +#define BOARD_ST_STM32373C_XVERT +#define BOARD_NAME "STMicroelectronics STM32373C-xvert" + +/* + * 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 16000000U +#endif + +/* + * MCU type as defined in the ST header. + */ +#define STM32F373xC + +/* + * IO pins assignments. + */ +#define GPIOA_PIN0 0U +#define GPIOA_ADC_VDD 1U +#define GPIOA_UART2TX 2U +#define GPIOA_UART2RX 3U +#define GPIOA_PIN4 4U +#define GPIOA_ADC1 5U +#define GPIOA_ADC2 6U +#define GPIOA_PIN7 7U +#define GPIOA_LED_RED 8U +#define GPIOA_UART1TX 9U +#define GPIOA_UART1RX 10U +#define GPIOA_PWM_PIN11 11U +#define GPIOA_PWM_PIN12 12U +#define GPIOA_SWD 13U +#define GPIOA_SWCLK 14U +#define GPIOA_PIN15 15U + +#define GPIOB_MIC_IN 0U +#define GPIOB_ADC_POT_IN 1U +#define GPIOB_PIN2 2U +#define GPIOB_SWO 3U +#define GPIOB_JTRST 4U +#define GPIOB_PIN5 5U +#define GPIOB_I2C1_SCL 6U +#define GPIOB_I2C1_SDA 7U +#define GPIOB_PIN8 8U +#define GPIOB_PIN9 9U +#define GPIOB_PIN10 10U +#define GPIOB_PIN11 11U +#define GPIOB_PIN12 12U +#define GPIOB_PIN13 13U +#define GPIOB_PIN14 14U +#define GPIOB_PIN15 15U + +#define GPIOC_LED1 0U +#define GPIOC_LED2 1U +#define GPIOC_LED3 2U +#define GPIOC_LED4 3U +#define GPIOC_PIN4 4U +#define GPIOC_USB_DISCONNECT 5U +#define GPIOC_PIN6 6U +#define GPIOC_PIN7 7U +#define GPIOC_PIN8 8U +#define GPIOC_PIN9 9U +#define GPIOC_PIN10 10U +#define GPIOC_PIN11 11U +#define GPIOC_PIN12 12U +#define GPIOC_PIN13 13U +#define GPIOC_OSC32_IN 14U +#define GPIOC_OSC32_OUT 15U + +#define GPIOD_CAN_RX 0U +#define GPIOD_CAN_TX 1U +#define GPIOD_LCD_CS 2U +#define GPIOD_USART2_CTS 3U +#define GPIOD_USART2_RST 4U +#define GPIOD_USART2_TX 5U +#define GPIOD_USART2_RX 6U +#define GPIOD_PIN7 7U +#define GPIOD_LED_GREEN 8U +#define GPIOD_PIN9 9U +#define GPIOD_PIN10 10U +#define GPIOD_AUDIO_RST 11U +#define GPIOD_PIN12 12U +#define GPIOD_PIN13 13U +#define GPIOD_PIN14 14U +#define GPIOD_PIN15 15U + +#define GPIOE_PIN0 0U +#define GPIOE_PIN1 1U +#define GPIOE_SD_CS 2U +#define GPIOE_SD_DETECT 3U +#define GPIOE_PIN4 4U +#define GPIOE_PIN5 5U +#define GPIOE_JOY_SEL 6U +#define GPIOE_RTD_IN 7U +#define GPIOE_PRESSUREP 8U +#define GPIOE_PRESSUREN 9U +#define GPIOE_PIN10 10U +#define GPIOE_PIN11 11U +#define GPIOE_PIN12 12U +#define GPIOE_PIN13 13U +#define GPIOE_PRESSURE_TEPM 14U +#define GPIOE_PIN15 15U + +#define GPIOF_OSC_IN 0U +#define GPIOF_OSC_OUT 1U +#define GPIOF_JOY_DOWN 2U +#define GPIOF_PIN3 3U +#define GPIOF_JOY_LEFT 4U +#define GPIOF_PIN5 5U +#define GPIOF_I2C2_SCL 6U +#define GPIOF_I2C2_SDA 7U +#define GPIOF_PIN8 8U +#define GPIOF_JOY_RIGHT 9U +#define GPIOF_JOY_UP 10U +#define GPIOF_PIN11 11U +#define GPIOF_PIN12 12U +#define GPIOF_PIN13 13U +#define GPIOF_PIN14 14U +#define GPIOF_PIN15 15U + +#define GPIOG_PIN0 0U +#define GPIOG_PIN1 1U +#define GPIOG_PIN2 2U +#define GPIOG_PIN3 3U +#define GPIOG_PIN4 4U +#define GPIOG_PIN5 5U +#define GPIOG_PIN6 6U +#define GPIOG_PIN7 7U +#define GPIOG_PIN8 8U +#define GPIOG_PIN9 9U +#define GPIOG_PIN10 10U +#define GPIOG_PIN11 11U +#define GPIOG_PIN12 12U +#define GPIOG_PIN13 13U +#define GPIOG_PIN14 14U +#define GPIOG_PIN15 15U + +#define GPIOH_PIN0 0U +#define GPIOH_PIN1 1U +#define GPIOH_PIN2 2U +#define GPIOH_PIN3 3U +#define GPIOH_PIN4 4U +#define GPIOH_PIN5 5U +#define GPIOH_PIN6 6U +#define GPIOH_PIN7 7U +#define GPIOH_PIN8 8U +#define GPIOH_PIN9 9U +#define GPIOH_PIN10 10U +#define GPIOH_PIN11 11U +#define GPIOH_PIN12 12U +#define GPIOH_PIN13 13U +#define GPIOH_PIN14 14U +#define GPIOH_PIN15 15U + +/* + * IO lines assignments. + */ +//#define LINE_WKUP_BUTTON PAL_LINE(GPIOA, 0U) +//#define LINE_LDR_OUT PAL_LINE(GPIOA, 1U) +//#define LINE_KEY_BUTTON PAL_LINE(GPIOA, 2U) +//#define LINE_COMP2_OUT PAL_LINE(GPIOA, 7U) +//#define LINE_I2C2_SMB PAL_LINE(GPIOA, 8U) +//#define LINE_I2C2_SCL PAL_LINE(GPIOA, 9U) +//#define LINE_I2C2_SDA 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_JTDI PAL_LINE(GPIOA, 15U) + +//#define LINE_MIC_IN PAL_LINE(GPIOB, 0U) +//#define LINE_ADC_POT_IN PAL_LINE(GPIOB, 1U) +//#define LINE_SWO PAL_LINE(GPIOB, 3U) +//#define LINE_JTRST PAL_LINE(GPIOB, 4U) +//#define LINE_I2C1_SCL PAL_LINE(GPIOB, 6U) +//#define LINE_I2C1_SDA PAL_LINE(GPIOB, 7U) + +//#define LINE_LED1 PAL_LINE(GPIOC, 0U) +//#define LINE_LED2 PAL_LINE(GPIOC, 1U) +//#define LINE_LED3 PAL_LINE(GPIOC, 2U) +//#define LINE_LED4 PAL_LINE(GPIOC, 3U) +//#define LINE_USB_DISCONNECT PAL_LINE(GPIOC, 5U) +//#define LINE_SPI3_SCK PAL_LINE(GPIOC, 10U) +//#define LINE_SPI3_MISO PAL_LINE(GPIOC, 11U) +//#define LINE_SPI3_MOSI PAL_LINE(GPIOC, 12U) +//#define LINE_OSC32_IN PAL_LINE(GPIOC, 14U) +//#define LINE_OSC32_OUT PAL_LINE(GPIOC, 15U) + +//#define LINE_CAN_RX PAL_LINE(GPIOD, 0U) +//#define LINE_CAN_TX PAL_LINE(GPIOD, 1U) +//#define LINE_LCD_CS PAL_LINE(GPIOD, 2U) +//#define LINE_USART2_CTS PAL_LINE(GPIOD, 3U) +//#define LINE_USART2_RST PAL_LINE(GPIOD, 4U) +//#define LINE_USART2_TX PAL_LINE(GPIOD, 5U) +//#define LINE_USART2_RX PAL_LINE(GPIOD, 6U) +//#define LINE_AUDIO_RST PAL_LINE(GPIOD, 11U) + +//#define LINE_SD_CS PAL_LINE(GPIOE, 2U) +//#define LINE_SD_DETECT PAL_LINE(GPIOE, 3U) +//#define LINE_JOY_SEL PAL_LINE(GPIOE, 6U) +//#define LINE_RTD_IN PAL_LINE(GPIOE, 7U) +//#define LINE_PRESSUREP PAL_LINE(GPIOE, 8U) +//#define LINE_PRESSUREN PAL_LINE(GPIOE, 9U) +//#define LINE_PRESSURE_TEPM PAL_LINE(GPIOE, 14U) + +//#define LINE_OSC_IN PAL_LINE(GPIOF, 0U) +//#define LINE_OSC_OUT PAL_LINE(GPIOF, 1U) +//#define LINE_JOY_DOWN PAL_LINE(GPIOF, 2U) +//#define LINE_JOY_LEFT PAL_LINE(GPIOF, 4U) +//#define LINE_JOY_RIGHT PAL_LINE(GPIOF, 9U) +//#define LINE_JOY_UP PAL_LINE(GPIOF, 10U) + +/* + * 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_LOW(n) (0U << (n)) +#define PIN_ODR_HIGH(n) (1U << (n)) +#define PIN_OTYPE_PUSHPULL(n) (0U << (n)) +#define PIN_OTYPE_OPENDRAIN(n) (1U << (n)) +#define PIN_OSPEED_VERYLOW(n) (0U << ((n) * 2U)) +#define PIN_OSPEED_LOW(n) (1U << ((n) * 2U)) +#define PIN_OSPEED_MEDIUM(n) (2U << ((n) * 2U)) +#define PIN_OSPEED_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_INPUT(GPIOA_PIN0) | \ + PIN_MODE_ANALOG(GPIOA_ADC_VDD) | \ + PIN_MODE_ALTERNATE(GPIOA_UART2TX) | \ + PIN_MODE_ALTERNATE(GPIOA_UART2RX) | \ + PIN_MODE_INPUT(GPIOA_PIN4) | \ + PIN_MODE_ANALOG(GPIOA_ADC1) | \ + PIN_MODE_ANALOG(GPIOA_ADC2) | \ + PIN_MODE_OUTPUT(GPIOA_PIN7) | \ + PIN_MODE_OUTPUT(GPIOA_LED_RED) | \ + PIN_MODE_ALTERNATE(GPIOA_UART1TX) | \ + PIN_MODE_ALTERNATE(GPIOA_UART1RX) | \ + PIN_MODE_INPUT(GPIOA_PWM_PIN11) | \ + PIN_MODE_INPUT(GPIOA_PWM_PIN12) | \ + PIN_MODE_ALTERNATE(GPIOA_SWD) | \ + PIN_MODE_ALTERNATE(GPIOA_SWCLK) | \ + PIN_MODE_INPUT(GPIOA_PIN15)) + +#define VAL_GPIOA_OTYPER (PIN_OTYPE_PUSHPULL(GPIOA_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOA_ADC_VDD) | \ + PIN_OTYPE_PUSHPULL(GPIOA_UART2TX) | \ + PIN_OTYPE_PUSHPULL(GPIOA_UART2RX) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOA_ADC1) | \ + PIN_OTYPE_PUSHPULL(GPIOA_ADC2) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOA_LED_RED) | \ + PIN_OTYPE_PUSHPULL(GPIOA_UART1TX) | \ + PIN_OTYPE_PUSHPULL(GPIOA_UART1RX) | \ + PIN_OTYPE_OPENDRAIN(GPIOA_PWM_PIN11) | \ + PIN_OTYPE_OPENDRAIN(GPIOA_PWM_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SWD) | \ + PIN_OTYPE_PUSHPULL(GPIOA_SWCLK) | \ + PIN_OTYPE_PUSHPULL(GPIOA_PIN15)) + +#define VAL_GPIOA_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOA_PIN0) |\ + PIN_OSPEED_VERYLOW(GPIOA_ADC_VDD) | \ + PIN_OSPEED_HIGH(GPIOA_UART2TX) | \ + PIN_OSPEED_HIGH(GPIOA_UART2RX) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOA_ADC1) | \ + PIN_OSPEED_VERYLOW(GPIOA_ADC2) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOA_LED_RED) | \ + PIN_OSPEED_HIGH(GPIOA_UART1TX) | \ + PIN_OSPEED_HIGH(GPIOA_UART1RX) | \ + PIN_OSPEED_VERYLOW(GPIOA_PWM_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOA_PWM_PIN12) | \ + PIN_OSPEED_HIGH(GPIOA_SWD) | \ + PIN_OSPEED_HIGH(GPIOA_SWCLK) | \ + PIN_OSPEED_VERYLOW(GPIOA_PIN15)) + +#define VAL_GPIOA_PUPDR (PIN_PUPDR_FLOATING(GPIOA_PIN0) |\ + PIN_PUPDR_FLOATING(GPIOA_ADC_VDD) | \ + PIN_PUPDR_FLOATING(GPIOA_UART2TX) | \ + PIN_PUPDR_FLOATING(GPIOA_UART2RX) | \ + PIN_PUPDR_PULLUP(GPIOA_PIN4) | \ + PIN_PUPDR_FLOATING(GPIOA_ADC1) | \ + PIN_PUPDR_FLOATING(GPIOA_ADC2) | \ + PIN_PUPDR_FLOATING(GPIOA_PIN7) | \ + PIN_PUPDR_FLOATING(GPIOA_LED_RED) | \ + PIN_PUPDR_FLOATING(GPIOA_UART1TX) | \ + PIN_PUPDR_FLOATING(GPIOA_UART1RX) | \ + PIN_PUPDR_PULLDOWN(GPIOA_PWM_PIN11) | \ + PIN_PUPDR_PULLDOWN(GPIOA_PWM_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOA_SWD) | \ + PIN_PUPDR_PULLDOWN(GPIOA_SWCLK) | \ + PIN_PUPDR_FLOATING(GPIOA_PIN15)) +#define VAL_GPIOA_ODR (PIN_ODR_HIGH(GPIOA_PIN0) | \ + PIN_ODR_HIGH(GPIOA_ADC_VDD) | \ + PIN_ODR_HIGH(GPIOA_UART2TX) | \ + PIN_ODR_HIGH(GPIOA_UART2RX) | \ + PIN_ODR_HIGH(GPIOA_PIN4) | \ + PIN_ODR_HIGH(GPIOA_ADC1) | \ + PIN_ODR_HIGH(GPIOA_ADC2) | \ + PIN_ODR_LOW(GPIOA_PIN7) | \ + PIN_ODR_HIGH(GPIOA_LED_RED) | \ + PIN_ODR_HIGH(GPIOA_UART1TX) | \ + PIN_ODR_HIGH(GPIOA_UART1RX) | \ + PIN_ODR_HIGH(GPIOA_PWM_PIN11) | \ + PIN_ODR_HIGH(GPIOA_PWM_PIN12) | \ + PIN_ODR_HIGH(GPIOA_SWD) | \ + PIN_ODR_HIGH(GPIOA_SWCLK) | \ + PIN_ODR_HIGH(GPIOA_PIN15)) +#define VAL_GPIOA_AFRL (PIN_AFIO_AF(GPIOA_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOA_ADC_VDD, 0U) | \ + PIN_AFIO_AF(GPIOA_UART2TX, 7U) | \ + PIN_AFIO_AF(GPIOA_UART2RX, 7U) | \ + PIN_AFIO_AF(GPIOA_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOA_ADC1, 0U) | \ + PIN_AFIO_AF(GPIOA_ADC2, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN7, 0U)) +#define VAL_GPIOA_AFRH (PIN_AFIO_AF(GPIOA_LED_RED, 0U) | \ + PIN_AFIO_AF(GPIOA_UART1TX, 7U) | \ + PIN_AFIO_AF(GPIOA_UART1RX, 7U) | \ + PIN_AFIO_AF(GPIOA_PWM_PIN11, 2U) | \ + PIN_AFIO_AF(GPIOA_PWM_PIN12, 2U) | \ + PIN_AFIO_AF(GPIOA_SWD, 0U) | \ + PIN_AFIO_AF(GPIOA_SWCLK, 0U) | \ + PIN_AFIO_AF(GPIOA_PIN15, 0U)) + +/* + * GPIOB setup: + * + * PB0 - MIC_IN (analog). + * PB1 - ADC_POT_IN (analog). + * PB2 - PIN2 (input pullup). + * PB3 - SWO (alternate 0). + * PB4 - JTRST (input floating). + * PB5 - PIN5 (input pullup). + * PB6 - I2C1_SCL (alternate 4). + * PB7 - I2C1_SDA (alternate 4). + * PB8 - PIN8 (input pullup). + * PB9 - PIN9 (input pullup). + * PB10 - PIN10 (input pullup). + * PB11 - PIN11 (input pullup). + * PB12 - PIN12 (input pullup). + * PB13 - PIN13 (input pullup). + * PB14 - PIN14 (input pullup). + * PB15 - PIN15 (input pullup). + */ +#define VAL_GPIOB_MODER (PIN_MODE_ANALOG(GPIOB_MIC_IN) | \ + PIN_MODE_ANALOG(GPIOB_ADC_POT_IN) | \ + PIN_MODE_INPUT(GPIOB_PIN2) | \ + PIN_MODE_ALTERNATE(GPIOB_SWO) | \ + PIN_MODE_INPUT(GPIOB_JTRST) | \ + PIN_MODE_INPUT(GPIOB_PIN5) | \ + PIN_MODE_ALTERNATE(GPIOB_I2C1_SCL) | \ + PIN_MODE_ALTERNATE(GPIOB_I2C1_SDA) | \ + PIN_MODE_INPUT(GPIOB_PIN8) | \ + PIN_MODE_INPUT(GPIOB_PIN9) | \ + PIN_MODE_INPUT(GPIOB_PIN10) | \ + PIN_MODE_INPUT(GPIOB_PIN11) | \ + PIN_MODE_INPUT(GPIOB_PIN12) | \ + PIN_MODE_INPUT(GPIOB_PIN13) | \ + PIN_MODE_INPUT(GPIOB_PIN14) | \ + PIN_MODE_INPUT(GPIOB_PIN15)) +#define VAL_GPIOB_OTYPER (PIN_OTYPE_PUSHPULL(GPIOB_MIC_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOB_ADC_POT_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOB_SWO) | \ + PIN_OTYPE_PUSHPULL(GPIOB_JTRST) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN5) | \ + PIN_OTYPE_OPENDRAIN(GPIOB_I2C1_SCL) | \ + PIN_OTYPE_OPENDRAIN(GPIOB_I2C1_SDA) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOB_PIN15)) +#define VAL_GPIOB_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOB_MIC_IN) | \ + PIN_OSPEED_VERYLOW(GPIOB_ADC_POT_IN) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN2) | \ + PIN_OSPEED_HIGH(GPIOB_SWO) | \ + PIN_OSPEED_HIGH(GPIOB_JTRST) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN5) | \ + PIN_OSPEED_HIGH(GPIOB_I2C1_SCL) | \ + PIN_OSPEED_HIGH(GPIOB_I2C1_SDA) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOB_PIN15)) +#define VAL_GPIOB_PUPDR (PIN_PUPDR_FLOATING(GPIOB_MIC_IN) | \ + PIN_PUPDR_FLOATING(GPIOB_ADC_POT_IN) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN2) | \ + PIN_PUPDR_FLOATING(GPIOB_SWO) | \ + PIN_PUPDR_FLOATING(GPIOB_JTRST) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN5) | \ + PIN_PUPDR_FLOATING(GPIOB_I2C1_SCL) | \ + PIN_PUPDR_FLOATING(GPIOB_I2C1_SDA) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOB_PIN15)) +#define VAL_GPIOB_ODR (PIN_ODR_HIGH(GPIOB_MIC_IN) | \ + PIN_ODR_HIGH(GPIOB_ADC_POT_IN) | \ + PIN_ODR_HIGH(GPIOB_PIN2) | \ + PIN_ODR_HIGH(GPIOB_SWO) | \ + PIN_ODR_HIGH(GPIOB_JTRST) | \ + PIN_ODR_HIGH(GPIOB_PIN5) | \ + PIN_ODR_HIGH(GPIOB_I2C1_SCL) | \ + PIN_ODR_HIGH(GPIOB_I2C1_SDA) | \ + PIN_ODR_HIGH(GPIOB_PIN8) | \ + PIN_ODR_HIGH(GPIOB_PIN9) | \ + PIN_ODR_HIGH(GPIOB_PIN10) | \ + PIN_ODR_HIGH(GPIOB_PIN11) | \ + PIN_ODR_HIGH(GPIOB_PIN12) | \ + PIN_ODR_HIGH(GPIOB_PIN13) | \ + PIN_ODR_HIGH(GPIOB_PIN14) | \ + PIN_ODR_HIGH(GPIOB_PIN15)) +#define VAL_GPIOB_AFRL (PIN_AFIO_AF(GPIOB_MIC_IN, 0U) | \ + PIN_AFIO_AF(GPIOB_ADC_POT_IN, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOB_SWO, 0U) | \ + PIN_AFIO_AF(GPIOB_JTRST, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOB_I2C1_SCL, 4U) | \ + PIN_AFIO_AF(GPIOB_I2C1_SDA, 4U)) +#define VAL_GPIOB_AFRH (PIN_AFIO_AF(GPIOB_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOB_PIN15, 0U)) + +/* + * GPIOC setup: + * + * PC0 - LED1 (output opendrain maximum). + * PC1 - LED2 (output opendrain maximum). + * PC2 - LED3 (output opendrain maximum). + * PC3 - LED4 (output opendrain maximum). + * PC4 - PIN4 (input pullup). + * PC5 - USB_DISCONNECT (output pushpull maximum). + * PC6 - PIN6 (input pullup). + * PC7 - PIN7 (input pullup). + * PC8 - PIN8 (input pullup). + * PC9 - PIN9 (input pullup). + * PC10 - SPI3_SCK (alternate 6). + * PC11 - SPI3_MISO (alternate 6). + * PC12 - SPI3_MOSI (alternate 6). + * PC13 - PIN13 (input pullup). + * PC14 - OSC32_IN (input floating). + * PC15 - OSC32_OUT (input floating). + */ +#define VAL_GPIOC_MODER (PIN_MODE_OUTPUT(GPIOC_LED1) | \ + PIN_MODE_OUTPUT(GPIOC_LED2) | \ + PIN_MODE_OUTPUT(GPIOC_LED3) | \ + PIN_MODE_OUTPUT(GPIOC_LED4) | \ + PIN_MODE_INPUT(GPIOC_PIN4) | \ + PIN_MODE_OUTPUT(GPIOC_USB_DISCONNECT) |\ + PIN_MODE_INPUT(GPIOC_PIN6) | \ + PIN_MODE_INPUT(GPIOC_PIN7) | \ + PIN_MODE_INPUT(GPIOC_PIN8) | \ + PIN_MODE_INPUT(GPIOC_PIN9) | \ + PIN_MODE_INPUT(GPIOC_PIN10) | \ + PIN_MODE_INPUT(GPIOC_PIN11) | \ + PIN_MODE_INPUT(GPIOC_PIN12) | \ + PIN_MODE_INPUT(GPIOC_PIN13) | \ + PIN_MODE_INPUT(GPIOC_OSC32_IN) | \ + PIN_MODE_INPUT(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_OTYPER (PIN_OTYPE_OPENDRAIN(GPIOC_LED1) | \ + PIN_OTYPE_OPENDRAIN(GPIOC_LED2) | \ + PIN_OTYPE_OPENDRAIN(GPIOC_LED3) | \ + PIN_OTYPE_OPENDRAIN(GPIOC_LED4) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOC_USB_DISCONNECT) |\ + PIN_OTYPE_PUSHPULL(GPIOC_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOC_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOC_OSC32_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_OSPEEDR (PIN_OSPEED_HIGH(GPIOC_LED1) | \ + PIN_OSPEED_HIGH(GPIOC_LED2) | \ + PIN_OSPEED_HIGH(GPIOC_LED3) | \ + PIN_OSPEED_HIGH(GPIOC_LED4) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN4) | \ + PIN_OSPEED_HIGH(GPIOC_USB_DISCONNECT) |\ + PIN_OSPEED_VERYLOW(GPIOC_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOC_PIN13) | \ + PIN_OSPEED_HIGH(GPIOC_OSC32_IN) | \ + PIN_OSPEED_HIGH(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_PUPDR (PIN_PUPDR_FLOATING(GPIOC_LED1) | \ + PIN_PUPDR_FLOATING(GPIOC_LED2) | \ + PIN_PUPDR_FLOATING(GPIOC_LED3) | \ + PIN_PUPDR_FLOATING(GPIOC_LED4) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN4) | \ + PIN_PUPDR_FLOATING(GPIOC_USB_DISCONNECT) |\ + PIN_PUPDR_PULLUP(GPIOC_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOC_PIN13) | \ + PIN_PUPDR_FLOATING(GPIOC_OSC32_IN) | \ + PIN_PUPDR_FLOATING(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_ODR (PIN_ODR_HIGH(GPIOC_LED1) | \ + PIN_ODR_HIGH(GPIOC_LED2) | \ + PIN_ODR_HIGH(GPIOC_LED3) | \ + PIN_ODR_HIGH(GPIOC_LED4) | \ + PIN_ODR_HIGH(GPIOC_PIN4) | \ + PIN_ODR_HIGH(GPIOC_USB_DISCONNECT) | \ + PIN_ODR_HIGH(GPIOC_PIN6) | \ + PIN_ODR_HIGH(GPIOC_PIN7) | \ + PIN_ODR_HIGH(GPIOC_PIN8) | \ + PIN_ODR_HIGH(GPIOC_PIN9) | \ + PIN_ODR_HIGH(GPIOC_PIN10) | \ + PIN_ODR_HIGH(GPIOC_PIN11) | \ + PIN_ODR_HIGH(GPIOC_PIN12) | \ + PIN_ODR_HIGH(GPIOC_PIN13) | \ + PIN_ODR_HIGH(GPIOC_OSC32_IN) | \ + PIN_ODR_HIGH(GPIOC_OSC32_OUT)) +#define VAL_GPIOC_AFRL (PIN_AFIO_AF(GPIOC_LED1, 0U) | \ + PIN_AFIO_AF(GPIOC_LED2, 0U) | \ + PIN_AFIO_AF(GPIOC_LED3, 0U) | \ + PIN_AFIO_AF(GPIOC_LED4, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOC_USB_DISCONNECT, 0U) |\ + PIN_AFIO_AF(GPIOC_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN7, 0U)) +#define VAL_GPIOC_AFRH (PIN_AFIO_AF(GPIOC_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOC_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOC_OSC32_IN, 0U) | \ + PIN_AFIO_AF(GPIOC_OSC32_OUT, 0U)) + +/* + * GPIOD setup: + * + * PD0 - CAN_RX (alternate 7). + * PD1 - CAN_TX (alternate 7). + * PD2 - LCD_CS (output pushpull maximum). + * PD3 - USART2_CTS (alternate 7). + * PD4 - USART2_RST (alternate 7). + * PD5 - USART2_TX (alternate 7). + * PD6 - USART2_RX (alternate 7). + * PD7 - PIN7 (input pullup). + * PD8 - PIN8 (input pullup). + * PD9 - PIN9 (input pullup). + * PD10 - PIN10 (input pullup). + * PD11 - AUDIO_RST (output pushpull maximum). + * PD12 - PIN12 (input pullup). + * PD13 - PIN13 (input pullup). + * PD14 - PIN14 (input pullup). + * PD15 - PIN15 (input pullup). + */ +#define VAL_GPIOD_MODER (PIN_MODE_ALTERNATE(GPIOD_CAN_RX) | \ + PIN_MODE_ALTERNATE(GPIOD_CAN_TX) | \ + PIN_MODE_OUTPUT(GPIOD_LCD_CS) | \ + PIN_MODE_ALTERNATE(GPIOD_USART2_CTS) | \ + PIN_MODE_ALTERNATE(GPIOD_USART2_RST) | \ + PIN_MODE_ALTERNATE(GPIOD_USART2_TX) | \ + PIN_MODE_ALTERNATE(GPIOD_USART2_RX) | \ + PIN_MODE_INPUT(GPIOD_PIN7) | \ + PIN_MODE_OUTPUT(GPIOD_LED_GREEN) | \ + PIN_MODE_INPUT(GPIOD_PIN9) | \ + PIN_MODE_INPUT(GPIOD_PIN10) | \ + PIN_MODE_OUTPUT(GPIOD_AUDIO_RST) | \ + PIN_MODE_INPUT(GPIOD_PIN12) | \ + PIN_MODE_INPUT(GPIOD_PIN13) | \ + PIN_MODE_INPUT(GPIOD_PIN14) | \ + PIN_MODE_INPUT(GPIOD_PIN15)) +#define VAL_GPIOD_OTYPER (PIN_OTYPE_PUSHPULL(GPIOD_CAN_RX) | \ + PIN_OTYPE_PUSHPULL(GPIOD_CAN_TX) | \ + PIN_OTYPE_PUSHPULL(GPIOD_LCD_CS) | \ + PIN_OTYPE_PUSHPULL(GPIOD_USART2_CTS) | \ + PIN_OTYPE_PUSHPULL(GPIOD_USART2_RST) | \ + PIN_OTYPE_PUSHPULL(GPIOD_USART2_TX) | \ + PIN_OTYPE_PUSHPULL(GPIOD_USART2_RX) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOD_LED_GREEN) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOD_AUDIO_RST) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOD_PIN15)) +#define VAL_GPIOD_OSPEEDR (PIN_OSPEED_HIGH(GPIOD_CAN_RX) | \ + PIN_OSPEED_HIGH(GPIOD_CAN_TX) | \ + PIN_OSPEED_HIGH(GPIOD_LCD_CS) | \ + PIN_OSPEED_HIGH(GPIOD_USART2_CTS) | \ + PIN_OSPEED_HIGH(GPIOD_USART2_RST) | \ + PIN_OSPEED_HIGH(GPIOD_USART2_TX) | \ + PIN_OSPEED_HIGH(GPIOD_USART2_RX) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOD_LED_GREEN) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN10) | \ + PIN_OSPEED_HIGH(GPIOD_AUDIO_RST) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOD_PIN15)) +#define VAL_GPIOD_PUPDR (PIN_PUPDR_FLOATING(GPIOD_CAN_RX) | \ + PIN_PUPDR_FLOATING(GPIOD_CAN_TX) | \ + PIN_PUPDR_FLOATING(GPIOD_LCD_CS) | \ + PIN_PUPDR_FLOATING(GPIOD_USART2_CTS) | \ + PIN_PUPDR_FLOATING(GPIOD_USART2_RST) | \ + PIN_PUPDR_FLOATING(GPIOD_USART2_TX) | \ + PIN_PUPDR_FLOATING(GPIOD_USART2_RX) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOD_LED_GREEN) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN10) | \ + PIN_PUPDR_FLOATING(GPIOD_AUDIO_RST) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOD_PIN15)) +#define VAL_GPIOD_ODR (PIN_ODR_HIGH(GPIOD_CAN_RX) | \ + PIN_ODR_HIGH(GPIOD_CAN_TX) | \ + PIN_ODR_HIGH(GPIOD_LCD_CS) | \ + PIN_ODR_HIGH(GPIOD_USART2_CTS) | \ + PIN_ODR_HIGH(GPIOD_USART2_RST) | \ + PIN_ODR_HIGH(GPIOD_USART2_TX) | \ + PIN_ODR_HIGH(GPIOD_USART2_RX) | \ + PIN_ODR_HIGH(GPIOD_PIN7) | \ + PIN_ODR_HIGH(GPIOD_LED_GREEN) | \ + PIN_ODR_HIGH(GPIOD_PIN9) | \ + PIN_ODR_HIGH(GPIOD_PIN10) | \ + PIN_ODR_LOW(GPIOD_AUDIO_RST) | \ + PIN_ODR_HIGH(GPIOD_PIN12) | \ + PIN_ODR_HIGH(GPIOD_PIN13) | \ + PIN_ODR_HIGH(GPIOD_PIN14) | \ + PIN_ODR_HIGH(GPIOD_PIN15)) +#define VAL_GPIOD_AFRL (PIN_AFIO_AF(GPIOD_CAN_RX, 7U) | \ + PIN_AFIO_AF(GPIOD_CAN_TX, 7U) | \ + PIN_AFIO_AF(GPIOD_LCD_CS, 0U) | \ + PIN_AFIO_AF(GPIOD_USART2_CTS, 7U) | \ + PIN_AFIO_AF(GPIOD_USART2_RST, 7U) | \ + PIN_AFIO_AF(GPIOD_USART2_TX, 7U) | \ + PIN_AFIO_AF(GPIOD_USART2_RX, 7U) | \ + PIN_AFIO_AF(GPIOD_PIN7, 0U)) +#define VAL_GPIOD_AFRH (PIN_AFIO_AF(GPIOD_LED_GREEN, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOD_AUDIO_RST, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOD_PIN15, 0U)) + +/* + * GPIOE setup: + * + * PE0 - PIN0 (input pullup). + * PE1 - PIN1 (input pullup). + * PE2 - SD_CS (output opendrain maximum). + * PE3 - SD_DETECT (input pullup). + * PE4 - PIN4 (input pullup). + * PE5 - PIN5 (input pullup). + * PE6 - JOY_SEL (input pulldown). + * PE7 - RTD_IN (analog). + * PE8 - PRESSUREP (analog). + * PE9 - PRESSUREN (analog). + * PE10 - PIN10 (input pullup). + * PE11 - PIN11 (input pullup). + * PE12 - PIN12 (input pullup). + * PE13 - PIN13 (input pullup). + * PE14 - PRESSURE_TEPM (input floating). + * PE15 - PIN15 (input pullup). + */ +#define VAL_GPIOE_MODER (PIN_MODE_INPUT(GPIOE_PIN0) | \ + PIN_MODE_INPUT(GPIOE_PIN1) | \ + PIN_MODE_OUTPUT(GPIOE_SD_CS) | \ + PIN_MODE_INPUT(GPIOE_SD_DETECT) | \ + PIN_MODE_INPUT(GPIOE_PIN4) | \ + PIN_MODE_INPUT(GPIOE_PIN5) | \ + PIN_MODE_INPUT(GPIOE_JOY_SEL) | \ + PIN_MODE_ANALOG(GPIOE_RTD_IN) | \ + PIN_MODE_ANALOG(GPIOE_PRESSUREP) | \ + PIN_MODE_ANALOG(GPIOE_PRESSUREN) | \ + PIN_MODE_INPUT(GPIOE_PIN10) | \ + PIN_MODE_INPUT(GPIOE_PIN11) | \ + PIN_MODE_INPUT(GPIOE_PIN12) | \ + PIN_MODE_INPUT(GPIOE_PIN13) | \ + PIN_MODE_INPUT(GPIOE_PRESSURE_TEPM) | \ + PIN_MODE_INPUT(GPIOE_PIN15)) +#define VAL_GPIOE_OTYPER (PIN_OTYPE_PUSHPULL(GPIOE_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN1) | \ + PIN_OTYPE_OPENDRAIN(GPIOE_SD_CS) | \ + PIN_OTYPE_PUSHPULL(GPIOE_SD_DETECT) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOE_JOY_SEL) | \ + PIN_OTYPE_PUSHPULL(GPIOE_RTD_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PRESSUREP) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PRESSUREN) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOE_PRESSURE_TEPM) |\ + PIN_OTYPE_PUSHPULL(GPIOE_PIN15)) +#define VAL_GPIOE_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOE_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN1) | \ + PIN_OSPEED_HIGH(GPIOE_SD_CS) | \ + PIN_OSPEED_HIGH(GPIOE_SD_DETECT) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN5) | \ + PIN_OSPEED_HIGH(GPIOE_JOY_SEL) | \ + PIN_OSPEED_VERYLOW(GPIOE_RTD_IN) | \ + PIN_OSPEED_HIGH(GPIOE_PRESSUREP) | \ + PIN_OSPEED_HIGH(GPIOE_PRESSUREN) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOE_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOE_PRESSURE_TEPM) |\ + PIN_OSPEED_VERYLOW(GPIOE_PIN15)) +#define VAL_GPIOE_PUPDR (PIN_PUPDR_PULLUP(GPIOE_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN1) | \ + PIN_PUPDR_FLOATING(GPIOE_SD_CS) | \ + PIN_PUPDR_PULLUP(GPIOE_SD_DETECT) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN5) | \ + PIN_PUPDR_PULLDOWN(GPIOE_JOY_SEL) | \ + PIN_PUPDR_FLOATING(GPIOE_RTD_IN) | \ + PIN_PUPDR_FLOATING(GPIOE_PRESSUREP) | \ + PIN_PUPDR_FLOATING(GPIOE_PRESSUREN) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOE_PIN13) | \ + PIN_PUPDR_FLOATING(GPIOE_PRESSURE_TEPM) |\ + PIN_PUPDR_PULLUP(GPIOE_PIN15)) +#define VAL_GPIOE_ODR (PIN_ODR_HIGH(GPIOE_PIN0) | \ + PIN_ODR_HIGH(GPIOE_PIN1) | \ + PIN_ODR_HIGH(GPIOE_SD_CS) | \ + PIN_ODR_HIGH(GPIOE_SD_DETECT) | \ + PIN_ODR_HIGH(GPIOE_PIN4) | \ + PIN_ODR_HIGH(GPIOE_PIN5) | \ + PIN_ODR_HIGH(GPIOE_JOY_SEL) | \ + PIN_ODR_HIGH(GPIOE_RTD_IN) | \ + PIN_ODR_HIGH(GPIOE_PRESSUREP) | \ + PIN_ODR_HIGH(GPIOE_PRESSUREN) | \ + PIN_ODR_HIGH(GPIOE_PIN10) | \ + PIN_ODR_HIGH(GPIOE_PIN11) | \ + PIN_ODR_HIGH(GPIOE_PIN12) | \ + PIN_ODR_LOW(GPIOE_PIN13) | \ + PIN_ODR_LOW(GPIOE_PRESSURE_TEPM) | \ + PIN_ODR_LOW(GPIOE_PIN15)) +#define VAL_GPIOE_AFRL (PIN_AFIO_AF(GPIOE_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOE_SD_CS, 0U) | \ + PIN_AFIO_AF(GPIOE_SD_DETECT, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOE_JOY_SEL, 0U) | \ + PIN_AFIO_AF(GPIOE_RTD_IN, 0U)) +#define VAL_GPIOE_AFRH (PIN_AFIO_AF(GPIOE_PRESSUREP, 0U) | \ + PIN_AFIO_AF(GPIOE_PRESSUREN, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOE_PRESSURE_TEPM, 0U) | \ + PIN_AFIO_AF(GPIOE_PIN15, 0U)) + +/* + * GPIOF setup: + * + * PF0 - OSC_IN (input floating). + * PF1 - OSC_OUT (input floating). + * PF2 - JOY_DOWN (input pulldown). + * PF3 - PIN3 (input pullup). + * PF4 - JOY_LEFT (input pulldown). + * PF5 - PIN5 (input pullup). + * PF6 - PIN6 (input pullup). + * PF7 - PIN7 (input pullup). + * PF8 - PIN8 (input pullup). + * PF9 - JOY_RIGHT (input pulldown). + * PF10 - JOY_UP (input pulldown). + * PF11 - PIN11 (input pullup). + * PF12 - PIN12 (input pullup). + * PF13 - PIN13 (input pullup). + * PF14 - PIN14 (input pullup). + * PF15 - PIN15 (input pullup). + */ +#define VAL_GPIOF_MODER (PIN_MODE_INPUT(GPIOF_OSC_IN) | \ + PIN_MODE_INPUT(GPIOF_OSC_OUT) | \ + PIN_MODE_INPUT(GPIOF_JOY_DOWN) | \ + PIN_MODE_INPUT(GPIOF_PIN3) | \ + PIN_MODE_INPUT(GPIOF_JOY_LEFT) | \ + PIN_MODE_INPUT(GPIOF_PIN5) | \ + PIN_MODE_ALTERNATE(GPIOF_I2C2_SCL) | \ + PIN_MODE_ALTERNATE(GPIOF_I2C2_SDA) | \ + PIN_MODE_INPUT(GPIOF_PIN8) | \ + PIN_MODE_INPUT(GPIOF_JOY_RIGHT) | \ + PIN_MODE_INPUT(GPIOF_JOY_UP) | \ + PIN_MODE_INPUT(GPIOF_PIN11) | \ + PIN_MODE_INPUT(GPIOF_PIN12) | \ + PIN_MODE_INPUT(GPIOF_PIN13) | \ + PIN_MODE_INPUT(GPIOF_PIN14) | \ + PIN_MODE_INPUT(GPIOF_PIN15)) +#define VAL_GPIOF_OTYPER (PIN_OTYPE_PUSHPULL(GPIOF_OSC_IN) | \ + PIN_OTYPE_PUSHPULL(GPIOF_OSC_OUT) | \ + PIN_OTYPE_PUSHPULL(GPIOF_JOY_DOWN) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOF_JOY_LEFT) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN5) | \ + PIN_OTYPE_OPENDRAIN(GPIOF_I2C2_SCL) | \ + PIN_OTYPE_OPENDRAIN(GPIOF_I2C2_SDA) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOF_JOY_RIGHT) | \ + PIN_OTYPE_PUSHPULL(GPIOF_JOY_UP) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOF_PIN15)) +#define VAL_GPIOF_OSPEEDR (PIN_OSPEED_HIGH(GPIOF_OSC_IN) | \ + PIN_OSPEED_HIGH(GPIOF_OSC_OUT) | \ + PIN_OSPEED_HIGH(GPIOF_JOY_DOWN) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN3) | \ + PIN_OSPEED_HIGH(GPIOF_JOY_LEFT) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN5) | \ + PIN_OSPEED_HIGH(GPIOF_I2C2_SCL) | \ + PIN_OSPEED_HIGH(GPIOF_I2C2_SDA) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN8) | \ + PIN_OSPEED_HIGH(GPIOF_JOY_RIGHT) | \ + PIN_OSPEED_HIGH(GPIOF_JOY_UP) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOF_PIN15)) +#define VAL_GPIOF_PUPDR (PIN_PUPDR_FLOATING(GPIOF_OSC_IN) | \ + PIN_PUPDR_FLOATING(GPIOF_OSC_OUT) | \ + PIN_PUPDR_PULLDOWN(GPIOF_JOY_DOWN) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN3) | \ + PIN_PUPDR_PULLDOWN(GPIOF_JOY_LEFT) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN5) | \ + PIN_PUPDR_FLOATING(GPIOF_I2C2_SCL) | \ + PIN_PUPDR_FLOATING(GPIOF_I2C2_SDA) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN8) | \ + PIN_PUPDR_PULLDOWN(GPIOF_JOY_RIGHT) | \ + PIN_PUPDR_PULLDOWN(GPIOF_JOY_UP) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOF_PIN15)) +#define VAL_GPIOF_ODR (PIN_ODR_HIGH(GPIOF_OSC_IN) | \ + PIN_ODR_HIGH(GPIOF_OSC_OUT) | \ + PIN_ODR_HIGH(GPIOF_JOY_DOWN) | \ + PIN_ODR_HIGH(GPIOF_PIN3) | \ + PIN_ODR_HIGH(GPIOF_JOY_LEFT) | \ + PIN_ODR_HIGH(GPIOF_PIN5) | \ + PIN_ODR_HIGH(GPIOF_I2C2_SCL) | \ + PIN_ODR_HIGH(GPIOF_I2C2_SDA) | \ + PIN_ODR_HIGH(GPIOF_PIN8) | \ + PIN_ODR_HIGH(GPIOF_JOY_RIGHT) | \ + PIN_ODR_HIGH(GPIOF_JOY_UP) | \ + PIN_ODR_HIGH(GPIOF_PIN11) | \ + PIN_ODR_HIGH(GPIOF_PIN12) | \ + PIN_ODR_HIGH(GPIOF_PIN13) | \ + PIN_ODR_HIGH(GPIOF_PIN14) | \ + PIN_ODR_HIGH(GPIOF_PIN15)) +#define VAL_GPIOF_AFRL (PIN_AFIO_AF(GPIOF_OSC_IN, 0U) | \ + PIN_AFIO_AF(GPIOF_OSC_OUT, 0U) | \ + PIN_AFIO_AF(GPIOF_JOY_DOWN, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOF_JOY_LEFT, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOF_I2C2_SCL, 4U) | \ + PIN_AFIO_AF(GPIOF_I2C2_SDA, 4U)) +#define VAL_GPIOF_AFRH (PIN_AFIO_AF(GPIOF_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOF_JOY_RIGHT, 0U) | \ + PIN_AFIO_AF(GPIOF_JOY_UP, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOF_PIN15, 0U)) + +/* + * GPIOG setup: + * + * PG0 - PIN0 (input pullup). + * PG1 - PIN1 (input pullup). + * PG2 - PIN2 (input pullup). + * PG3 - PIN3 (input pullup). + * PG4 - PIN4 (input pullup). + * PG5 - PIN5 (input pullup). + * PG6 - PIN6 (input pullup). + * PG7 - PIN7 (input pullup). + * PG8 - PIN8 (input pullup). + * PG9 - PIN9 (input pullup). + * PG10 - PIN10 (input pullup). + * PG11 - PIN11 (input pullup). + * PG12 - PIN12 (input pullup). + * PG13 - PIN13 (input pullup). + * PG14 - PIN14 (input pullup). + * PG15 - PIN15 (input pullup). + */ +#define VAL_GPIOG_MODER (PIN_MODE_INPUT(GPIOG_PIN0) | \ + PIN_MODE_INPUT(GPIOG_PIN1) | \ + PIN_MODE_INPUT(GPIOG_PIN2) | \ + PIN_MODE_INPUT(GPIOG_PIN3) | \ + PIN_MODE_INPUT(GPIOG_PIN4) | \ + PIN_MODE_INPUT(GPIOG_PIN5) | \ + PIN_MODE_INPUT(GPIOG_PIN6) | \ + PIN_MODE_INPUT(GPIOG_PIN7) | \ + PIN_MODE_INPUT(GPIOG_PIN8) | \ + PIN_MODE_INPUT(GPIOG_PIN9) | \ + PIN_MODE_INPUT(GPIOG_PIN10) | \ + PIN_MODE_INPUT(GPIOG_PIN11) | \ + PIN_MODE_INPUT(GPIOG_PIN12) | \ + PIN_MODE_INPUT(GPIOG_PIN13) | \ + PIN_MODE_INPUT(GPIOG_PIN14) | \ + PIN_MODE_INPUT(GPIOG_PIN15)) +#define VAL_GPIOG_OTYPER (PIN_OTYPE_PUSHPULL(GPIOG_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOG_PIN15)) +#define VAL_GPIOG_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOG_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOG_PIN15)) +#define VAL_GPIOG_PUPDR (PIN_PUPDR_PULLUP(GPIOG_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOG_PIN15)) +#define VAL_GPIOG_ODR (PIN_ODR_HIGH(GPIOG_PIN0) | \ + PIN_ODR_HIGH(GPIOG_PIN1) | \ + PIN_ODR_HIGH(GPIOG_PIN2) | \ + PIN_ODR_HIGH(GPIOG_PIN3) | \ + PIN_ODR_HIGH(GPIOG_PIN4) | \ + PIN_ODR_HIGH(GPIOG_PIN5) | \ + PIN_ODR_HIGH(GPIOG_PIN6) | \ + PIN_ODR_HIGH(GPIOG_PIN7) | \ + PIN_ODR_HIGH(GPIOG_PIN8) | \ + PIN_ODR_HIGH(GPIOG_PIN9) | \ + PIN_ODR_HIGH(GPIOG_PIN10) | \ + PIN_ODR_HIGH(GPIOG_PIN11) | \ + PIN_ODR_HIGH(GPIOG_PIN12) | \ + PIN_ODR_HIGH(GPIOG_PIN13) | \ + PIN_ODR_HIGH(GPIOG_PIN14) | \ + PIN_ODR_HIGH(GPIOG_PIN15)) +#define VAL_GPIOG_AFRL (PIN_AFIO_AF(GPIOG_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN7, 0U)) +#define VAL_GPIOG_AFRH (PIN_AFIO_AF(GPIOG_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOG_PIN15, 0U)) + +/* + * GPIOH setup: + * + * PH0 - PIN0 (input pullup). + * PH1 - PIN1 (input pullup). + * PH2 - PIN2 (input pullup). + * PH3 - PIN3 (input pullup). + * PH4 - PIN4 (input pullup). + * PH5 - PIN5 (input pullup). + * PH6 - PIN6 (input pullup). + * PH7 - PIN7 (input pullup). + * PH8 - PIN8 (input pullup). + * PH9 - PIN9 (input pullup). + * PH10 - PIN10 (input pullup). + * PH11 - PIN11 (input pullup). + * PH12 - PIN12 (input pullup). + * PH13 - PIN13 (input pullup). + * PH14 - PIN14 (input pullup). + * PH15 - PIN15 (input pullup). + */ +#define VAL_GPIOH_MODER (PIN_MODE_INPUT(GPIOH_PIN0) | \ + PIN_MODE_INPUT(GPIOH_PIN1) | \ + PIN_MODE_INPUT(GPIOH_PIN2) | \ + PIN_MODE_INPUT(GPIOH_PIN3) | \ + PIN_MODE_INPUT(GPIOH_PIN4) | \ + PIN_MODE_INPUT(GPIOH_PIN5) | \ + PIN_MODE_INPUT(GPIOH_PIN6) | \ + PIN_MODE_INPUT(GPIOH_PIN7) | \ + PIN_MODE_INPUT(GPIOH_PIN8) | \ + PIN_MODE_INPUT(GPIOH_PIN9) | \ + PIN_MODE_INPUT(GPIOH_PIN10) | \ + PIN_MODE_INPUT(GPIOH_PIN11) | \ + PIN_MODE_INPUT(GPIOH_PIN12) | \ + PIN_MODE_INPUT(GPIOH_PIN13) | \ + PIN_MODE_INPUT(GPIOH_PIN14) | \ + PIN_MODE_INPUT(GPIOH_PIN15)) +#define VAL_GPIOH_OTYPER (PIN_OTYPE_PUSHPULL(GPIOH_PIN0) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN1) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN2) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN3) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN4) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN5) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN6) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN7) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN8) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN9) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN10) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN11) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN12) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN13) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN14) | \ + PIN_OTYPE_PUSHPULL(GPIOH_PIN15)) +#define VAL_GPIOH_OSPEEDR (PIN_OSPEED_VERYLOW(GPIOH_PIN0) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN1) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN2) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN3) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN4) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN5) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN6) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN7) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN8) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN9) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN10) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN11) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN12) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN13) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN14) | \ + PIN_OSPEED_VERYLOW(GPIOH_PIN15)) +#define VAL_GPIOH_PUPDR (PIN_PUPDR_PULLUP(GPIOH_PIN0) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN1) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN2) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN3) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN4) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN5) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN6) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN7) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN8) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN9) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN10) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN11) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN12) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN13) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN14) | \ + PIN_PUPDR_PULLUP(GPIOH_PIN15)) +#define VAL_GPIOH_ODR (PIN_ODR_HIGH(GPIOH_PIN0) | \ + PIN_ODR_HIGH(GPIOH_PIN1) | \ + PIN_ODR_HIGH(GPIOH_PIN2) | \ + PIN_ODR_HIGH(GPIOH_PIN3) | \ + PIN_ODR_HIGH(GPIOH_PIN4) | \ + PIN_ODR_HIGH(GPIOH_PIN5) | \ + PIN_ODR_HIGH(GPIOH_PIN6) | \ + PIN_ODR_HIGH(GPIOH_PIN7) | \ + PIN_ODR_HIGH(GPIOH_PIN8) | \ + PIN_ODR_HIGH(GPIOH_PIN9) | \ + PIN_ODR_HIGH(GPIOH_PIN10) | \ + PIN_ODR_HIGH(GPIOH_PIN11) | \ + PIN_ODR_HIGH(GPIOH_PIN12) | \ + PIN_ODR_HIGH(GPIOH_PIN13) | \ + PIN_ODR_HIGH(GPIOH_PIN14) | \ + PIN_ODR_HIGH(GPIOH_PIN15)) +#define VAL_GPIOH_AFRL (PIN_AFIO_AF(GPIOH_PIN0, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN1, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN2, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN3, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN4, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN5, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN6, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN7, 0U)) +#define VAL_GPIOH_AFRH (PIN_AFIO_AF(GPIOH_PIN8, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN9, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN10, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN11, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN12, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN13, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN14, 0U) | \ + PIN_AFIO_AF(GPIOH_PIN15, 0U)) + +//***************************************************************************** + +/* + * AHB_CLK + */ +#define AHB_CLK STM32_HCLK + +/* + * LEDs + */ +/* red */ +#ifndef USE_LED_1 +#define USE_LED_1 1 +#endif +#define LED_1_GPIO GPIOA +#define LED_1_GPIO_PIN GPIO8 +#define LED_1_GPIO_ON gpio_clear +#define LED_1_GPIO_OFF gpio_set + +/* green */ +#ifndef USE_LED_2 +#define USE_LED_2 1 +#endif +#define LED_2_GPIO GPIOD +#define LED_2_GPIO_PIN GPIO8 +#define LED_2_GPIO_ON gpio_clear +#define LED_2_GPIO_OFF gpio_set + +/*orange */ +#ifndef USE_LED_3 +#define USE_LED_3 0 +#endif +#define LED_3_GPIO GPIOE +#define LED_3_GPIO_PIN GPIO10 +#define LED_3_GPIO_ON gpio_clear +#define LED_3_GPIO_OFF gpio_set + +/* green */ +#ifndef USE_LED_4 +#define USE_LED_4 0 +#endif +#define LED_4_GPIO GPIOE +#define LED_4_GPIO_PIN GPIO11 +#define LED_4_GPIO_ON gpio_clear +#define LED_4_GPIO_OFF gpio_set + +/* blue*/ +#ifndef USE_LED_5 +#define USE_LED_5 0 +#endif +#define LED_5_GPIO GPIOE +#define LED_5_GPIO_PIN GPIO12 +#define LED_5_GPIO_ON gpio_set +#define LED_5_GPIO_OFF gpio_clear + +/* red*/ +#ifndef USE_LED_6 +#define USE_LED_6 0 +#endif +#define LED_6_GPIO GPIOE +#define LED_6_GPIO_PIN GPIO13 +#define LED_6_GPIO_ON gpio_set +#define LED_6_GPIO_OFF gpio_clear + +/* orange*/ +#ifndef USE_LED_7 +#define USE_LED_7 0 +#endif +#define LED_7_GPIO GPIOE +#define LED_7_GPIO_PIN GPIO13 +#define LED_7_GPIO_ON gpio_set +#define LED_7_GPIO_OFF gpio_clear + +/* green*/ +#ifndef USE_LED_8 +#define USE_LED_8 0 +#endif +#define LED_8_GPIO GPIOE +#define LED_8_GPIO_PIN GPIO15 +#define LED_8_GPIO_ON gpio_set +#define LED_8_GPIO_OFF gpio_clear + + +/* 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 + +/* + * ADCs + */ +// AUX 1 +#ifndef USE_ADC_1 +#define USE_ADC_1 1 +#endif +#if USE_ADC_1 +#define AD1_1_CHANNEL ADC_CHANNEL_IN1 +#define ADC_1 AD1_1 +#define ADC_1_GPIO_PORT GPIOA +#define ADC_1_GPIO_PIN GPIO1 +#endif + +// AUX 2 +#if USE_ADC_2 +#define AD1_2_CHANNEL ADC_CHANNEL_IN15 +#define ADC_2 AD1_2 +#define ADC_2_GPIO_PORT GPIOA +#define ADC_2_GPIO_PIN GPIO6 +#endif + +// AUX 3 +#if USE_ADC_3 +#define AD1_3_CHANNEL ADC_CHANNEL_IN14 +#define ADC_3 AD1_3 +#define ADC_3_GPIO_PORT GPIOC +#define ADC_3_GPIO_PIN GPIO4 +#endif + +#if USE_ADC_4 +#define AD1_4_CHANNEL ADC_CHANNEL_IN4 +#define ADC_4 AD1_4 +#define ADC_4_GPIO_PORT GPIOA +#define ADC_4_GPIO_PIN GPIO4 +#endif + +///* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY +#define ADC_CHANNEL_VSUPPLY ADC_1 +#endif + +#define DefaultVoltageOfAdc(adc) (0.003765*adc) + +#define ACTUATORS_PWM_NB 4 +//the first two motors are through the xvert escs +//the second two are two standard pwm servos + +#define XVERT_ESC_0 0 +#define XVERT_ESC_1 1 + +#ifndef USE_PWM2 +#define USE_PWM2 1 +#endif +#if USE_PWM2 +#define PWM_SERVO_2 2 +#define PWM_SERVO_2_GPIO GPIOA +#define PWM_SERVO_2_PIN GPIO11 +#define PWM_SERVO_2_AF GPIO_AF2 //alternate function of the pin, alsu used to select which timer (table 12 in datasheet) +#define PWM_SERVO_2_DRIVER PWMD5 //timer ID. Which timer is being used by this pwm pin +#define PWM_SERVO_2_CHANNEL 1 //channel *in* the timer Find it in table 12 (subtract by 1!) +#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH +#else +#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED +#endif + +#ifndef USE_PWM3 +#define USE_PWM3 1 +#endif +#if USE_PWM3 +#define PWM_SERVO_3 3 +#define PWM_SERVO_3_GPIO GPIOA +#define PWM_SERVO_3_PIN GPIO12 +#define PWM_SERVO_3_AF GPIO_AF2 +#define PWM_SERVO_3_DRIVER PWMD5 +#define PWM_SERVO_3_CHANNEL 2 +#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH +#else +#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED +#endif + +#if !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_3_ACTIVE, NULL }, \ + { PWM_SERVO_2_ACTIVE, NULL }, \ + { PWM_SERVO_3_ACTIVE, NULL }, \ + { PWM_SERVO_3_ACTIVE, 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 ICUD1 + +///* +// * PWM input +// */ +//// PWM_INPUT 1 on PA8 (also PPM IN) +//#define PWM_INPUT1_ICU ICUD1 +//#define PWM_INPUT1_CHANNEL ICU_CHANNEL_1 +//// PPM in (aka PA8) is used: not compatible with PPM RC receiver +//#define PWM_INPUT1_GPIO_PORT GPIOA +//#define PWM_INPUT1_GPIO_PIN GPIO8 +//#define PWM_INPUT1_GPIO_AF GPIO_AF1 + +//// PWM_INPUT 2 on PA3 (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_GPIO_PORT GPIOA +//#define PWM_INPUT2_GPIO_PIN GPIO2 +//#define PWM_INPUT2_GPIO_AF GPIO_AF3 + +/** + * I2C defines + */ +#define I2C1_CFG_DEF { \ + STM32_TIMINGR_PRESC(15U) | \ + STM32_TIMINGR_SCLDEL(4U) | \ + STM32_TIMINGR_SDADEL(2U) | \ + STM32_TIMINGR_SCLH(15U) | \ + STM32_TIMINGR_SCLL(21U), \ + 0,0 } + +#define I2C2_CFG_DEF { \ + STM32_TIMINGR_PRESC(15U) | \ + STM32_TIMINGR_SCLDEL(4U) | \ + STM32_TIMINGR_SDADEL(2U) | \ + STM32_TIMINGR_SCLH(15U) | \ + STM32_TIMINGR_SCLL(21U), \ + 0,0 } + + +///** +// * SPI Config +// */ +//#define SPI1_GPIO_AF GPIO_AF5 +//#define SPI1_GPIO_PORT_MISO GPIOA +//#define SPI1_GPIO_MISO GPIO6 +//#define SPI1_GPIO_PORT_MOSI GPIOA +//#define SPI1_GPIO_MOSI GPIO7 +//#define SPI1_GPIO_PORT_SCK GPIOA +//#define SPI1_GPIO_SCK GPIO5 + +//// SLAVE0 on SPI connector +//#define SPI_SELECT_SLAVE0_PORT GPIOB +//#define SPI_SELECT_SLAVE0_PIN GPIO9 +//// SLAVE1 on AUX1 +//#define SPI_SELECT_SLAVE1_PORT GPIOB +//#define SPI_SELECT_SLAVE1_PIN GPIO1 +//// SLAVE2 on AUX2 +//#define SPI_SELECT_SLAVE2_PORT GPIOC +//#define SPI_SELECT_SLAVE2_PIN GPIO5 +//// SLAVE3 on AUX3 +//#define SPI_SELECT_SLAVE3_PORT GPIOC +//#define SPI_SELECT_SLAVE3_PIN GPIO4 +//// SLAVE4 on AUX4 +//#define SPI_SELECT_SLAVE4_PORT GPIOB +//#define SPI_SELECT_SLAVE4_PIN GPIO15 + +/** + * Baro + * + * Apparently needed for backwards compatibility + * with the ancient onboard baro boards + */ +#ifndef USE_BARO_BOARD +#define USE_BARO_BOARD 1 +#endif + +/* + * Actuators for fixedwing + */ +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + + +///** +// * SDIO +// */ +//#define SDIO_D0_PORT GPIOC +//#define SDIO_D0_PIN GPIOC_SDIO_D0 +//#define SDIO_D1_PORT GPIOC +//#define SDIO_D1_PIN GPIOC_SDIO_D1 +//#define SDIO_D2_PORT GPIOC +//#define SDIO_D2_PIN GPIOC_SDIO_D2 +//#define SDIO_D3_PORT GPIOC +//#define SDIO_D3_PIN GPIOC_SDIO_D3 +//#define SDIO_CK_PORT GPIOC +//#define SDIO_CK_PIN GPIOC_SDIO_CK +//#define SDIO_CMD_PORT GPIOD +//#define SDIO_CMD_PIN GPIOD_SDIO_CMD +//#define SDIO_AF 12 +//// bat monitoring for file closing +//#define SDLOG_BAT_ADC ADCD1 +//#define SDLOG_BAT_CHAN AD1_4_CHANNEL +//// usb led status +//#define SDLOG_USB_LED 4 +//#define SDLOG_USB_VBUS_PORT GPIOA +//#define SDLOG_USB_VBUS_PIN GPIO9 + + +//***************************************************************************** + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif +void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* BOARD_H */ diff --git a/sw/airborne/boards/xvert/chibios/v1.0/board.mk b/sw/airborne/boards/xvert/chibios/v1.0/board.mk new file mode 100644 index 0000000000..00cb8ed3d1 --- /dev/null +++ b/sw/airborne/boards/xvert/chibios/v1.0/board.mk @@ -0,0 +1,20 @@ +# +# 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 diff --git a/sw/airborne/boards/xvert/chibios/v1.0/mcuconf.h b/sw/airborne/boards/xvert/chibios/v1.0/mcuconf.h new file mode 100644 index 0000000000..bdb84f140b --- /dev/null +++ b/sw/airborne/boards/xvert/chibios/v1.0/mcuconf.h @@ -0,0 +1,270 @@ +/* + ChibiOS - Copyright (C) 2006..2016 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 + +/* + * STM32F37x 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 STM32F37x_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 +#define STM32_HSI_ENABLED TRUE +#define STM32_LSI_ENABLED TRUE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PREDIV_VALUE 2 +#define STM32_PLLMUL_VALUE 9 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK +#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_SDPRE STM32_SDPRE_DIV12 +#define STM32_USART1SW STM32_USART1SW_PCLK +#define STM32_USART2SW STM32_USART2SW_PCLK +#define STM32_USART3SW STM32_USART3SW_PCLK +#define STM32_I2C1SW STM32_I2C1SW_SYSCLK +#define STM32_I2C2SW STM32_I2C2SW_SYSCLK +#define STM32_RTCSEL STM32_RTCSEL_LSI +#define STM32_USB_CLOCK_REQUIRED TRUE +#define STM32_USBPRE STM32_USBPRE_DIV1P5 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_USE_ADC1 TRUE +#define STM32_ADC_USE_SDADC1 FALSE +#define STM32_ADC_USE_SDADC2 FALSE +#define STM32_ADC_USE_SDADC3 FALSE +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_SDADC1_DMA_PRIORITY 2 +#define STM32_ADC_SDADC2_DMA_PRIORITY 2 +#define STM32_ADC_SDADC3_DMA_PRIORITY 2 +#define STM32_ADC_ADC1_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC1_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC2_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC3_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC1_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC2_DMA_IRQ_PRIORITY 5 +#define STM32_ADC_SDADC3_DMA_IRQ_PRIORITY 5 + +/* + * CAN driver system settings. + */ +#if USE_CAN1 +#define STM32_CAN_USE_CAN1 TRUE +#else +#define STM32_CAN_USE_CAN1 FALSE +#endif +#define STM32_CAN_CAN1_IRQ_PRIORITY 11 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI20_23_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI30_32_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI33_IRQ_PRIORITY 6 + +/* + * GPT driver system settings. + */ +#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_TIM12 FALSE +#define STM32_GPT_USE_TIM14 FALSE +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM6_IRQ_PRIORITY 7 +#define STM32_GPT_TIM7_IRQ_PRIORITY 7 +#define STM32_GPT_TIM12_IRQ_PRIORITY 7 +#define STM32_GPT_TIM14_IRQ_PRIORITY 7 + +/* + * 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 +#define STM32_I2C_BUSY_TIMEOUT 50 +#define STM32_I2C_I2C1_IRQ_PRIORITY 10 +#define STM32_I2C_I2C2_IRQ_PRIORITY 10 +#define STM32_I2C_USE_DMA TRUE +#define STM32_I2C_I2C1_DMA_PRIORITY 1 +#define STM32_I2C_I2C2_DMA_PRIORITY 1 +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") + +/* + * ICU driver system settings. + */ +#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_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_TIM2 FALSE +#define STM32_PWM_USE_TIM3 FALSE +#define STM32_PWM_USE_TIM4 FALSE +#define STM32_PWM_USE_TIM5 TRUE +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 + +/* + * 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 +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 +#define STM32_SERIAL_UART4_PRIORITY 12 +#define STM32_SERIAL_UART5_PRIORITY 12 + +/* + * 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 +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_SPI3_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") + +/* + * ST driver system settings. + */ +#define STM32_ST_IRQ_PRIORITY 8 +#define STM32_ST_USE_TIMER 2 + +/* + * UART driver system settings. + */ +#define STM32_UART_USE_USART1 TRUE +#define STM32_UART_USE_USART2 TRUE +#define STM32_UART_USE_USART3 FALSE +#define STM32_UART_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_USB1 FALSE +#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE +#define STM32_USB_USB1_HP_IRQ_PRIORITY 13 +#define STM32_USB_USB1_LP_IRQ_PRIORITY 14 + +/* + * WDG driver system settings. + */ +#define STM32_WDG_USE_IWDG FALSE + +#endif /* MCUCONF_H */ diff --git a/sw/airborne/firmwares/rotorcraft/main_chibios.c b/sw/airborne/firmwares/rotorcraft/main_chibios.c index 7cf089e937..2ab47c4e58 100644 --- a/sw/airborne/firmwares/rotorcraft/main_chibios.c +++ b/sw/airborne/firmwares/rotorcraft/main_chibios.c @@ -37,12 +37,16 @@ #include "firmwares/rotorcraft/main_ap.h" +#ifndef THD_WORKING_AREA_MAIN +#define THD_WORKING_AREA_MAIN 8192 +#endif + /* * PPRZ/AP thread * Also include FBW on single MCU */ static void thd_ap(void *arg); -static THD_WORKING_AREA(wa_thd_ap, 8192); +THD_WORKING_AREA(wa_thd_ap, THD_WORKING_AREA_MAIN); static thread_t *apThdPtr = NULL; /** diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi_simple.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi_simple.c index 019046895f..6856ed9eeb 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi_simple.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi_simple.c @@ -94,14 +94,16 @@ struct IndiVariables indi = { STABILIZATION_INDI_REF_ERR_R, STABILIZATION_INDI_REF_RATE_P, STABILIZATION_INDI_REF_RATE_Q, - STABILIZATION_INDI_REF_RATE_R}, + STABILIZATION_INDI_REF_RATE_R + }, /* Estimation parameters for adaptive INDI */ .est = { .g1 = { STABILIZATION_INDI_G1_P / INDI_EST_SCALE, STABILIZATION_INDI_G1_Q / INDI_EST_SCALE, - STABILIZATION_INDI_G1_R / INDI_EST_SCALE}, + STABILIZATION_INDI_G1_R / INDI_EST_SCALE + }, .g2 = STABILIZATION_INDI_G2_R / INDI_EST_SCALE, .mu = STABILIZATION_INDI_ADAPTIVE_MU, }, @@ -162,15 +164,16 @@ void stabilization_indi_init(void) #endif } -void indi_init_filters(void) { +void indi_init_filters(void) +{ // tau = 1/(2*pi*Fc) - float tau = 1.0/(2.0*M_PI*STABILIZATION_INDI_FILT_CUTOFF); - float tau_r = 1.0/(2.0*M_PI*STABILIZATION_INDI_FILT_CUTOFF_R); + float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF); + float tau_r = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_R); float tau_axis[3] = {tau, tau, tau_r}; - float tau_est = 1.0/(2.0*M_PI*STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF); - float sample_time = 1.0/PERIODIC_FREQUENCY; + float tau_est = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF); + float sample_time = 1.0 / PERIODIC_FREQUENCY; // Filtering of gyroscope and actuators - for(int8_t i=0; i<3; i++) { + for (int8_t i = 0; i < 3; i++) { init_butterworth_2_low_pass(&indi.u[i], tau_axis[i], sample_time, 0.0); init_butterworth_2_low_pass(&indi.rate[i], tau_axis[i], sample_time, 0.0); init_butterworth_2_low_pass(&indi.est.u[i], tau_est, sample_time, 0.0); @@ -243,7 +246,8 @@ void stabilization_indi_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading) * @param filter The filter array to use * @param new_values The new values */ -static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *new_values) { +static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *new_values) +{ update_butterworth_2_low_pass(&filter[0], new_values->p); update_butterworth_2_low_pass(&filter[1], new_values->q); update_butterworth_2_low_pass(&filter[2], new_values->r); @@ -256,9 +260,10 @@ static inline void filter_pqr(Butterworth2LowPass *filter, struct FloatRates *ne * @param output The output array * @param filter The filter array input */ -static inline void finite_difference_from_filter(float *output, Butterworth2LowPass *filter) { - for(int8_t i=0; i<3; i++) { - output[i] = (filter[i].o[0] - filter[i].o[1])*PERIODIC_FREQUENCY; +static inline void finite_difference_from_filter(float *output, Butterworth2LowPass *filter) +{ + for (int8_t i = 0; i < 3; i++) { + output[i] = (filter[i].o[0] - filter[i].o[1]) * PERIODIC_FREQUENCY; } } @@ -269,8 +274,9 @@ static inline void finite_difference_from_filter(float *output, Butterworth2LowP * @param new[3] The newest values * @param old[3] The values of the previous timestep */ -static inline void finite_difference(float output[3], float new[3], float old[3]) { - for(int8_t i=0; i<3; i++) { +static inline void finite_difference(float output[3], float new[3], float old[3]) +{ + for (int8_t i = 0; i < 3; i++) { output[i] = (new[i] - old[i])*PERIODIC_FREQUENCY; } } @@ -315,12 +321,12 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I - indi.reference_acceleration.rate_q * rates_for_feedback.q; //This separates the P and D controller and lets you impose a maximum yaw rate. - float rate_ref_r = indi.reference_acceleration.err_r * QUAT1_FLOAT_OF_BFP(att_err->qz)/indi.reference_acceleration.rate_r; + float rate_ref_r = indi.reference_acceleration.err_r * QUAT1_FLOAT_OF_BFP(att_err->qz) / indi.reference_acceleration.rate_r; BoundAbs(rate_ref_r, indi.attitude_max_yaw_rate); indi.angular_accel_ref.r = indi.reference_acceleration.rate_r * (rate_ref_r - rates_for_feedback.r); /* Check if we are running the rate controller and overwrite */ - if(rate_control) { + if (rate_control) { indi.angular_accel_ref.p = indi.reference_acceleration.rate_p * ((float)radio_control.values[RADIO_ROLL] / MAX_PPRZ * indi.max_rate - body_rates->p); indi.angular_accel_ref.q = indi.reference_acceleration.rate_q * ((float)radio_control.values[RADIO_PITCH] / MAX_PPRZ * indi.max_rate - body_rates->q); indi.angular_accel_ref.r = indi.reference_acceleration.rate_r * ((float)radio_control.values[RADIO_YAW] / MAX_PPRZ * indi.max_rate - body_rates->r); @@ -340,9 +346,17 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I indi.u_in.r = indi.u[2].o[0] + indi.du.r; //bound the total control input +#if STABILIZATION_INDI_FULL_AUTHORITY + Bound(indi.u_in.p, -9600, 9600); + Bound(indi.u_in.q, -9600, 9600); + float rlim = 9600 - fabs(indi.u_in.q); + Bound(indi.u_in.r, -rlim, rlim); + Bound(indi.u_in.r, -9600, 9600); +#else Bound(indi.u_in.p, -4500, 4500); Bound(indi.u_in.q, -4500, 4500); Bound(indi.u_in.r, -4500, 4500); +#endif //Propagate input filters //first order actuator dynamics diff --git a/sw/airborne/math/pprz_trig_int.c b/sw/airborne/math/pprz_trig_int.c index b538f33179..655c9ffca1 100644 --- a/sw/airborne/math/pprz_trig_int.c +++ b/sw/airborne/math/pprz_trig_int.c @@ -26,7 +26,7 @@ #include "pprz_trig_int.h" #include "pprz_algebra_int.h" - +#if !defined(PPRZ_TRIG_INT_USE_FLOAT) #if !defined(PPRZ_TRIG_INT_COMPR_FLASH) || defined(PPRZ_TRIG_INT_TEST) PPRZ_TRIG_CONST int16_t pprz_trig_int[6434] = { 0, 3, 7, 11, 15, 19, 23, 27, 31, 35, 39, 43, 47, 51, 55, 59, 63, @@ -581,7 +581,7 @@ const uint8_t pprz_trig_int_compr[TRIG_INT_COMPR_LEN] = { 0x10, 0x1F, 0x10, 0x3F, 0x10, 0x8F, 0x10, 0xFF, 0xA8, 0x00 }; #endif - +#endif #if defined(PPRZ_TRIG_INT_COMPR_FLASH) @@ -858,6 +858,13 @@ inline int16_t pprz_trig_int_f(int32_t angle) int32_t pprz_itrig_sin(int32_t angle) { +#if defined(PPRZ_TRIG_INT_USE_FLOAT) + float tmp; + tmp = ANGLE_FLOAT_OF_BFP(angle); + tmp = sinf(tmp); + angle = ANGLE_BFP_OF_REAL(tmp); + return angle; +#else INT32_ANGLE_NORMALIZE(angle); if (angle > INT32_ANGLE_PI_2) { angle = INT32_ANGLE_PI - angle; @@ -875,6 +882,7 @@ int32_t pprz_itrig_sin(int32_t angle) return -pprz_trig_int[-angle]; #endif } +#endif } int32_t pprz_itrig_cos(int32_t angle) diff --git a/sw/airborne/peripherals/mpu9250_i2c.c b/sw/airborne/peripherals/mpu9250_i2c.c index e547c8b6c1..ad18b93559 100644 --- a/sw/airborne/peripherals/mpu9250_i2c.c +++ b/sw/airborne/peripherals/mpu9250_i2c.c @@ -28,7 +28,7 @@ #include "peripherals/mpu9250_i2c.h" bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)), - void *mpu __attribute__((unused))); + void *mpu __attribute__((unused))); void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t addr) { @@ -47,8 +47,10 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t mpu->config.initialized = false; mpu->config.init_status = MPU9250_CONF_UNINIT; +#if IMU_MPU9250_READ_MAG /* "internal" ak8963 magnetometer */ ak8963_init(&mpu->akm, i2c_p, MPU9250_MAG_ADDR); + /* mag is declared as slave to call the configure function, * regardless if it is an actual MPU slave or passthrough */ @@ -59,6 +61,7 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t mpu->config.i2c_bypass = true; mpu->slave_init_status = MPU9250_I2C_CONF_UNINIT; +#endif } @@ -88,10 +91,12 @@ void mpu9250_i2c_read(struct Mpu9250_I2c *mpu) mpu->i2c_trans.buf[0] = MPU9250_REG_INT_STATUS; i2c_transceive(mpu->i2c_p, &(mpu->i2c_trans), mpu->i2c_trans.slave_addr, 1, mpu->config.nb_bytes); /* read mag */ +#if IMU_MPU9250_READ_MAG #ifdef MPU9250_MAG_PRESCALER RunOnceEvery(MPU9250_MAG_PRESCALER, ak8963_read(&mpu->akm)); #else ak8963_read(&mpu->akm); +#endif #endif } } @@ -144,8 +149,10 @@ void mpu9250_i2c_event(struct Mpu9250_I2c *mpu) break; } } +#if IMU_MPU9250_READ_MAG // Ak8963 event function ak8963_event(&mpu->akm); +#endif } /** callback function to configure ak8963 mag @@ -185,12 +192,11 @@ bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu) case MPU9250_I2C_CONF_SLAVES_CONFIGURE: /* configure each slave until all nb_slaves are done */ if (mpu_i2c->config.nb_slave_init < mpu_i2c->config.nb_slaves && mpu_i2c->config.nb_slave_init < MPU9250_I2C_NB_SLAVES) { - // proceed to next slave if configure for current one returns true + // proceed to next slave if configure for current one returns true if (mpu_i2c->config.slaves[mpu_i2c->config.nb_slave_init].configure(mpu_set, mpu)) { mpu_i2c->config.nb_slave_init++; } - } - else { + } else { /* all slave devies configured, continue MPU side configuration of I2C slave stuff */ mpu_i2c->slave_init_status++; } diff --git a/sw/airborne/peripherals/mpu9250_i2c.h b/sw/airborne/peripherals/mpu9250_i2c.h index 0d6a9bc2c5..158a723956 100644 --- a/sw/airborne/peripherals/mpu9250_i2c.h +++ b/sw/airborne/peripherals/mpu9250_i2c.h @@ -36,6 +36,10 @@ #include "peripherals/mpu9250.h" #include "peripherals/ak8963.h" +#ifndef IMU_MPU9250_READ_MAG +#define IMU_MPU9250_READ_MAG TRUE +//the MPU6500 is the same as the 9250, except for that its lacking a magneto +#endif #define MPU9250_BUFFER_EXT_LEN 16 @@ -67,7 +71,9 @@ struct Mpu9250_I2c { uint8_t data_ext[MPU9250_BUFFER_EXT_LEN]; struct Mpu9250Config config; enum Mpu9250I2cSlaveInitStatus slave_init_status; +#ifdef IMU_MPU9250_READ_MAG struct Ak8963 akm; ///< "internal" magnetometer +#endif }; // Functions diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c index 99981f6d3a..f6083f79e4 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c @@ -116,7 +116,7 @@ void ahrs_fc_init(void) } bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, - struct FloatVect3 *lp_mag) + struct FloatVect3 *lp_mag __attribute__((unused))) { #if USE_MAGNETOMETER @@ -276,7 +276,7 @@ void ahrs_fc_update_accel(struct FloatVect3 *accel, float dt) } -void ahrs_fc_update_mag(struct FloatVect3 *mag, float dt) +void ahrs_fc_update_mag(struct FloatVect3 *mag __attribute__((unused)), float dt __attribute__((unused))) { #if USE_MAGNETOMETER // check if we had at least one propagation since last update diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c index b9cabc84f7..2befa1ab72 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c +++ b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c @@ -126,14 +126,14 @@ void imu_mpu9250_event(void) if (imu_mpu9250.mpu.data_available) { // set channel order struct Int32Vect3 accel = { - IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_X]), - IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Y]), - IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Z]) + IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_X]), + IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Y]), + IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.data_accel.value[IMU_MPU9250_CHAN_Z]) }; struct Int32Rates rates = { - IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_X]), - IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Y]), - IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Z]) + IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_X]), + IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Y]), + IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.data_rates.value[IMU_MPU9250_CHAN_Z]) }; // unscaled vector VECT3_COPY(imu.accel_unscaled, accel); @@ -146,19 +146,20 @@ void imu_mpu9250_event(void) AbiSendMsgIMU_GYRO_INT32(IMU_MPU9250_ID, now_ts, &imu.gyro); AbiSendMsgIMU_ACCEL_INT32(IMU_MPU9250_ID, now_ts, &imu.accel); } - +#if IMU_MPU9250_READ_MAG // Test if mag data are updated if (imu_mpu9250.mpu.akm.data_available) { struct Int32Vect3 mag = { - IMU_MPU9250_X_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Y]), - IMU_MPU9250_Y_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_X]), - -IMU_MPU9250_Z_SIGN * (int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Z]) + IMU_MPU9250_X_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Y]), + IMU_MPU9250_Y_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_X]), + -IMU_MPU9250_Z_SIGN *(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Z]) }; VECT3_COPY(imu.mag_unscaled, mag); imu_mpu9250.mpu.akm.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_MPU9250_ID, now_ts, &imu.mag); - } + } +#endif } diff --git a/sw/tools/find_vpaths.py b/sw/tools/find_vpaths.py index 4fea177acd..17adade36b 100755 --- a/sw/tools/find_vpaths.py +++ b/sw/tools/find_vpaths.py @@ -3,55 +3,71 @@ #It finds the correct VPATH to each source file from make, and then feeds all info to gcc -MM. import sys import os -from os import path, getenv +from os import path, getenv, environ -# first argument is the gcc compiler -# thereafter are the vpaths closed by a '+' -# thereafter are the srcs closed by a '+' -# thereafter are the cflags +pprzswdir = os.environ['PAPARAZZI_SRC'] +pprzswdir = path.join(pprzswdir, "sw/airborne") -#parse the input arguments into seperate lists cc = sys.argv[1] -vpaths = list() -srcs = list() -cflags = list() -mode = 0 -for i in range(2,len(sys.argv)): - vpath = sys.argv[i] - if vpath == '+': - mode = mode + 1 - else: - if mode == 0: - vpaths.append(vpath) - elif mode == 1: - srcs.append(sys.argv[i]) - elif mode == 2: - cflags.append(sys.argv[i]) -#create the command for gcc -MM cflags srcs -cmd = cc + ' -MM ' -for flg in cflags: - qflg = "" # append all quotes with escape char - for i in range(0,len(flg)): - if flg[i] == "\"": - qflg = qflg + "\\\"" - else: - qflg = qflg + flg[i] - cmd = cmd + qflg + ' ' +with open(sys.argv[2]) as fp: + vpathsl = fp.readline() + srcsl = fp.readline() + cflagsl = fp.readline() + includesl = fp.readline() + toptl = fp.readline() -for i in range(0,len(srcs)): - f = srcs[i] - found = 0 - for vpath in vpaths: - if os.path.isfile(path.join(vpath, f)) : - cmd = cmd + path.join(vpath, f) + ' ' - found = found +1 - break - if found == 0: - print("ERROR, could not find: " + f) - if found > 1: - print("ERROR, found more than once: " + f) + vpaths = vpathsl.strip().split(" ") + srcs = srcsl.strip().split(" ") + cflags = cflagsl.strip().split(" ") + includes = includesl.strip().split(" ") -#call gcc -os.system(cmd) + + cflagsn = "" #" -I" + pprzswdir + " -I" + pprzvardir + " " + for i in range(0,len(cflags)): + f = cflags[i] + + nf = "" # append all quotes with escape char + for j in range(0,len(f)): + if f[j] == "\"": + nf = nf + "\\\"" + else: + nf = nf + f[j] + f = nf + + + if f.startswith("-I"): #for whatever reason, these includes miss the pprz path. Which gives issues with gcc + f = "-I" + path.join(pprzswdir, f[2:]) + elif f.startswith ("-M"): + break; + f = " " + cflagsn = cflagsn + f + " " + + topt = toptl.strip().split(" ") + + vpaths.append(pprzswdir) + + #create the command for gcc -MM cflags srcs + cmd = cc + ' -MM ' + includesl.strip() + " " + cflagsn.strip() + " " + toptl.strip() + + #print("****************************************************") + for i in range(0,len(srcs)): + f = srcs[i] + found = 0 + for vpath in vpaths: + if os.path.isfile(path.join(vpath, f)) : + cmd = cmd + path.join(vpath, f) + ' ' + found = found +1 + # break + if found == 0: + tmps = "ERROR: could not find src: " + f + cmd = cmd + tmps #hack to make the error known + print(tmps) + if found > 1: + tmps = "ERROR: found src more than once: " + f + cmd = cmd + tmps #hack to make the error known + print(tmps) + #print(cmd) + #call gcc + os.system(cmd) diff --git a/sw/tools/qt_project.py b/sw/tools/qt_project.py index 2d1e0f5e6b..f65020a68a 100755 --- a/sw/tools/qt_project.py +++ b/sw/tools/qt_project.py @@ -96,8 +96,7 @@ for src in srcs: # Parse the header files headers_all = "" line = "1" -while line: - line=ap_srcs_list.readline() +for line in ap_srcs_list: line = line.strip() if ":" in line: line = line.split(":")[-1] diff --git a/sw/tools/qtc.creator.user_template b/sw/tools/qtc.creator.user_template index 5869247310..f241f25e90 100644 --- a/sw/tools/qtc.creator.user_template +++ b/sw/tools/qtc.creator.user_template @@ -1,10 +1,10 @@ - + EnvironmentId - {3799acf3-eb9e-4a06-886d-992bd0f8d07a} + {67a68b0c-7516-47dc-923e-e0da33c1f7ec} ProjectExplorer.Project.ActiveTarget @@ -19,7 +19,7 @@ Cpp - qt3 + CppGlobal @@ -54,16 +54,14 @@ ProjectExplorer.Project.PluginSettings - - - + ProjectExplorer.Project.Target.0 - Desktop Qt 5.7.0 GCC 64bit - Desktop Qt 5.7.0 GCC 64bit - qt.57.gcc_64_kit + Desktop Qt 5.9.1 GCC 64bit + Desktop Qt 5.9.1 GCC 64bit + qt.591.gcc_64_kit 0 0 0