diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp
index c8a566c609128..bb34d34387814 100644
--- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp
+++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp
@@ -744,7 +744,22 @@ void Scheduler::watchdog_pat(void)
{
stm32_watchdog_pat();
last_watchdog_pat_ms = AP_HAL::millis();
+#if defined(HAL_GPIO_PIN_EXT_WDOG)
+ ext_watchdog_pat(last_watchdog_pat_ms);
+#endif
+}
+
+#if defined(HAL_GPIO_PIN_EXT_WDOG)
+// toggle the external watchdog gpio pin
+void Scheduler::ext_watchdog_pat(uint32_t now_ms)
+{
+ // toggle watchdog GPIO every WDI_OUT_INTERVAL_TIME_MS
+ if ((now_ms - last_ext_watchdog_ms) >= EXT_WDOG_INTERVAL_MS) {
+ palToggleLine(HAL_GPIO_PIN_EXT_WDOG);
+ last_ext_watchdog_ms = now_ms;
+ }
}
+#endif
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
/*
diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h
index 95a9ce4d55e56..a6fd2d30b23bf 100644
--- a/libraries/AP_HAL_ChibiOS/Scheduler.h
+++ b/libraries/AP_HAL_ChibiOS/Scheduler.h
@@ -192,5 +192,11 @@ class ChibiOS::Scheduler : public AP_HAL::Scheduler {
// check for free stack space
void check_stack_free(void);
+
+#if defined(HAL_GPIO_PIN_EXT_WDOG)
+ // external watchdog GPIO support
+ void ext_watchdog_pat(uint32_t now_ms);
+ uint32_t last_ext_watchdog_ms;
+#endif
};
#endif
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md
new file mode 100644
index 0000000000000..a5f52fdd550d8
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md
@@ -0,0 +1,140 @@
+# JFB-110 Flight Controller
+
+The JFB-110 flight controller is sold by [JAE](https://www.jae.com/Motion_Sensor_Control/eVTOL/FlightController/)
+
+## Features
+
+ - STM32H755 microcontroller
+ - Three IMUs: SCHA63T and IIM42652 x2
+ - Two BAROs: MS5611 SPI barometer x2
+ - builtin I2C IST8310 magnetometer
+ - microSD card slot
+ - 5 UARTs plus USB, RCIN, SBUS_OUT
+ - 16 PWM outputs
+ - Four I2C and two CAN ports
+ - External Buzzer (Open/Drain and 33V Out)
+ - external safety Switch
+ - voltage monitoring for servo rail and Vcc
+ - two dedicated power input ports for external power bricks
+
+## UART Mapping
+
+ - SERIAL0 -> USB
+ - SERIAL1 -> UART7 (Telem1)
+ - SERIAL2 -> UART5 (Telem2)
+ - SERIAL3 -> USART1 (GPS)
+ - SERIAL4 -> UART4 (GPS2, marked UART/I2CB)
+ - SERIAL5 -> USART6 (RCIN)
+ - SERIAL6 -> UART8 (SBUS_OUT)
+ - SERIAL7 -> USART3 (debug)
+ - SERIAL8 -> USB (SLCAN)
+
+
+The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not
+have RTS/CTS.
+
+The USART3 connector is labelled debug, but is available as a general
+purpose UART with ArduPilot.
+
+## RC Input
+
+RC input is configured on the port marked DSM/SBUS RC. This connector
+supports all RC protocols. Two cables are available for this port. To
+use software binding of Spektrum satellite receivers you need to use
+the Spektrum satellite cable.
+
+## PWM Output
+
+The JFB-110 supports up to 16 PWM outputs.
+These are directly attached to the STM32H755 and support all
+PWM protocols.
+
+The 16 PWM outputs are in 6 groups:
+ - PWM 1 and 2 in group1 (TIM15)
+ - PWM 3 and 4 in group2 (TIM3)
+ - PWM 5, 11 ,12 and 13 in group3 (TIM4)
+ - PWM 6 ,9 and 10 in group4 (TIM1)
+ - PWM 7 ,8 and 15 in group5 (TIM5)
+ - PWM 14 and 16 in group6 (TIM12)
+
+Channels within the same group need to use the same output rate. If
+any channel in a group uses DShot then all channels in the group need
+to use DShot.
+
+## Battery Monitoring
+
+The board has two dedicated power monitor ports on 8 pin
+connectors. The correct battery setting parameters are dependent on
+the type of power brick which is connected.
+Recomended input voltage is 4.9 to 5.5 volt.
+
+## Compass
+
+The JFB-110 has a builtin IST8310 compass. Due to potential
+interference the board is usually used with an external I2C compass as
+part of a GPS/Compass combination.
+
+## GPIOs
+
+The 16 PWM ports can be used as GPIOs (relays, buttons, RPM etc). To
+use them you need to limit the number of these pins that is used for
+PWM by setting the BRD_PWM_COUNT to a number less than 6. For example
+if you set BRD_PWM_COUNT to 4 then PWM5 and PWM6 will be available for
+use as GPIOs.
+
+The numbering of the GPIOs for PIN variables in ArduPilot is:
+ - PWM(1) 50
+ - PWM(2) 51
+ - PWM(3) 52
+ - PWM(4) 53
+ - PWM(5) 54
+ - PWM(6) 55
+ - PWM(7) 56
+ - PWM(8) 57
+ - PWM(9) 58
+ - PWM(10) 59
+ - PWM(11) 60
+ - PWM(12) 61
+ - PWM(13) 62
+ - PWM(14) 63
+ - PWM(15) 64
+ - PWM(16) 65
+ - FMU_CAP1 66
+ - FMU_CAP2 67
+
+
+## Analog inputs
+
+The JFB-110 has 9 analog inputs
+ - ADC Pin16 -> Battery Voltage
+ - ADC Pin18 -> Battery Current Sensor
+ - ADC Pin9 -> Battery Voltage 2
+ - ADC Pin6 -> Battery Current Sensor 2
+ - ADC Pin5 -> ADC 5V Sense
+ - ADC Pin11 -> ADC 3.3V Sense
+ - ADC Pin10 -> RSSI voltage monitoring
+ - ADC Pin13 -> ADC SPARE 1
+ - ADC Pin12 -> ADC SPARE 2
+
+## I2C Buses
+
+The JFB-110 has 4 I2C interfaces.
+I2C 3 is for internal only.
+ - the internal I2C port is bus 3 in ArduPilot (I2C3 in hardware)
+ - the port labelled I2CA is bus 4 in ArduPilot (I2C4 in hardware)
+ - the port labelled I2CB is bus 2 in ArduPilot (I2C2 in hardware)
+ - the port labelled GPS is bus 1 in ArduPilot (I2C1 in hardware)
+
+## CAN
+
+The JFB-110 has two independent CAN buses, with the following pinouts.
+
+## Debug
+
+The JFB-110 supports SWD debugging on the debug port
+
+## Loading Firmware
+
+The board comes pre-installed with an ArduPilot compatible bootloader,
+allowing the loading of *.apj firmware files with any ArduPilot
+compatible ground station.
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm
new file mode 100644
index 0000000000000..4207e693ce825
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm
@@ -0,0 +1,19 @@
+# board setting
+BRD_VBUS_MIN 4.9
+
+# setup SERIAL5 to RCIN
+SERIAL5_PROTOCOL 23
+
+# setup SERIAL6 to SBUS OUT
+SERIAL6_BAUD 100
+SERIAL6_PROTOCOL 15
+SERIAL6_OPTIONS 3
+
+#Three IMU Setting
+EK3_IMU_MASK 7
+
+
+#RSSI Setting
+RSSI_TYPE 1
+RSSI_ANA_PIN 10
+
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat
new file mode 100644
index 0000000000000..6a7b2f739bd48
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat
@@ -0,0 +1,139 @@
+# hw definition file for processing by chibios_hwdef.py
+# for the JFB110 hardware
+
+# board ID for firmware load
+APJ_BOARD_ID 1110
+
+# MCU class and specific type
+MCU STM32H7xx STM32H755xx
+define CORE_CM7
+#define SMPS_PWR
+
+# crystal frequency 24MHz
+OSCILLATOR_HZ 24000000
+
+# the location where the bootloader will put the firmware
+# bootloader is installed at zero offset
+FLASH_RESERVE_START_KB 0
+# the H755 has 128k sectors
+FLASH_BOOTLOADER_LOAD_KB 128
+# with 2M flash we can afford to optimize for speed
+FLASH_SIZE_KB 2048
+HAL_STORAGE_SIZE 32768
+
+env OPTIMIZE -Os
+
+# ChibiOS system timer
+STM32_ST_USE_TIMER 2
+
+# USB setup
+# USB_VENDOR 0x0A8E # JAE
+# USB_PRODUCT 0x8888 # This is temp Number
+USB_STRING_MANUFACTURER "Japan Aviation Electronics Industry Ltd."
+USB_STRING_PRODUCT "JFB-110"
+
+# order of UARTs (and USB)
+SERIAL_ORDER OTG1 UART7 UART5 USART3
+
+# serial port for stdout, set SERIAL7_PROTOCOL 0(none) when using
+# The value for STDOUT_SERIAL is a serial device name, and must be for a
+# serial device for which pins are defined in this file. For example, SD3
+# is for USART3 (SD3 == "serial device 3" in ChibiOS).
+STDOUT_SERIAL SD3
+STDOUT_BAUDRATE 921600
+
+# default to all pins low to avoid ESD issues
+DEFAULTGPIO OUTPUT LOW PULLDOWN
+
+# USB OTG1 SERIAL0
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+
+# pins for SWD debugging
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+# CS pins
+PH3 SCHA63T_G_CS CS # SPI1_CS1
+PH4 SCHA63T_A_CS CS # SPI1_CS2
+PH5 MS5611_2_CS CS # SPI1_CS3
+PG6 AT25512_CS CS # SPI1_CS4
+PG7 FRAM_CS CS # SPI3_CS1
+PF10 IIM42652_1_CS CS # SPI3_CS2
+PH15 MS5611_1_CS CS # SPI4_CS1
+PG15 IIM42652_2_CS CS # SPI4_CS2
+
+# telem1
+PE8 UART7_TX UART7
+PE10 UART7_CTS UART7
+PF6 UART7_RX UART7
+PF8 UART7_RTS UART7
+
+# telem2
+PC12 UART5_TX UART5
+PC9 UART5_CTS UART5
+PD2 UART5_RX UART5
+PC8 UART5_RTS UART5
+
+# debug uart
+PD8 USART3_TX USART3 NODMA
+PD9 USART3_RX USART3 NODMA
+
+# armed indication
+PB10 nARMED OUTPUT HIGH # TP8
+
+# This defines an output pin which will default to output HIGH. It is
+# a pin that enables peripheral power on this board. It starts in the
+# off state, then is pulled low to enable peripherals in
+# peripheral_power_enable()
+PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH
+PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH
+PG12 VDD_3V3_SENSORS_EN OUTPUT LOW
+PD4 VDD_3V3_SENSORS2_EN OUTPUT LOW
+PD3 VDD_3V3_SENSORS3_EN OUTPUT LOW
+#VDD_3V3_SENSORS4_EN OUTPUT LOW
+#VDD_3V3_SD_CARD_EN OUTPUT LOW
+
+# PWM output pins
+# we need to disable DMA on the last 2 FMU channels
+# as timer 12 doesn't have a TIMn_UP DMA option
+PA2 PWMOUT1 OUTPUT LOW
+PE6 PWMOUT2 OUTPUT LOW
+PA7 PWMOUT3 OUTPUT LOW
+PA6 PWMOUT4 OUTPUT LOW
+PD15 PWMOUT5 OUTPUT LOW
+PE9 PWMOUT6 OUTPUT LOW
+PH11 PWMOUT7 OUTPUT LOW
+PH10 PWMOUT8 OUTPUT LOW
+PA10 PWMOUT9 OUTPUT LOW
+PA9 PWMOUT10 OUTPUT LOW
+PD14 PWMOUT11 OUTPUT LOW
+PD13 PWMOUT12 OUTPUT LOW
+PD12 PWMOUT13 OUTPUT LOW
+PH9 PWMOUT14 OUTPUT LOW
+PH12 PWMOUT15 OUTPUT LOW
+PH6 PWMOUT16 OUTPUT LOW
+PD11 PWM_OE OUTPUT HIGH
+PD5 PWM_OE2 OUTPUT HIGH
+
+# controlled manually
+PG13 GPIO_CAN1_SILENT OUTPUT PUSHPULL HIGH
+PG8 GPIO_CAN2_SILENT OUTPUT PUSHPULL HIGH
+
+# Control of Spektrum power pin
+PH2 SPEKTRUM_PWR OUTPUT LOW GPIO(69)
+
+# LEDs
+#PE3 LED_RED OUTPUT OPENDRAIN GPIO(70) HIGH
+##PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(71) LOW
+##PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(72) LOW
+
+PE4 LED_BOOTLOADER OUTPUT HIGH
+PE5 LED_ACTIVITY OUTPUT HIGH
+define HAL_LED_ON 0
+
+#define HAL_USE_EMPTY_STORAGE 1
+#define HAL_STORAGE_SIZE 32768
+
+# enable DFU by default
+#ENABLE_DFU_BOOT 1
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat
new file mode 100644
index 0000000000000..42da12e0c1d70
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat
@@ -0,0 +1,355 @@
+# hw definition file for processing by chibios_hwdef.py
+# for the JFB110 hardware
+
+# board ID for firmware load
+APJ_BOARD_ID 1110
+
+# MCU class and specific type
+MCU STM32H7xx STM32H755xx
+define CORE_CM7
+#define SMPS_PWR
+
+# crystal frequency 24MHz
+OSCILLATOR_HZ 24000000
+
+# the H755 has 128k sectors
+# bootloader is installed at 128kb offset
+FLASH_BOOTLOADER_LOAD_KB 128
+FLASH_RESERVE_START_KB 128
+FLASH_SIZE_KB 2048
+HAL_STORAGE_SIZE 32768
+
+# USB setup
+# USB_VENDOR 0x0A8E # JAE
+USB_STRING_MANUFACTURER "Japan Aviation Electronics Industry Ltd."
+USB_STRING_PRODUCT "JFB-110"
+
+# ChibiOS system timer
+STM32_ST_USE_TIMER 2
+
+# enable board sub-type detection
+define CONFIG_HAL_BOARD HAL_BOARD_CHIBIOS
+#define HAL_CHIBIOS_ARCH_FMUV6 1
+#define AP_FEATURE_BOARD_DETECT 1
+#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV5
+#define HAL_CHIBIOS_ARCH_FMUV5 1
+
+env OPTIMIZE -O2
+
+# order of UARTs (and USB)
+# SERIAL | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 |
+SERIAL_ORDER OTG1 UART7 UART5 USART1 UART4 USART6 UART8 USART3 OTG2
+#USART6 is RX only for SBUS_IN
+#UART8 is TX only for SBUS_OUT
+
+# serial port for stdout, set SERIAL7_PROTOCOL 5(GPS) when using
+# The value for STDOUT_SERIAL is a serial device name, and must be for a
+# serial device for which pins are defined in this file. For example, SD3
+# is for USART3 (SD3 == "serial device 3" in ChibiOS).
+STDOUT_SERIAL SD3
+STDOUT_BAUDRATE 921600
+
+# default to all pins low to avoid ESD issues
+DEFAULTGPIO OUTPUT LOW PULLDOWN
+
+# USB OTG1 SERIAL0
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+# default the 2nd interface to MAVLink2
+define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
+
+# pins for SWD debugging
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+# telem1
+PE8 UART7_TX UART7 SPEED_VERYLOW
+PE10 UART7_CTS UART7 SPEED_VERYLOW
+PF6 UART7_RX UART7 SPEED_VERYLOW
+PF8 UART7_RTS UART7 SPEED_VERYLOW
+
+# telem2
+PC12 UART5_TX UART5 SPEED_VERYLOW
+PC9 UART5_CTS UART5 SPEED_VERYLOW
+PD2 UART5_RX UART5 SPEED_VERYLOW
+PC8 UART5_RTS UART5 SPEED_VERYLOW
+
+# telem3 for future use
+#PD5 TP14 OUTPUT LOW #TP14
+
+# GPS1
+PB6 USART1_TX USART1 SPEED_VERYLOW
+PB7 USART1_RX USART1 SPEED_VERYLOW
+
+# uart4
+PH13 UART4_TX UART4 SPEED_VERYLOW
+PH14 UART4_RX UART4 SPEED_VERYLOW
+
+# TX Only, for SBUS OUT
+PE0 UART8_RX UART8 SPEED_VERYLOW #TP3
+PE1 UART8_TX UART8 SPEED_VERYLOW
+
+# RX only, for RC input
+#PG14 USART6_TX USART6 SPEED_VERYLOW #TP10
+PC7 USART6_RX USART6 SPEED_VERYLOW
+
+# debug uart
+PD8 USART3_TX USART3 SPEED_VERYLOW NODMA
+PD9 USART3_RX USART3 SPEED_VERYLOW NODMA
+
+# ADC
+PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) # ADC1_16
+PF12 BATT_CURRENT_SENS ADC1 SCALE(1) # ADC1_6
+PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1) # ADC1_9
+PA4 BATT2_CURRENT_SENS ADC1 SCALE(1) # ADC1_18
+
+# setup scaling defaults for supplied power brick
+define HAL_BATT_VOLT_SCALE 1 #18.182
+define HAL_BATT_CURR_SCALE 1 #36.364
+define HAL_BATT2_VOLT_SCALE 1 #18.182
+define HAL_BATT2_CURR_SCALE 1 #36.364
+define HAL_BATT_VOLT_PIN 16
+define HAL_BATT_CURR_PIN 6
+define HAL_BATT2_VOLT_PIN 9
+define HAL_BATT2_CURR_PIN 18
+
+# Now the VDD sense pin. This is used to sense primary board voltage.
+PB1 VDD_5V_SENS ADC1 SCALE(2) # ADC1_5
+define ANALOG_VCC_5V_PIN 5
+define HAL_HAVE_BOARD_VOLTAGE 1
+PB3 VBUS_RESERVED INPUT
+
+# JFB110 has SERVORAIL ADC
+# Set SENSOR_3.3V power signal insted.
+PC1 SCALED_V3V3 ADC1 SCALE(2) # ADC1_11
+PA3 FMU_SERVORAIL_VCC ADC1 SCALE(2) # ADC1_15
+define FMU_SERVORAIL_ADC_PIN 15
+define HAL_HAVE_SERVO_VOLTAGE 1
+
+PC0 RSSI_IN ADC1 SCALE(1) # ADC1_10
+define RSSI_ANA_PIN 10
+
+PC2 ADC1_6V6 ADC1 SCALE(2) # ADC1_12
+PC3 ADC1_3V3 ADC1 SCALE(1) # ADC1_13
+
+# This defines an output pin which will default to output HIGH. It is
+# a pin that enables peripheral power on this board. It starts in the
+# off state, then is pulled low to enable peripherals in
+# peripheral_power_enable()
+PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH
+PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH
+PG12 VDD_3V3_SENSORS_EN OUTPUT LOW
+PD4 VDD_3V3_SENSORS2_EN OUTPUT LOW
+PD3 VDD_3V3_SENSORS3_EN OUTPUT LOW
+#VDD_3V3_SENSORS4_EN OUTPUT LOW
+#VDD_3V3_SD_CARD_EN OUTPUT LOW
+
+# controlled manually
+PG13 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW
+PG8 GPIO_CAN2_SILENT OUTPUT PUSHPULL LOW
+
+# Control of Spektrum power pin
+# no SPEKTRUM_RC pin so this is controlled
+# manually
+PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(69)
+define HAL_GPIO_SPEKTRUM_PWR 69
+define HAL_SPEKTRUM_PWR_ENABLED 1
+
+#Checked in Analogin.cpp -> MAV_POWER_STATUS
+PG1 VDD_BRICK_nVALID INPUT
+PG2 VDD_BRICK2_nVALID INPUT
+PG3 VBUS_nVALID INPUT
+PE15 VDD_5V_PERIPH_nOC INPUT
+PF13 VDD_5V_HIPOWER_nOC INPUT
+
+# ID pins
+PG0 HW_VER_REV_DRIVE OUTPUT LOW SPEED_VERYLOW
+PC4 HW_VER_SENS ADC1 SCALE(1) # ADC1_4
+PC5 HW_REV_SENS ADC1 SCALE(1) # ADC1_8
+
+# SPI1 - IMU1(murata),MS5611(BARO),EEPROM
+PA5 SPI1_SCK SPI1 SPEED_VERYLOW
+PB5 SPI1_MOSI SPI1 SPEED_VERYLOW
+PG9 SPI1_MISO SPI1 SPEED_VERYLOW
+PH3 SCHA63T_A_CS CS SPEED_VERYLOW # SPI1_CS1
+PH4 SCHA63T_G_CS CS SPEED_VERYLOW # SPI1_CS2
+PH5 MS5611_1_CS CS SPEED_VERYLOW # SPI1_CS3
+PG6 AT25512_CS CS SPEED_VERYLOW # SPI1_CS4
+
+# SPI2
+
+# SPI3 - FRAM,IMU2(42652)
+PB2 SPI3_MOSI SPI3 SPEED_VERYLOW
+PC10 SPI3_SCK SPI3 SPEED_VERYLOW
+PC11 SPI3_MISO SPI3 SPEED_VERYLOW
+PG7 FRAM_CS CS SPEED_VERYLOW # SPI3_CS1
+PF10 IIM42652_CS CS SPEED_VERYLOW # SPI3_CS2
+
+# SPI4 - MS5611(BARO),IMU3(42652),
+PE12 SPI4_SCK SPI4 SPEED_VERYLOW
+PE13 SPI4_MISO SPI4 SPEED_VERYLOW
+PE14 SPI4_MOSI SPI4 SPEED_VERYLOW
+PH15 MS5611_2_CS CS SPEED_VERYLOW # SPI4_CS1
+PG15 IIM42652_2_CS CS SPEED_VERYLOW # SPI4_CS2
+
+# SPI5 - External SPI I/F
+#PF7 SPI5_SCK SPI5 SPEED_VERYLOW
+#PH7 SPI5_MISO SPI5 SPEED_VERYLOW
+#PF11 SPI5_MOSI SPI5 SPEED_VERYLOW
+#PE2 SPI5_CS1 CS SPEED_VERYLOW
+
+# IMU Device Ready Signal Input
+PF3 DRDY1_IIM42652_1 INPUT
+PF2 DRDY2_IIM42652_1 INPUT
+PA15 DRDY1_IIM42652_2 INPUT
+PA1 DRDY2_IIM42652_2 INPUT
+
+PE7 SCHA63T_RESET OUTPUT LOW
+
+# SPI devices
+SPIDEV scha63t_g SPI1 DEVID1 SCHA63T_G_CS MODE0 10*MHZ 10*MHZ
+SPIDEV scha63t_a SPI1 DEVID2 SCHA63T_A_CS MODE0 10*MHZ 10*MHZ
+SPIDEV ms5611_1 SPI1 DEVID3 MS5611_1_CS MODE3 20*MHZ 20*MHZ
+SPIDEV at25512 SPI1 DEVID4 AT25512_CS MODE3 2*MHZ 8*MHZ
+SPIDEV ramtron SPI3 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
+SPIDEV iim42652_1 SPI3 DEVID2 IIM42652_CS MODE3 2*MHZ 8*MHZ
+SPIDEV ms5611_2 SPI4 DEVID1 MS5611_2_CS MODE3 20*MHZ 20*MHZ
+SPIDEV iim42652_2 SPI4 DEVID2 IIM42652_2_CS MODE3 2*MHZ 8*MHZ
+#define HAL_SPI_CHECK_CLOCK_FREQ
+
+# JFB110 has 3 IMUs
+# IMU devices for JFB110. The JFB110 board has a SCHA63T, two ICM42652,
+# the SCHA63T and ICM42652_1 are on the same SPI buses and CS pins.
+# The IIM42652_2 is on a different bus
+IMU SCHA63T SPI:scha63t_a SPI:scha63t_g ROTATION_NONE
+IMU Invensensev3 SPI:iim42652_1 ROTATION_NONE
+IMU Invensensev3 SPI:iim42652_2 ROTATION_NONE
+
+# JFB110 has 2 BAROs
+BARO MS56XX SPI:ms5611_1
+BARO MS56XX SPI:ms5611_2
+
+define HAL_DEFAULT_INS_FAST_SAMPLE 7
+
+# PWM output pins
+# we need to disable DMA on the last 2 FMU channels
+# as timer 12 doesn't have a TIMn_UP DMA option
+PA2 TIM15_CH1 TIM15 PWM(1) GPIO(50) SPEED_VERYLOW
+PE6 TIM15_CH2 TIM15 PWM(2) GPIO(51) SPEED_VERYLOW
+PA7 TIM3_CH2 TIM3 PWM(3) GPIO(52) SPEED_VERYLOW
+PA6 TIM3_CH1 TIM3 PWM(4) GPIO(53) SPEED_VERYLOW
+PD15 TIM4_CH4 TIM4 PWM(5) GPIO(54) SPEED_VERYLOW
+PE9 TIM1_CH1 TIM1 PWM(6) GPIO(55) SPEED_VERYLOW
+PH11 TIM5_CH2 TIM5 PWM(7) GPIO(56) SPEED_VERYLOW
+PH10 TIM5_CH1 TIM5 PWM(8) GPIO(57) SPEED_VERYLOW
+PA10 TIM1_CH3 TIM1 PWM(9) GPIO(58) SPEED_VERYLOW
+PA9 TIM1_CH2 TIM1 PWM(10) GPIO(59) SPEED_VERYLOW
+PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) SPEED_VERYLOW
+PD13 TIM4_CH2 TIM4 PWM(12) GPIO(61) SPEED_VERYLOW
+PD12 TIM4_CH1 TIM4 PWM(13) GPIO(62) SPEED_VERYLOW
+PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) SPEED_VERYLOW NODMA
+PH12 TIM5_CH3 TIM5 PWM(15) GPIO(64) SPEED_VERYLOW
+PH6 TIM12_CH1 TIM12 PWM(16) GPIO(65) SPEED_VERYLOW NODMA
+PD11 PWM_OE OUTPUT HIGH
+PD5 PWM_OE2 OUTPUT HIGH
+
+# GPIOs
+PE11 FMU_CAP1 INPUT GPIO(66)
+PB11 FMU_CAP2 INPUT GPIO(67)
+
+# CAN bus
+PD0 CAN1_RX CAN1 SPEED_VERYLOW
+PD1 CAN1_TX CAN1 SPEED_VERYLOW
+PB12 CAN2_RX CAN2 SPEED_VERYLOW
+PB13 CAN2_TX CAN2 SPEED_VERYLOW
+
+# I2C buses
+# I2C1, GPS+MAG
+PB8 I2C1_SCL I2C1
+PB9 I2C1_SDA I2C1
+
+# I2C2, GPS2+MAG
+PF1 I2C2_SCL I2C2
+PF0 I2C2_SDA I2C2
+
+# I2C3, IST8310 Internal
+PA8 I2C3_SCL I2C3 SPEED_VERYLOW
+PH8 I2C3_SDA I2C3 SPEED_VERYLOW
+
+# I2C4 external
+PF14 I2C4_SCL I2C4
+PF15 I2C4_SDA I2C4
+
+# order of I2C buses
+I2C_ORDER I2C3 I2C1 I2C2 I2C4
+define HAL_I2C_INTERNAL_MASK 1
+
+# this board is very tight on DMA channels. To allow for more UART DMA
+# we disable DMA on I2C. This also prevents a problem with DMA on I2C
+# interfering with IMUs
+NODMA I2C*
+define STM32_I2C_USE_DMA FALSE
+
+# builtin compass on JAE JFB110
+define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
+define HAL_PROBE_EXTERNAL_I2C_COMPASSES
+COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_270
+COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
+
+# armed indication
+PB10 nARMED OUTPUT HIGH # TP8
+
+# microSD support
+PD6 SDMMC2_CK SDMMC2 SPEED_VERYLOW
+PD7 SDMMC2_CMD SDMMC2 SPEED_VERYLOW
+PB14 SDMMC2_D0 SDMMC2 SPEED_VERYLOW
+PB15 SDMMC2_D1 SDMMC2 SPEED_VERYLOW
+PG11 SDMMC2_D2 SDMMC2 SPEED_VERYLOW
+PB4 SDMMC2_D3 SDMMC2 SPEED_VERYLOW
+define FATFS_HAL_DEVICE SDCD2
+PC13 SD_CARD_EN INPUT
+
+# safety
+PD10 LED_SAFETY OUTPUT
+PF5 SAFETY_IN INPUT PULLDOWN
+
+# LEDs
+PE3 LED_RED OUTPUT OPENDRAIN GPIO(70) HIGH SPEED_VERYLOW
+PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(71) LOW SPEED_VERYLOW
+PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(72) HIGH SPEED_VERYLOW
+
+# setup for "AP_BoardLED" RGB LEDs
+define HAL_GPIO_A_LED_PIN 72
+define HAL_GPIO_B_LED_PIN 70
+#define HAL_GPIO_C_LED_PIN 71
+define HAL_GPIO_LED_ON 0
+
+# PWM output for buzzer
+PF9 TIM14_CH1 TIM14 GPIO(73) ALARM SPEED_VERYLOW
+
+# RC input (PPM)
+PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW
+
+# enable RAMTRON parameter storage
+define HAL_STORAGE_SIZE 32768
+define HAL_WITH_RAMTRON 1
+
+# allow to have a dedicated safety switch pin
+define HAL_HAVE_SAFETY_SWITCH 1
+
+DMA_PRIORITY SDMMC* UART* USART* ADC* SPI* TIM*
+
+# enable FAT filesystem support (needs a microSD defined via SDMMC)
+define HAL_OS_FATFS_IO 1
+# for building Copter-4.3.7
+define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
+define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
+
+# enable DFU reboot for installing bootloader
+# note that if firmware is build with --secure-bl then DFU is
+# disabled
+ENABLE_DFU_BOOT 1
+
+# External watchdog gpio
+PG5 EXT_WDOG OUTPUT SPEED_VERYLOW
+define EXT_WDOG_INTERVAL_MS 50
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py
new file mode 100644
index 0000000000000..405511f9b2725
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py
@@ -0,0 +1,1304 @@
+#!/usr/bin/env python
+'''
+these tables are generated from the STM32 datasheets for the STM32H755
+'''
+
+# additional build information for ChibiOS
+build = {
+ "CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32h7xx.mk",
+ "CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32H7xx/platform.mk"
+ }
+
+# MCU parameters
+mcu = {
+ # location of MCU serial number
+ 'UDID_START' : 0x1FF1E800,
+
+ # DMA peripheral capabilities:
+ # - can't use ITCM or DTCM for any DMA
+ # - SPI1 to SPI5 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 for DMA
+ # - SPI6, I2C4 and ADC3 can use SRAM4 on BDMA
+ # - UARTS can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 for DMA
+ # - I2C1, I2C2 and I2C3 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 with DMA
+ # - timers can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 with DMA
+ # - ADC12 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4
+ # - SDMMC can use AXI SRAM, SRAM1 to SRAM3 with IDMA (cannot use SRAM4)
+
+ # ram map, as list of (address, size-kb, flags)
+ # flags of 1 means DMA-capable (DMA and BDMA)
+ # flags of 2 means faster memory for CPU intensive work
+ # flags of 4 means memory can be used for SDMMC DMA
+ 'RAM_MAP' : [
+ (0x30000000, 256, 0), # SRAM1, SRAM2
+ (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
+ (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
+ (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
+ (0x30040000, 32, 0), # SRAM3.
+ (0x38000000, 64, 1), # SRAM4.
+ ],
+ # alternative RAM_MAP needed for px4 bootloader compatibility
+ 'ALT_RAM_MAP' : [
+ (0x24000000, 512, 4), # AXI SRAM.
+ (0x30000000, 256, 0), # SRAM1, SRAM2
+ (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
+ (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
+ (0x30040000, 32, 0), # SRAM3.
+ (0x38000000, 64, 1), # SRAM4.
+ ],
+ 'RAM_MAP_EXTERNAL_FLASH' : [
+ # SSBL checks that stack is in this region so needs to come first
+ (0x30000000, 256, 0), # SRAM1, SRAM2
+ (0x20000000, 64, 2), # DTCM, tightly coupled, no DMA, fast
+ (0x24000000, 128, 4), # AXI SRAM. Use this for SDMMC IDMA ops
+ (0x30040000, 32, 0), # SRAM3.
+ (0x38000000, 64, 1), # SRAM4.
+ ],
+ 'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
+ 'FLASH_RAM' : (0x24020000, 384), # AXI SRAM used for process stack and ram functions
+ 'DATA_RAM' : (0x20010000, 64), # DTCM, tightly coupled, no DMA, fast
+
+ # avoid a problem in the bootloader by making DTCM first. The DCache init
+ # when using SRAM1 as primary memory gets a hard fault in bootloader
+ # we can't use DTCM first for main firmware as some builds overflow the first segment
+ 'RAM_MAP_BOOTLOADER' : [
+ (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
+ (0x30000000, 256, 0), # SRAM1, SRAM2
+ (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
+ (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
+ (0x30040000, 32, 0), # SRAM3.
+ (0x38000000, 64, 1), # SRAM4.
+ ],
+
+ 'EXPECTED_CLOCK' : 400000000,
+
+ # this MCU has M7 instructions and hardware double precision
+ 'CORTEX' : 'cortex-m7',
+ 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
+
+ 'DEFINES' : {
+ 'HAL_HAVE_HARDWARE_DOUBLE' : '1',
+ 'HAL_WITH_MCU_MONITORING' : '1',
+ 'STM32H7' : '1',
+ }
+}
+
+pincount = {
+ 'A': 16,
+ 'B': 16,
+ 'C': 16,
+ 'D': 16,
+ 'E': 16,
+ 'F': 16,
+ 'G': 16,
+ 'H': 16,
+ 'I': 16,
+ 'J': 16,
+ 'K': 16
+}
+
+# no DMA map as we will dynamically allocate DMA channels using the DMAMUX
+DMA_Map = None
+
+AltFunction_map = {
+ # format is PIN:FUNCTION : AFNUM
+ # extracted from tabula-AF-H743.csv
+ "PA0:ETH_MII_CRS" : 11,
+ "PA0:EVENT-OUT" : 15,
+ "PA0:SAI2_SD_B" : 10,
+ "PA0:SDMMC2_CMD" : 9,
+ "PA0:TIM15_BKIN" : 4,
+ "PA0:TIM2_CH1" : 1,
+ "PA0:TIM2_ETR" : 1,
+ "PA0:TIM5_CH1" : 2,
+ "PA0:TIM8_ETR" : 3,
+ "PA0:UART4_TX" : 8,
+ "PA0:USART2_CTS" : 7,
+ "PA1:ETH_MII_RX_CLK" : 11,
+ "PA1:ETH_RMII_REF_CLK" : 11,
+ "PA1:EVENT-OUT" : 15,
+ "PA1:LCD_R2" : 14,
+ "PA1:LPTIM3_OUT" : 3,
+ "PA1:QUADSPI_BK1_IO3" : 9,
+ "PA1:SAI2_MCK_B" : 10,
+ "PA1:TIM15_CH1N" : 4,
+ "PA1:TIM2_CH2" : 1,
+ "PA1:TIM5_CH2" : 2,
+ "PA1:UART4_RX" : 8,
+ "PA1:USART2_RTS" : 7,
+ "PA2:ETH_MDIO" : 11,
+ "PA2:EVENT-OUT" : 15,
+ "PA2:LCD_R1" : 14,
+ "PA2:LPTIM4_OUT" : 3,
+ "PA2:MDIOS_MDIO" : 12,
+ "PA2:SAI2_SCK_B" : 8,
+ "PA2:TIM15_CH1" : 4,
+ "PA2:TIM2_CH3" : 1,
+ "PA2:TIM5_CH3" : 2,
+ "PA2:USART2_TX" : 7,
+ "PA3:ETH_MII_COL" : 11,
+ "PA3:EVENT-OUT" : 15,
+ "PA3:LCD_B2" : 9,
+ "PA3:LCD_B5" : 14,
+ "PA3:LPTIM5_OUT" : 3,
+ "PA3:OTG_HS_ULPI_D0" : 10,
+ "PA3:TIM15_CH2" : 4,
+ "PA3:TIM2_CH4" : 1,
+ "PA3:TIM5_CH4" : 2,
+ "PA3:USART2_RX" : 7,
+ "PA4:DCMI_HSYNC" : 13,
+ "PA4:EVENT-OUT" : 15,
+ "PA4:I2S1_WS" : 5,
+ "PA4:I2S3_WS" : 6,
+ "PA4:LCD_VSYNC" : 14,
+ "PA4:OTG_HS_SOF" : 12,
+ "PA4:SPI1_NSS" : 5,
+ "PA4:SPI3_NSS" : 6,
+ "PA4:SPI6_NSS" : 8,
+ "PA4:TIM5_ETR" : 2,
+ "PA4:USART2_CK" : 7,
+ "PA5:EVENT-OUT" : 15,
+ "PA5:I2S1_CK" : 5,
+ "PA5:LCD_R4" : 14,
+ "PA5:OTG_HS_ULPI_CK" : 10,
+ "PA5:SPI1_SCK" : 5,
+ "PA5:SPI6_SCK" : 8,
+ "PA5:TIM2_CH1" : 1,
+ "PA5:TIM2_ETR" : 1,
+ "PA5:TIM8_CH1N" : 3,
+ "PA6:DCMI_PIXCLK" : 13,
+ "PA6:EVENT-OUT" : 15,
+ "PA6:I2S1_SDI" : 5,
+ "PA6:LCD_G2" : 14,
+ "PA6:MDIOS_MDC" : 11,
+ "PA6:SPI1_MISO" : 5,
+ "PA6:SPI6_MISO" : 8,
+ "PA6:TIM13_CH1" : 9,
+ "PA6:TIM1_BKIN" : 1,
+ "PA6:TIM1_BKIN_COMP12" : 12,
+ "PA6:TIM3_CH1" : 2,
+ "PA6:TIM8_BKIN" : 3,
+ "PA6:TIM8_BKIN_COMP12" : 10,
+ "PA7:ETH_MII_RX_DV" : 11,
+ "PA7:ETH_RMII_CRS_DV" : 11,
+ "PA7:EVENT-OUT" : 15,
+ "PA7:FMC_SDNWE" : 12,
+ "PA7:I2S1_SDO" : 5,
+ "PA7:SPI1_MOSI" : 5,
+ "PA7:SPI6_MOSI" : 8,
+ "PA7:TIM14_CH1" : 9,
+ "PA7:TIM1_CH1N" : 1,
+ "PA7:TIM3_CH2" : 2,
+ "PA7:TIM8_CH1N" : 3,
+ "PA8:EVENT-OUT" : 15,
+ "PA8:HRTIM_CHB2" : 2,
+ "PA8:I2C3_SCL" : 4,
+ "PA8:LCD_B3" : 13,
+ "PA8:LCD_R6" : 14,
+ "PA8:MCO1" : 0,
+ "PA8:OTG_FS_SOF" : 10,
+ "PA8:TIM1_CH1" : 1,
+ "PA8:TIM8_BKIN2" : 3,
+ "PA8:TIM8_BKIN2_COMP12" : 12,
+ "PA8:UART7_RX" : 11,
+ "PA8:USART1_CK" : 7,
+ "PA9:DCMI_D0" : 13,
+ "PA9:EVENT-OUT" : 15,
+ "PA9:CAN1_RX" : 9,
+ "PA9:HRTIM_CHC1" : 2,
+ "PA9:I2C3_SMBA" : 4,
+ "PA9:I2S2_CK" : 5,
+ "PA9:LCD_R5" : 14,
+ "PA9:LPUART1_TX" : 3,
+ "PA9:SPI2_SCK" : 5,
+ "PA9:TIM1_CH2" : 1,
+ "PA9:USART1_TX" : 7,
+ "PA10:DCMI_D1" : 13,
+ "PA10:EVENT-OUT" : 15,
+ "PA10:CAN1_TX" : 9,
+ "PA10:HRTIM_CHC2" : 2,
+ "PA10:LCD_B1" : 14,
+ "PA10:LCD_B4" : 12,
+ "PA10:LPUART1_RX" : 3,
+ "PA10:MDIOS_MDIO" : 11,
+ "PA10:OTG_FS_ID" : 10,
+ "PA10:TIM1_CH3" : 1,
+ "PA10:USART1_RX" : 7,
+ "PA11:EVENT-OUT" : 15,
+ "PA11:CAN1_RX" : 9,
+ "PA11:HRTIM_CHD1" : 2,
+ "PA11:I2S2_WS" : 5,
+ "PA11:LCD_R4" : 14,
+ "PA11:LPUART1_CTS" : 3,
+ "PA11:OTG_FS_DM" : 10,
+ "PA11:SPI2_NSS" : 5,
+ "PA11:TIM1_CH4" : 1,
+ "PA11:UART4_RX" : 6,
+ "PA11:USART1_CTS_NSS" : 7,
+ "PA12:EVENT-OUT" : 15,
+ "PA12:CAN1_TX" : 9,
+ "PA12:HRTIM_CHD2" : 2,
+ "PA12:I2S2_CK" : 5,
+ "PA12:LCD_R5" : 14,
+ "PA12:LPUART1_RTS" : 3,
+ "PA12:OTG_FS_DP" : 10,
+ "PA12:SAI2_FS_B" : 8,
+ "PA12:SPI2_SCK" : 5,
+ "PA12:TIM1_ETR" : 1,
+ "PA12:UART4_TX" : 6,
+ "PA12:USART1_RTS" : 7,
+ "PA13:EVENT-OUT" : 15,
+ "PA13:JTMS-SWDIO" : 0,
+ "PA14:EVENT-OUT" : 15,
+ "PA14:JTCK-SWCLK" : 0,
+ "PA15:EVENT-OUT" : 15,
+ "PA15:HDMI_CEC" : 4,
+ "PA15:HRTIM_FLT1" : 2,
+ "PA15:I2S1_WS" : 5,
+ "PA15:I2S3_WS" : 6,
+ "PA15:JTDI" : 0,
+ "PA15:SPI1_NSS" : 5,
+ "PA15:SPI3_NSS" : 6,
+ "PA15:SPI6_NSS" : 7,
+ "PA15:TIM2_CH1" : 1,
+ "PA15:TIM2_ETR" : 1,
+ "PA15:UART4_RTS" : 8,
+ "PA15:UART7_TX" : 11,
+ "PB0:DFSDM_CKOUT" : 6,
+ "PB0:ETH_MII_RXD2" : 11,
+ "PB0:EVENT-OUT" : 15,
+ "PB0:LCD_G1" : 14,
+ "PB0:LCD_R3" : 9,
+ "PB0:OTG_HS_ULPI_D1" : 10,
+ "PB0:TIM1_CH2N" : 1,
+ "PB0:TIM3_CH3" : 2,
+ "PB0:TIM8_CH2N" : 3,
+ "PB0:UART4_CTS" : 8,
+ "PB1:DFSDM_DATIN1" : 6,
+ "PB1:ETH_MII_RXD3" : 11,
+ "PB1:EVENT-OUT" : 15,
+ "PB1:LCD_G0" : 14,
+ "PB1:LCD_R6" : 9,
+ "PB1:OTG_HS_ULPI_D2" : 10,
+ "PB1:TIM1_CH3N" : 1,
+ "PB1:TIM3_CH4" : 2,
+ "PB1:TIM8_CH3N" : 3,
+ "PB2:DFSDM_CKIN1" : 4,
+ "PB2:EVENT-OUT" : 15,
+ "PB2:I2S3_SDO" : 7,
+ "PB2:QUADSPI_CLK" : 9,
+ "PB2:SAI1_D1" : 2,
+ "PB2:SAI1_SD_A" : 6,
+ "PB2:SAI4_D1" : 10,
+ "PB2:SAI4_SD_A" : 8,
+ "PB2:SPI3_MOSI" : 7,
+ "PB3:EVENT-OUT" : 15,
+ "PB3:HRTIM_FLT4" : 2,
+ "PB3:I2S1_CK" : 5,
+ "PB3:I2S3_CK" : 6,
+ "PB3:JTDO" : 0,
+ "PB3:SDMMC2_D2" : 9,
+ "PB3:SPI1_SCK" : 5,
+ "PB3:SPI3_SCK" : 6,
+ "PB3:SPI6_SCK" : 8,
+ "PB3:TIM2_CH2" : 1,
+ "PB3:TRACESWO" : 0,
+ "PB3:UART7_RX" : 11,
+ "PB4:EVENT-OUT" : 15,
+ "PB4:HRTIM_EEV6" : 3,
+ "PB4:I2S1_SDI" : 5,
+ "PB4:I2S2_WS" : 7,
+ "PB4:I2S3_SDI" : 6,
+ "PB4:NJTRST" : 0,
+ "PB4:SDMMC2_D3" : 9,
+ "PB4:SPI1_MISO" : 5,
+ "PB4:SPI2_NSS" : 7,
+ "PB4:SPI3_MISO" : 6,
+ "PB4:SPI6_MISO" : 8,
+ "PB4:TIM16_BKIN" : 1,
+ "PB4:TIM3_CH1" : 2,
+ "PB4:UART7_TX" : 11,
+ "PB5:DCMI_D10" : 13,
+ "PB5:ETH_PPS_OUT" : 11,
+ "PB5:EVENT-OUT" : 15,
+ "PB5:CAN2_RX" : 9,
+ "PB5:FMC_SDCKE1" : 12,
+ "PB5:HRTIM_EEV7" : 3,
+ "PB5:I2C1_SMBA" : 4,
+ "PB5:I2C4_SMBA" : 6,
+ "PB5:I2S1_SDO" : 5,
+ "PB5:I2S3_SDO" : 7,
+ "PB5:OTG_HS_ULPI_D7" : 10,
+ "PB5:SPI1_MOSI" : 5,
+ "PB5:SPI3_MOSI" : 7,
+ "PB5:SPI6_MOSI" : 8,
+ "PB5:TIM17_BKIN" : 1,
+ "PB5:TIM3_CH2" : 2,
+ "PB5:UART5_RX" : 14,
+ "PB6:DCMI_D5" : 13,
+ "PB6:DFSDM_DATIN5" : 11,
+ "PB6:EVENT-OUT" : 15,
+ "PB6:CAN2_TX" : 9,
+ "PB6:FMC_SDNE1" : 12,
+ "PB6:HDMI_CEC" : 5,
+ "PB6:HRTIM_EEV8" : 3,
+ "PB6:I2C1_SCL" : 4,
+ "PB6:I2C4_SCL" : 6,
+ "PB6:LPUART1_TX" : 8,
+ "PB6:QUADSPI_BK1_NCS" : 10,
+ "PB6:TIM16_CH1N" : 1,
+ "PB6:TIM4_CH1" : 2,
+ "PB6:UART5_TX" : 14,
+ "PB6:USART1_TX" : 7,
+ "PB7:DCMI_VSYNC" : 13,
+ "PB7:DFSDM_CKIN5" : 11,
+ "PB7:EVENT-OUT" : 15,
+ "PB7:CAN2_TX" : 9,
+ "PB7:FMC_NL" : 12,
+ "PB7:HRTIM_EEV9" : 3,
+ "PB7:I2C1_SDA" : 4,
+ "PB7:I2C4_SDA" : 6,
+ "PB7:LPUART1_RX" : 8,
+ "PB7:TIM17_CH1N" : 1,
+ "PB7:TIM4_CH2" : 2,
+ "PB7:USART1_RX" : 7,
+ "PB8:DCMI_D6" : 13,
+ "PB8:DFSDM_CKIN7" : 3,
+ "PB8:ETH_MII_TXD3" : 11,
+ "PB8:EVENT-OUT" : 15,
+ "PB8:CAN1_RX" : 9,
+ "PB8:I2C1_SCL" : 4,
+ "PB8:I2C4_SCL" : 6,
+ "PB8:LCD_B6" : 14,
+ "PB8:SDMMC1_CKIN" : 7,
+ "PB8:SDMMC1_D4" : 12,
+ "PB8:SDMMC2_D4" : 10,
+ "PB8:TIM16_CH1" : 1,
+ "PB8:TIM4_CH3" : 2,
+ "PB8:UART4_RX" : 8,
+ "PB9:DCMI_D7" : 13,
+ "PB9:DFSDM_DATIN7" : 3,
+ "PB9:EVENT-OUT" : 15,
+ "PB9:CAN1_TX" : 9,
+ "PB9:I2C1_SDA" : 4,
+ "PB9:I2C4_SDA" : 6,
+ "PB9:I2C4_SMBA" : 11,
+ "PB9:I2S2_WS" : 5,
+ "PB9:LCD_B7" : 14,
+ "PB9:SDMMC1_CDIR" : 7,
+ "PB9:SDMMC1_D5" : 12,
+ "PB9:SDMMC2_D5" : 10,
+ "PB9:SPI2_NSS" : 5,
+ "PB9:TIM17_CH1" : 1,
+ "PB9:TIM4_CH4" : 2,
+ "PB9:UART4_TX" : 8,
+ "PB10:DFSDM_DATIN7" : 6,
+ "PB10:ETH_MII_RX_ER" : 11,
+ "PB10:EVENT-OUT" : 15,
+ "PB10:HRTIM_SCOUT" : 2,
+ "PB10:I2C2_SCL" : 4,
+ "PB10:I2S2_CK" : 5,
+ "PB10:LCD_G4" : 14,
+ "PB10:LPTIM2_IN1" : 3,
+ "PB10:OTG_HS_ULPI_D3" : 10,
+ "PB10:QUADSPI_BK1_NCS" : 9,
+ "PB10:SPI2_SCK" : 5,
+ "PB10:TIM2_CH3" : 1,
+ "PB10:USART3_TX" : 7,
+ "PB11:DFSDM_CKIN7" : 6,
+ "PB11:ETH_MII_TX_EN" : 11,
+ "PB11:ETH_RMII_TX_EN" : 11,
+ "PB11:EVENT-OUT" : 15,
+ "PB11:HRTIM_SCIN" : 2,
+ "PB11:I2C2_SDA" : 4,
+ "PB11:LCD_G5" : 14,
+ "PB11:LPTIM2_ETR" : 3,
+ "PB11:OTG_HS_ULPI_D4" : 10,
+ "PB11:TIM2_CH4" : 1,
+ "PB11:USART3_RX" : 7,
+ "PB12:DFSDM_DATIN1" : 6,
+ "PB12:ETH_MII_TXD0" : 11,
+ "PB12:ETH_RMII_TXD0" : 11,
+ "PB12:EVENT-OUT" : 15,
+ "PB12:CAN2_RX" : 9,
+ "PB12:I2C2_SMBA" : 4,
+ "PB12:I2S2_WS" : 5,
+ "PB12:OTG_HS_ID" : 12,
+ "PB12:OTG_HS_ULPI_D5" : 10,
+ "PB12:SPI2_NSS" : 5,
+ "PB12:TIM1_BKIN" : 1,
+ "PB12:TIM1_BKIN_COMP12" : 13,
+ "PB12:UART5_RX" : 14,
+ "PB12:USART3_CK" : 7,
+ "PB13:DFSDM_CKIN1" : 6,
+ "PB13:ETH_MII_TXD1" : 11,
+ "PB13:ETH_RMII_TXD1" : 11,
+ "PB13:EVENT-OUT" : 15,
+ "PB13:CAN2_TX" : 9,
+ "PB13:I2S2_CK" : 5,
+ "PB13:LPTIM2_OUT" : 3,
+ "PB13:OTG_HS_ULPI_D6" : 10,
+ "PB13:SPI2_SCK" : 5,
+ "PB13:TIM1_CH1N" : 1,
+ "PB13:UART5_TX" : 14,
+ "PB13:USART3_CTS_NSS" : 7,
+ "PB14:DFSDM_DATIN2" : 6,
+ "PB14:EVENT-OUT" : 15,
+ "PB14:I2S2_SDI" : 5,
+ "PB14:OTG_HS_DM" : 12,
+ "PB14:SDMMC2_D0" : 9,
+ "PB14:SPI2_MISO" : 5,
+ "PB14:TIM12_CH1" : 2,
+ "PB14:TIM1_CH2N" : 1,
+ "PB14:TIM8_CH2N" : 3,
+ "PB14:UART4_RTS" : 8,
+ "PB14:USART1_TX" : 4,
+ "PB14:USART3_RTS" : 7,
+ "PB15:DFSDM_CKIN2" : 6,
+ "PB15:EVENT-OUT" : 15,
+ "PB15:I2S2_SDO" : 5,
+ "PB15:OTG_HS_DP" : 12,
+ "PB15:RTC_REFIN" : 0,
+ "PB15:SDMMC2_D1" : 9,
+ "PB15:SPI2_MOSI" : 5,
+ "PB15:TIM12_CH2" : 2,
+ "PB15:TIM1_CH3N" : 1,
+ "PB15:TIM8_CH3N" : 3,
+ "PB15:UART4_CTS" : 8,
+ "PB15:USART1_RX" : 4,
+ "PC0:DFSDM_CKIN0" : 3,
+ "PC0:DFSDM_DATIN4" : 6,
+ "PC0:EVENT-OUT" : 15,
+ "PC0:FMC_SDNWE" : 12,
+ "PC0:LCD_R5" : 14,
+ "PC0:OTG_HS_ULPI_STP" : 10,
+ "PC0:SAI2_FS_B" : 8,
+ "PC1:DFSDM_CKIN4" : 4,
+ "PC1:DFSDM_DATIN0" : 3,
+ "PC1:ETH_MDC" : 11,
+ "PC1:EVENT-OUT" : 15,
+ "PC1:I2S2_SDO" : 5,
+ "PC1:MDIOS_MDC" : 12,
+ "PC1:SAI1_D1" : 2,
+ "PC1:SAI1_SD_A" : 6,
+ "PC1:SAI4_D1" : 10,
+ "PC1:SAI4_SD_A" : 8,
+ "PC1:SDMMC2_CK" : 9,
+ "PC1:SPI2_MOSI" : 5,
+ "PC1:TRACED0" : 0,
+ "PC2:DFSDM_CKIN1" : 3,
+ "PC2:DFSDM_CKOUT" : 6,
+ "PC2:ETH_MII_TXD2" : 11,
+ "PC2:EVENT-OUT" : 15,
+ "PC2:FMC_SDNE0" : 12,
+ "PC2:I2S2_SDI" : 5,
+ "PC2:OTG_HS_ULPI_DIR" : 10,
+ "PC2:SPI2_MISO" : 5,
+ "PC3:DFSDM_DATIN1" : 3,
+ "PC3:ETH_MII_TX_CLK" : 11,
+ "PC3:EVENT-OUT" : 15,
+ "PC3:FMC_SDCKE0" : 12,
+ "PC3:I2S2_SDO" : 5,
+ "PC3:OTG_HS_ULPI_NXT" : 10,
+ "PC3:SPI2_MOSI" : 5,
+ "PC4:DFSDM_CKIN2" : 3,
+ "PC4:ETH_MII_RXD0" : 11,
+ "PC4:ETH_RMII_RXD0" : 11,
+ "PC4:EVENT-OUT" : 15,
+ "PC4:FMC_SDNE0" : 12,
+ "PC4:I2S1_MCK" : 5,
+ "PC4:SPDIFRX_IN2" : 9,
+ "PC5:COMP_1_OUT" : 13,
+ "PC5:DFSDM_DATIN2" : 3,
+ "PC5:ETH_MII_RXD1" : 11,
+ "PC5:ETH_RMII_RXD1" : 11,
+ "PC5:EVENT-OUT" : 15,
+ "PC5:FMC_SDCKE0" : 12,
+ "PC5:SAI1_D3" : 2,
+ "PC5:SAI4_D3" : 10,
+ "PC5:SPDIFRX_IN3" : 9,
+ "PC6:DCMI_D0" : 13,
+ "PC6:DFSDM_CKIN3" : 4,
+ "PC6:EVENT-OUT" : 15,
+ "PC6:FMC_NWAIT" : 9,
+ "PC6:HRTIM_CHA1" : 1,
+ "PC6:I2S2_MCK" : 5,
+ "PC6:LCD_HSYNC" : 14,
+ "PC6:SDMMC1_D0DIR" : 8,
+ "PC6:SDMMC1_D6" : 12,
+ "PC6:SDMMC2_D6" : 10,
+ "PC6:TIM3_CH1" : 2,
+ "PC6:TIM8_CH1" : 3,
+ "PC6:USART6_TX" : 7,
+ "PC7:DCMI_D1" : 13,
+ "PC7:DFSDM_DATIN3" : 4,
+ "PC7:EVENT-OUT" : 15,
+ "PC7:FMC_NE1" : 9,
+ "PC7:HRTIM_CHA2" : 1,
+ "PC7:I2S3_MCK" : 6,
+ "PC7:LCD_G6" : 14,
+ "PC7:SDMMC1_D123DIR" : 8,
+ "PC7:SDMMC1_D7" : 12,
+ "PC7:SDMMC2_D7" : 10,
+ "PC7:SWPMI_TX" : 11,
+ "PC7:TIM3_CH2" : 2,
+ "PC7:TIM8_CH2" : 3,
+ "PC7:TRGIO" : 0,
+ "PC7:USART6_RX" : 7,
+ "PC8:DCMI_D2" : 13,
+ "PC8:EVENT-OUT" : 15,
+ "PC8:FMC_NCE" : 9,
+ "PC8:FMC_NE2" : 9,
+ "PC8:HRTIM_CHB1" : 1,
+ "PC8:SDMMC1_D0" : 12,
+ "PC8:SWPMI_RX" : 11,
+ "PC8:TIM3_CH3" : 2,
+ "PC8:TIM8_CH3" : 3,
+ "PC8:TRACED1" : 0,
+ "PC8:UART5_RTS" : 8,
+ "PC8:USART6_CK" : 7,
+ "PC9:DCMI_D3" : 13,
+ "PC9:EVENT-OUT" : 15,
+ "PC9:I2C3_SDA" : 4,
+ "PC9:I2S_CKIN" : 5,
+ "PC9:LCD_B2" : 14,
+ "PC9:LCD_G3" : 10,
+ "PC9:MCO2" : 0,
+ "PC9:QUADSPI_BK1_IO0" : 9,
+ "PC9:SDMMC1_D1" : 12,
+ "PC9:SWPMI_SUSPEND" : 11,
+ "PC9:TIM3_CH4" : 2,
+ "PC9:TIM8_CH4" : 3,
+ "PC9:UART5_CTS" : 8,
+ "PC10:DCMI_D8" : 13,
+ "PC10:DFSDM_CKIN5" : 3,
+ "PC10:EVENT-OUT" : 15,
+ "PC10:HRTIM_EEV1" : 2,
+ "PC10:I2S3_CK" : 6,
+ "PC10:LCD_R2" : 14,
+ "PC10:QUADSPI_BK1_IO1" : 9,
+ "PC10:SDMMC1_D2" : 12,
+ "PC10:SPI3_SCK" : 6,
+ "PC10:UART4_TX" : 8,
+ "PC10:USART3_TX" : 7,
+ "PC11:DCMI_D4" : 13,
+ "PC11:DFSDM_DATIN5" : 3,
+ "PC11:EVENT-OUT" : 15,
+ "PC11:HRTIM_FLT2" : 2,
+ "PC11:I2S3_SDI" : 6,
+ "PC11:QUADSPI_BK2_NCS" : 9,
+ "PC11:SDMMC1_D3" : 12,
+ "PC11:SPI3_MISO" : 6,
+ "PC11:UART4_RX" : 8,
+ "PC11:USART3_RX" : 7,
+ "PC12:DCMI_D9" : 13,
+ "PC12:EVENT-OUT" : 15,
+ "PC12:HRTIM_EEV2" : 2,
+ "PC12:I2S3_SDO" : 6,
+ "PC12:SDMMC1_CK" : 12,
+ "PC12:SPI3_MOSI" : 6,
+ "PC12:TRACED3" : 0,
+ "PC12:UART5_TX" : 8,
+ "PC12:USART3_CK" : 7,
+ "PC13:EVENT-OUT" : 15,
+ "PC14:EVENT-OUT" : 15,
+ "PC15:EVENT-OUT" : 15,
+ "PD0:DFSDM_CKIN6" : 3,
+ "PD0:EVENT-OUT" : 15,
+ "PD0:CAN1_RX" : 9,
+ "PD0:FMC_D2" : 12,
+ "PD0:FMC_DA2" : 12,
+ "PD0:SAI3_SCK_A" : 6,
+ "PD0:UART4_RX" : 8,
+ "PD1:DFSDM_DATIN6" : 3,
+ "PD1:EVENT-OUT" : 15,
+ "PD1:CAN1_TX" : 9,
+ "PD1:FMC_D3" : 12,
+ "PD1:FMC_DA3" : 12,
+ "PD1:SAI3_SD_A" : 6,
+ "PD1:UART4_TX" : 8,
+ "PD2:DCMI_D11" : 13,
+ "PD2:EVENT-OUT" : 15,
+ "PD2:SDMMC1_CMD" : 12,
+ "PD2:TIM3_ETR" : 2,
+ "PD2:TRACED2" : 0,
+ "PD2:UART5_RX" : 8,
+ "PD3:DCMI_D5" : 13,
+ "PD3:DFSDM_CKOUT" : 3,
+ "PD3:EVENT-OUT" : 15,
+ "PD3:FMC_CLK" : 12,
+ "PD3:I2S2_CK" : 5,
+ "PD3:LCD_G7" : 14,
+ "PD3:SPI2_SCK" : 5,
+ "PD3:USART2_CTS" : 7,
+ "PD4:EVENT-OUT" : 15,
+ "PD4:CAN1_RX" : 9,
+ "PD4:FMC_NOE" : 12,
+ "PD4:HRTIM_FLT3" : 2,
+ "PD4:SAI3_FS_A" : 6,
+ "PD4:USART2_RTS" : 7,
+ "PD5:EVENT-OUT" : 15,
+ "PD5:CAN1_TX" : 9,
+ "PD5:FMC_NWE" : 12,
+ "PD5:HRTIM_EEV3" : 2,
+ "PD5:USART2_TX" : 7,
+ "PD6:DCMI_D10" : 13,
+ "PD6:DFSDM_CKIN4" : 3,
+ "PD6:DFSDM_DATIN1" : 4,
+ "PD6:EVENT-OUT" : 15,
+ "PD6:CAN2_RX" : 9,
+ "PD6:FMC_NWAIT" : 12,
+ "PD6:I2S3_SDO" : 5,
+ "PD6:LCD_B2" : 14,
+ "PD6:SAI1_D1" : 2,
+ "PD6:SAI1_SD_A" : 6,
+ "PD6:SAI4_D1" : 10,
+ "PD6:SAI4_SD_A" : 8,
+ "PD6:SDMMC2_CK" : 11,
+ "PD6:SPI3_MOSI" : 5,
+ "PD6:USART2_RX" : 7,
+ "PD7:DFSDM_CKIN1" : 6,
+ "PD7:DFSDM_DATIN4" : 3,
+ "PD7:EVENT-OUT" : 15,
+ "PD7:FMC_NE1" : 12,
+ "PD7:I2S1_SDO" : 5,
+ "PD7:SDMMC2_CMD" : 11,
+ "PD7:SPDIFRX_IN0" : 9,
+ "PD7:SPI1_MOSI" : 5,
+ "PD7:USART2_CK" : 7,
+ "PD8:DFSDM_CKIN3" : 3,
+ "PD8:EVENT-OUT" : 15,
+ "PD8:FMC_D13" : 12,
+ "PD8:FMC_DA13" : 12,
+ "PD8:SAI3_SCK_B" : 6,
+ "PD8:SPDIFRX_IN1" : 9,
+ "PD8:USART3_TX" : 7,
+ "PD9:DFSDM_DATIN3" : 3,
+ "PD9:EVENT-OUT" : 15,
+ "PD9:CAN2_RX" : 9,
+ "PD9:FMC_D14" : 12,
+ "PD9:FMC_DA14" : 12,
+ "PD9:SAI3_SD_B" : 6,
+ "PD9:USART3_RX" : 7,
+ "PD10:DFSDM_CKOUT" : 3,
+ "PD10:EVENT-OUT" : 15,
+ "PD10:CAN2_TX" : 9,
+ "PD10:FMC_D15" : 12,
+ "PD10:FMC_DA15" : 12,
+ "PD10:LCD_B3" : 14,
+ "PD10:SAI3_FS_B" : 6,
+ "PD10:USART3_CK" : 7,
+ "PD11:EVENT-OUT" : 15,
+ "PD11:FMC_A16" : 12,
+ "PD11:I2C4_SMBA" : 4,
+ "PD11:LPTIM2_IN2" : 3,
+ "PD11:QUADSPI_BK1_IO0" : 9,
+ "PD11:SAI2_SD_A" : 10,
+ "PD11:USART3_CTS" : 7,
+ "PD12:EVENT-OUT" : 15,
+ "PD12:FMC_A17" : 12,
+ "PD12:I2C4_SCL" : 4,
+ "PD12:LPTIM1_IN1" : 1,
+ "PD12:LPTIM2_IN1" : 3,
+ "PD12:QUADSPI_BK1_IO1" : 9,
+ "PD12:SAI2_FS_A" : 10,
+ "PD12:TIM4_CH1" : 2,
+ "PD12:USART3_RTS" : 7,
+ "PD13:EVENT-OUT" : 15,
+ "PD13:FMC_A18" : 12,
+ "PD13:I2C4_SDA" : 4,
+ "PD13:LPTIM1_OUT" : 1,
+ "PD13:QUADSPI_BK1_IO3" : 9,
+ "PD13:SAI2_SCK_A" : 10,
+ "PD13:TIM4_CH2" : 2,
+ "PD14:EVENT-OUT" : 15,
+ "PD14:FMC_D0" : 12,
+ "PD14:FMC_DA0" : 12,
+ "PD14:SAI3_MCLK_B" : 6,
+ "PD14:TIM4_CH3" : 2,
+ "PD14:UART8_CTS" : 8,
+ "PD15:EVENT-OUT" : 15,
+ "PD15:FMC_D1" : 12,
+ "PD15:FMC_DA1" : 12,
+ "PD15:SAI3_MCLK_A" : 6,
+ "PD15:TIM4_CH4" : 2,
+ "PD15:UART8_RTS" : 8,
+ "PE0:DCMI_D2" : 13,
+ "PE0:EVENT-OUT" : 15,
+ "PE0:CAN1_RX" : 9,
+ "PE0:FMC_NBL0" : 12,
+ "PE0:HRTIM_SCIN" : 3,
+ "PE0:LPTIM1_ETR" : 1,
+ "PE0:LPTIM2_ETR" : 4,
+ "PE0:SAI2_MCK_A" : 10,
+ "PE0:TIM4_ETR" : 2,
+ "PE0:UART8_RX" : 8,
+ "PE1:DCMI_D3" : 13,
+ "PE1:EVENT-OUT" : 15,
+ "PE1:CAN1_TX" : 9,
+ "PE1:FMC_NBL1" : 12,
+ "PE1:HRTIM_SCOUT" : 3,
+ "PE1:LPTIM1_IN2" : 1,
+ "PE1:UART8_TX" : 8,
+ "PE2:ETH_MII_TXD3" : 11,
+ "PE2:EVENT-OUT" : 15,
+ "PE2:FMC_A23" : 12,
+ "PE2:QUADSPI_BK1_IO2" : 9,
+ "PE2:SAI1_CK1" : 2,
+ "PE2:SAI1_MCLK_A" : 6,
+ "PE2:SAI4_CK1" : 10,
+ "PE2:SAI4_MCLK_A" : 8,
+ "PE2:SPI4_SCK" : 5,
+ "PE2:TRACECLK" : 0,
+ "PE3:EVENT-OUT" : 15,
+ "PE3:FMC_A19" : 12,
+ "PE3:SAI1_SD_B" : 6,
+ "PE3:SAI4_SD_B" : 8,
+ "PE3:TIM15_BKIN" : 4,
+ "PE3:TRACED0" : 0,
+ "PE4:DCMI_D4" : 13,
+ "PE4:DFSDM_DATIN3" : 3,
+ "PE4:EVENT-OUT" : 15,
+ "PE4:FMC_A20" : 12,
+ "PE4:LCD_B0" : 14,
+ "PE4:SAI1_D2" : 2,
+ "PE4:SAI1_FS_A" : 6,
+ "PE4:SAI4_D2" : 10,
+ "PE4:SAI4_FS_A" : 8,
+ "PE4:SPI4_NSS" : 5,
+ "PE4:TIM15_CH1N" : 4,
+ "PE4:TRACED1" : 0,
+ "PE5:DCMI_D6" : 13,
+ "PE5:DFSDM_CKIN3" : 3,
+ "PE5:EVENT-OUT" : 15,
+ "PE5:FMC_A21" : 12,
+ "PE5:LCD_G0" : 14,
+ "PE5:SAI1_CK2" : 2,
+ "PE5:SAI1_SCK_A" : 6,
+ "PE5:SAI4_CK2" : 10,
+ "PE5:SAI4_SCK_A" : 8,
+ "PE5:SPI4_MISO" : 5,
+ "PE5:TIM15_CH1" : 4,
+ "PE5:TRACED2" : 0,
+ "PE6:DCMI_D7" : 13,
+ "PE6:EVENT-OUT" : 15,
+ "PE6:FMC_A22" : 12,
+ "PE6:LCD_G1" : 14,
+ "PE6:SAI1_D1" : 2,
+ "PE6:SAI1_SD_A" : 6,
+ "PE6:SAI2_MCK_B" : 10,
+ "PE6:SAI4_D1" : 9,
+ "PE6:SAI4_SD_A" : 8,
+ "PE6:SPI4_MOSI" : 5,
+ "PE6:TIM15_CH2" : 4,
+ "PE6:TIM1_BKIN2" : 1,
+ "PE6:TIM1_BKIN2_COMP12" : 11,
+ "PE6:TRACED3" : 0,
+ "PE7:DFSDM_DATIN2" : 3,
+ "PE7:EVENT-OUT" : 15,
+ "PE7:FMC_D4" : 12,
+ "PE7:FMC_DA4" : 12,
+ "PE7:QUADSPI_BK2_IO0" : 10,
+ "PE7:TIM1_ETR" : 1,
+ "PE7:UART7_RX" : 7,
+ "PE8:COMP_2_OUT" : 13,
+ "PE8:DFSDM_CKIN2" : 3,
+ "PE8:EVENT-OUT" : 15,
+ "PE8:FMC_D5" : 12,
+ "PE8:FMC_DA5" : 12,
+ "PE8:QUADSPI_BK2_IO1" : 10,
+ "PE8:TIM1_CH1N" : 1,
+ "PE8:UART7_TX" : 7,
+ "PE9:DFSDM_CKOUT" : 3,
+ "PE9:EVENT-OUT" : 15,
+ "PE9:FMC_D6" : 12,
+ "PE9:FMC_DA6" : 12,
+ "PE9:QUADSPI_BK2_IO2" : 10,
+ "PE9:TIM1_CH1" : 1,
+ "PE9:UART7_RTS" : 7,
+ "PE10:DFSDM_DATIN4" : 3,
+ "PE10:EVENT-OUT" : 15,
+ "PE10:FMC_D7" : 12,
+ "PE10:FMC_DA7" : 12,
+ "PE10:QUADSPI_BK2_IO3" : 10,
+ "PE10:TIM1_CH2N" : 1,
+ "PE10:UART7_CTS" : 7,
+ "PE11:DFSDM_CKIN4" : 3,
+ "PE11:EVENT-OUT" : 15,
+ "PE11:FMC_D8" : 12,
+ "PE11:FMC_DA8" : 12,
+ "PE11:LCD_G3" : 14,
+ "PE11:SAI2_SD_B" : 10,
+ "PE11:SPI4_NSS" : 5,
+ "PE11:TIM1_CH2" : 1,
+ "PE12:COMP_1_OUT" : 13,
+ "PE12:DFSDM_DATIN5" : 3,
+ "PE12:EVENT-OUT" : 15,
+ "PE12:FMC_D9" : 12,
+ "PE12:FMC_DA9" : 12,
+ "PE12:LCD_B4" : 14,
+ "PE12:SAI2_SCK_B" : 10,
+ "PE12:SPI4_SCK" : 5,
+ "PE12:TIM1_CH3N" : 1,
+ "PE13:COMP_2_OUT" : 13,
+ "PE13:DFSDM_CKIN5" : 3,
+ "PE13:EVENT-OUT" : 15,
+ "PE13:FMC_D10" : 12,
+ "PE13:FMC_DA10" : 12,
+ "PE13:LCD_DE" : 14,
+ "PE13:SAI2_FS_B" : 10,
+ "PE13:SPI4_MISO" : 5,
+ "PE13:TIM1_CH3" : 1,
+ "PE14:EVENT-OUT" : 15,
+ "PE14:FMC_D11" : 12,
+ "PE14:FMC_DA11" : 12,
+ "PE14:LCD_CLK" : 14,
+ "PE14:SAI2_MCK_B" : 10,
+ "PE14:SPI4_MOSI" : 5,
+ "PE14:TIM1_CH4" : 1,
+ "PE15:EVENT-OUT" : 15,
+ "PE15:FMC_D12" : 12,
+ "PE15:FMC_DA12" : 12,
+ "PE15:HDMI__TIM1_BKIN" : 5,
+ "PE15:LCD_R7" : 14,
+ "PE15:TIM1_BKIN" : 1,
+ "PE15:TIM1_BKIN_COMP12" : 13,
+ "PF0:EVENT-OUT" : 15,
+ "PF0:FMC_A0" : 12,
+ "PF0:I2C2_SDA" : 4,
+ "PF1:EVENT-OUT" : 15,
+ "PF1:FMC_A1" : 12,
+ "PF1:I2C2_SCL" : 4,
+ "PF2:EVENT-OUT" : 15,
+ "PF2:FMC_A2" : 12,
+ "PF2:I2C2_SMBA" : 4,
+ "PF3:EVENT-OUT" : 15,
+ "PF3:FMC_A3" : 12,
+ "PF4:EVENT-OUT" : 15,
+ "PF4:FMC_A4" : 12,
+ "PF5:EVENT-OUT" : 15,
+ "PF5:FMC_A5" : 12,
+ "PF6:EVENT-OUT" : 15,
+ "PF6:QUADSPI_BK1_IO3" : 9,
+ "PF6:SAI1_SD_B" : 6,
+ "PF6:SAI4_SD_B" : 8,
+ "PF6:SPI5_NSS" : 5,
+ "PF6:TIM16_CH1" : 1,
+ "PF6:UART7_RX" : 7,
+ "PF7:EVENT-OUT" : 15,
+ "PF7:QUADSPI_BK1_IO2" : 9,
+ "PF7:SAI1_MCLK_B" : 6,
+ "PF7:SAI4_MCLK_B" : 8,
+ "PF7:SPI5_SCK" : 5,
+ "PF7:TIM17_CH1" : 1,
+ "PF7:UART7_TX" : 7,
+ "PF8:EVENT-OUT" : 15,
+ "PF8:QUADSPI_BK1_IO0" : 10,
+ "PF8:SAI1_SCK_B" : 6,
+ "PF8:SAI4_SCK_B" : 8,
+ "PF8:SPI5_MISO" : 5,
+ "PF8:TIM13_CH1" : 9,
+ "PF8:TIM16_CH1N" : 1,
+ "PF8:UART7_RTS" : 7,
+ "PF9:EVENT-OUT" : 15,
+ "PF9:QUADSPI_BK1_IO1" : 10,
+ "PF9:SAI1_FS_B" : 6,
+ "PF9:SAI4_FS_B" : 8,
+ "PF9:SPI5_MOSI" : 5,
+ "PF9:TIM14_CH1" : 9,
+ "PF9:TIM17_CH1N" : 1,
+ "PF9:UART7_CTS" : 7,
+ "PF10:DCMI_D11" : 13,
+ "PF10:EVENT-OUT" : 15,
+ "PF10:LCD_DE" : 14,
+ "PF10:QUADSPI_CLK" : 9,
+ "PF10:SAI1_D3" : 2,
+ "PF10:SAI4_D3" : 10,
+ "PF10:TIM16_BKIN" : 1,
+ "PF11:DCMI_D12" : 13,
+ "PF11:EVENT-OUT" : 15,
+ "PF11:FMC_SDNRAS" : 12,
+ "PF11:SAI2_SD_B" : 10,
+ "PF11:SPI5_MOSI" : 5,
+ "PF12:EVENT-OUT" : 15,
+ "PF12:FMC_A6" : 12,
+ "PF13:DFSDM_DATIN6" : 3,
+ "PF13:EVENT-OUT" : 15,
+ "PF13:FMC_A7" : 12,
+ "PF13:I2C4_SMBA" : 4,
+ "PF14:DFSDM_CKIN6" : 3,
+ "PF14:EVENT-OUT" : 15,
+ "PF14:FMC_A8" : 12,
+ "PF14:I2C4_SCL" : 4,
+ "PF15:EVENT-OUT" : 15,
+ "PF15:FMC_A9" : 12,
+ "PF15:I2C4_SDA" : 4,
+ "PG0:EVENT-OUT" : 15,
+ "PG0:FMC_A10" : 12,
+ "PG1:EVENT-OUT" : 15,
+ "PG1:FMC_A11" : 12,
+ "PG2:EVENT-OUT" : 15,
+ "PG2:FMC_A12" : 12,
+ "PG2:TIM8_BKIN" : 3,
+ "PG2:TIM8_BKIN_COMP12" : 11,
+ "PG3:EVENT-OUT" : 15,
+ "PG3:FMC_A13" : 12,
+ "PG3:TIM8_BKIN2" : 3,
+ "PG3:TIM8_BKIN2_COMP12" : 11,
+ "PG4:EVENT-OUT" : 15,
+ "PG4:FMC_A14" : 12,
+ "PG4:FMC_BA0" : 12,
+ "PG4:TIM1_BKIN2" : 1,
+ "PG4:TIM1_BKIN2_COMP12" : 11,
+ "PG5:EVENT-OUT" : 15,
+ "PG5:FMC_A15" : 12,
+ "PG5:FMC_BA1" : 12,
+ "PG5:TIM1_ETR" : 1,
+ "PG6:DCMI_D12" : 13,
+ "PG6:EVENT-OUT" : 15,
+ "PG6:FMC_NE3" : 12,
+ "PG6:HRTIM_CHE1" : 2,
+ "PG6:LCD_R7" : 14,
+ "PG6:QUADSPI_BK1_NCS" : 10,
+ "PG6:TIM17_BKIN" : 1,
+ "PG7:DCMI_D13" : 13,
+ "PG7:EVENT-OUT" : 15,
+ "PG7:FMC_INT" : 12,
+ "PG7:HRTIM_CHE2" : 2,
+ "PG7:LCD_CLK" : 14,
+ "PG7:SAI1_MCLK_A" : 6,
+ "PG7:USART6_CK" : 7,
+ "PG8:ETH_PPS_OUT" : 11,
+ "PG8:EVENT-OUT" : 15,
+ "PG8:FMC_SDCLK" : 12,
+ "PG8:LCD_G7" : 14,
+ "PG8:SPDIFRX_IN2" : 8,
+ "PG8:SPI6_NSS" : 5,
+ "PG8:TIM8_ETR" : 3,
+ "PG8:USART6_RTS" : 7,
+ "PG9:DCMI_VSYNC" : 13,
+ "PG9:EVENT-OUT" : 15,
+ "PG9:FMC_NCE" : 12,
+ "PG9:FMC_NE2" : 12,
+ "PG9:I2S1_SDI" : 5,
+ "PG9:QUADSPI_BK2_IO2" : 9,
+ "PG9:SAI2_FS_B" : 10,
+ "PG9:SPDIFRX_IN3" : 8,
+ "PG9:SPI1_MISO" : 5,
+ "PG9:USART6_RX" : 7,
+ "PG10:DCMI_D2" : 13,
+ "PG10:EVENT-OUT" : 15,
+ "PG10:FMC_NE3" : 12,
+ "PG10:HRTIM_FLT5" : 2,
+ "PG10:I2S1_WS" : 5,
+ "PG10:LCD_B2" : 14,
+ "PG10:LCD_G3" : 9,
+ "PG10:SAI2_SD_B" : 10,
+ "PG10:SPI1_NSS" : 5,
+ "PG11:DCMI_D3" : 13,
+ "PG11:ETH_MII_TX_EN" : 11,
+ "PG11:ETH_RMII_TX_EN" : 11,
+ "PG11:EVENT-OUT" : 15,
+ "PG11:HRTIM_EEV4" : 2,
+ "PG11:I2S1_CK" : 5,
+ "PG11:LCD_B3" : 14,
+ "PG11:SDMMC2_D2" : 10,
+ "PG11:SPDIFRX_IN0" : 8,
+ "PG11:SPI1_SCK" : 5,
+ "PG12:ETH_MII_TXD1" : 11,
+ "PG12:ETH_RMII_TXD1" : 11,
+ "PG12:EVENT-OUT" : 15,
+ "PG12:FMC_NE4" : 12,
+ "PG12:HRTIM_EEV5" : 2,
+ "PG12:LCD_B1" : 14,
+ "PG12:LCD_B4" : 9,
+ "PG12:LPTIM1_IN1" : 1,
+ "PG12:SPDIFRX_IN1" : 8,
+ "PG12:SPI6_MISO" : 5,
+ "PG12:USART6_RTS" : 7,
+ "PG13:ETH_MII_TXD0" : 11,
+ "PG13:ETH_RMII_TXD0" : 11,
+ "PG13:EVENT-OUT" : 15,
+ "PG13:FMC_A24" : 12,
+ "PG13:HRTIM_EEV10" : 2,
+ "PG13:LCD_R0" : 14,
+ "PG13:LPTIM1_OUT" : 1,
+ "PG13:SPI6_SCK" : 5,
+ "PG13:TRACED0" : 0,
+ "PG13:USART6_CTS" : 7,
+ "PG14:ETH_MII_TXD1" : 11,
+ "PG14:ETH_RMII_TXD1" : 11,
+ "PG14:EVENT-OUT" : 15,
+ "PG14:FMC_A25" : 12,
+ "PG14:LCD_B0" : 14,
+ "PG14:LPTIM1_ETR" : 1,
+ "PG14:QUADSPI_BK2_IO3" : 9,
+ "PG14:SPI6_MOSI" : 5,
+ "PG14:TRACED1" : 0,
+ "PG14:USART6_TX" : 7,
+ "PG15:DCMI_D13" : 13,
+ "PG15:EVENT-OUT" : 15,
+ "PG15:FMC_SDNCAS" : 12,
+ "PG15:USART6_CTS" : 7,
+ "PH0:EVENT-OUT" : 15,
+ "PH1:EVENT-OUT" : 15,
+ "PH2:ETH_MII_CRS" : 11,
+ "PH2:EVENT-OUT" : 15,
+ "PH2:FMC_SDCKE0" : 12,
+ "PH2:LCD_R0" : 14,
+ "PH2:LPTIM1_IN2" : 1,
+ "PH2:QUADSPI_BK2_IO0" : 9,
+ "PH2:SAI2_SCK_B" : 10,
+ "PH3:ETH_MII_COL" : 11,
+ "PH3:EVENT-OUT" : 15,
+ "PH3:FMC_SDNE0" : 12,
+ "PH3:LCD_R1" : 14,
+ "PH3:QUADSPI_BK2_IO1" : 9,
+ "PH3:SAI2_MCK_B" : 10,
+ "PH4:EVENT-OUT" : 15,
+ "PH4:I2C2_SCL" : 4,
+ "PH4:LCD_G4" : 14,
+ "PH4:LCD_G5" : 9,
+ "PH4:OTG_HS_ULPI_NXT" : 10,
+ "PH5:EVENT-OUT" : 15,
+ "PH5:FMC_SDNWE" : 12,
+ "PH5:I2C2_SDA" : 4,
+ "PH5:SPI5_NSS" : 5,
+ "PH6:DCMI_D8" : 13,
+ "PH6:ETH_MII_RXD2" : 11,
+ "PH6:EVENT-OUT" : 15,
+ "PH6:FMC_SDNE1" : 12,
+ "PH6:I2C2_SMBA" : 4,
+ "PH6:SPI5_SCK" : 5,
+ "PH6:TIM12_CH1" : 2,
+ "PH7:DCMI_D9" : 13,
+ "PH7:ETH_MII_RXD3" : 11,
+ "PH7:EVENT-OUT" : 15,
+ "PH7:FMC_SDCKE1" : 12,
+ "PH7:I2C3_SCL" : 4,
+ "PH7:SPI5_MISO" : 5,
+ "PH8:DCMI_HSYNC" : 13,
+ "PH8:EVENT-OUT" : 15,
+ "PH8:FMC_D16" : 12,
+ "PH8:I2C3_SDA" : 4,
+ "PH8:LCD_R2" : 14,
+ "PH8:TIM5_ETR" : 2,
+ "PH9:DCMI_D0" : 13,
+ "PH9:EVENT-OUT" : 15,
+ "PH9:FMC_D17" : 12,
+ "PH9:I2C3_SMBA" : 4,
+ "PH9:LCD_R3" : 14,
+ "PH9:TIM12_CH2" : 2,
+ "PH10:DCMI_D1" : 13,
+ "PH10:EVENT-OUT" : 15,
+ "PH10:FMC_D18" : 12,
+ "PH10:I2C4_SMBA" : 4,
+ "PH10:LCD_R4" : 14,
+ "PH10:TIM5_CH1" : 2,
+ "PH11:DCMI_D2" : 13,
+ "PH11:EVENT-OUT" : 15,
+ "PH11:FMC_D19" : 12,
+ "PH11:I2C4_SCL" : 4,
+ "PH11:LCD_R5" : 14,
+ "PH11:TIM5_CH2" : 2,
+ "PH12:DCMI_D3" : 13,
+ "PH12:EVENT-OUT" : 15,
+ "PH12:FMC_D20" : 12,
+ "PH12:I2C4_SDA" : 4,
+ "PH12:LCD_R6" : 14,
+ "PH12:TIM5_CH3" : 2,
+ "PH13:EVENT-OUT" : 15,
+ "PH13:CAN1_TX" : 9,
+ "PH13:FMC_D21" : 12,
+ "PH13:LCD_G2" : 14,
+ "PH13:TIM8_CH1N" : 3,
+ "PH13:UART4_TX" : 8,
+ "PH14:DCMI_D4" : 13,
+ "PH14:EVENT-OUT" : 15,
+ "PH14:CAN1_RX" : 9,
+ "PH14:FMC_D22" : 12,
+ "PH14:LCD_G3" : 14,
+ "PH14:TIM8_UCH2N" : 3,
+ "PH14:UART4_RX" : 8,
+ "PH15:DCMI_D11" : 13,
+ "PH15:EVENT-OUT" : 15,
+ "PH15:CAN1_TX" : 9,
+ "PH15:FMC_D23" : 12,
+ "PH15:LCD_G4" : 14,
+ "PH15:TIM8_CH3N" : 3,
+ "PI0:DCMI_D13" : 13,
+ "PI0:EVENT-OUT" : 15,
+ "PI0:CAN1_RX" : 9,
+ "PI0:FMC_D24" : 12,
+ "PI0:I2S2_WS" : 5,
+ "PI0:LCD_G5" : 14,
+ "PI0:SPI2_NSS" : 5,
+ "PI0:TIM5_CH4" : 2,
+ "PI1:DCMI_D8" : 13,
+ "PI1:EVENT-OUT" : 15,
+ "PI1:FMC_D25" : 12,
+ "PI1:I2S2_CK" : 5,
+ "PI1:LCD_G6" : 14,
+ "PI1:SPI2_SCK" : 5,
+ "PI1:TIM8_BKIN2" : 3,
+ "PI1:TIM8_BKIN2_COMP12" : 11,
+ "PI2:DCMI_D9" : 13,
+ "PI2:EVENT-OUT" : 15,
+ "PI2:FMC_D26" : 12,
+ "PI2:I2S2_SDI" : 5,
+ "PI2:LCD_G7" : 14,
+ "PI2:SPI2_MISO" : 5,
+ "PI2:TIM8_CH4" : 3,
+ "PI3:DCMI_D10" : 13,
+ "PI3:EVENT-OUT" : 15,
+ "PI3:FMC_D27" : 12,
+ "PI3:I2S2_SDO" : 5,
+ "PI3:SPI2_MOSI" : 5,
+ "PI3:TIM8_ETR" : 3,
+ "PI4:DCMI_D5" : 13,
+ "PI4:EVENT-OUT" : 15,
+ "PI4:FMC_NBL2" : 12,
+ "PI4:LCD_B4" : 14,
+ "PI4:SAI2_MCK_A" : 10,
+ "PI4:TIM8_BKIN" : 3,
+ "PI4:TIM8_BKIN_COMP12" : 11,
+ "PI5:DCMI_VSYNC" : 13,
+ "PI5:EVENT-OUT" : 15,
+ "PI5:FMC_NBL3" : 12,
+ "PI5:LCD_B5" : 14,
+ "PI5:SAI2_SCK_A" : 10,
+ "PI5:TIM8_CH1" : 3,
+ "PI6:DCMI_D6" : 13,
+ "PI6:EVENT-OUT" : 15,
+ "PI6:FMC_D28" : 12,
+ "PI6:LCD_B6" : 14,
+ "PI6:SAI2_SD_A" : 10,
+ "PI6:TIM8_CH2" : 3,
+ "PI7:DCMI_D7" : 13,
+ "PI7:EVENT-OUT" : 15,
+ "PI7:FMC_D29" : 12,
+ "PI7:LCD_B7" : 14,
+ "PI7:SAI2_FS_A" : 10,
+ "PI7:TIM8_CH3" : 3,
+ "PI8:EVENT-OUT" : 15,
+ "PI9:EVENT-OUT" : 15,
+ "PI9:CAN1_RX" : 9,
+ "PI9:FMC_D30" : 12,
+ "PI9:LCD_VSYNC" : 14,
+ "PI9:UART4_RX" : 8,
+ "PI10:ETH_MII_RX_ER" : 11,
+ "PI10:EVENT-OUT" : 15,
+ "PI10:CAN1_RX" : 9,
+ "PI10:FMC_D31" : 12,
+ "PI10:LCD_HSYNC" : 14,
+ "PI11:EVENT-OUT" : 15,
+ "PI11:LCD_G6" : 9,
+ "PI11:OTG_HS_ULPI_DIR" : 10,
+ "PI12:EVENT-OUT" : 15,
+ "PI12:LCD_HSYNC" : 14,
+ "PI13:EVENT-OUT" : 15,
+ "PI13:LCD_VSYNC" : 14,
+ "PI14:EVENT-OUT" : 15,
+ "PI14:LCD_CLK" : 14,
+ "PI15:EVENT-OUT" : 15,
+ "PI15:LCD_G2" : 9,
+ "PI15:LCD_R0" : 14,
+ "PJ0:EVENT-OUT" : 15,
+ "PJ0:LCD_R1" : 14,
+ "PJ0:LCD_R7" : 9,
+ "PJ1:EVENT-OUT" : 15,
+ "PJ1:LCD_R2" : 14,
+ "PJ2:EVENT-OUT" : 15,
+ "PJ2:LCD_R3" : 14,
+ "PJ3:EVENT-OUT" : 15,
+ "PJ3:LCD_R4" : 14,
+ "PJ4:EVENT-OUT" : 15,
+ "PJ4:LCD_R5" : 14,
+ "PJ5:EVENT-OUT" : 15,
+ "PJ5:LCD_R6" : 14,
+ "PJ6:EVENT-OUT" : 15,
+ "PJ6:LCD_R7" : 14,
+ "PJ6:TIM8_CH2" : 3,
+ "PJ7:EVENT-OUT" : 15,
+ "PJ7:LCD_G0" : 14,
+ "PJ7:TIM8_CH2N" : 3,
+ "PJ7:TRGIN" : 0,
+ "PJ8:EVENT-OUT" : 15,
+ "PJ8:LCD_G1" : 14,
+ "PJ8:TIM1_CH3N" : 1,
+ "PJ8:TIM8_CH1" : 3,
+ "PJ8:UART8_TX" : 8,
+ "PJ9:EVENT-OUT" : 15,
+ "PJ9:LCD_G2" : 14,
+ "PJ9:TIM1_CH3" : 1,
+ "PJ9:TIM8_CH1N" : 3,
+ "PJ9:UART8_RX" : 8,
+ "PJ10:EVENT-OUT" : 15,
+ "PJ10:LCD_G3" : 14,
+ "PJ10:SPI5_MOSI" : 5,
+ "PJ10:TIM1_CH2N" : 1,
+ "PJ10:TIM8_CH2" : 3,
+ "PJ11:EVENT-OUT" : 15,
+ "PJ11:LCD_G4" : 14,
+ "PJ11:SPI5_MISO" : 5,
+ "PJ11:TIM1_CH2" : 1,
+ "PJ11:TIM8_CH2N" : 3,
+ "PJ12:EVENT-OUT" : 15,
+ "PJ12:LCD_B0" : 14,
+ "PJ12:LCD_G3" : 9,
+ "PJ12:TRGOUT" : 0,
+ "PJ13:EVENT-OUT" : 15,
+ "PJ13:LCD_B1" : 14,
+ "PJ13:LCD_B4" : 9,
+ "PJ14:EVENT-OUT" : 15,
+ "PJ14:LCD_B2" : 14,
+ "PJ15:EVENT-OUT" : 15,
+ "PJ15:LCD_B3" : 14,
+ "PK0:EVENT-OUT" : 15,
+ "PK0:LCD_G5" : 14,
+ "PK0:SPI5_SCK" : 5,
+ "PK0:TIM1_CH1N" : 1,
+ "PK0:TIM8_CH3" : 3,
+ "PK1:EVENT-OUT" : 15,
+ "PK1:LCD_G6" : 14,
+ "PK1:SPI5_NSS" : 5,
+ "PK1:TIM1_CH1" : 1,
+ "PK1:TIM8_CH3N" : 3,
+ "PK2:EVENT-OUT" : 15,
+ "PK2:LCD_G7" : 14,
+ "PK2:TIM1_BKIN" : 1,
+ "PK2:TIM1_BKIN_COMP12" : 11,
+ "PK2:TIM8_BKIN" : 3,
+ "PK2:TIM8_BKIN_COMP12" : 10,
+ "PK3:EVENT-OUT" : 15,
+ "PK3:LCD_B4" : 14,
+ "PK4:EVENT-OUT" : 15,
+ "PK4:LCD_B5" : 14,
+ "PK5:EVENT-OUT" : 15,
+ "PK5:LCD_B6" : 14,
+ "PK6:EVENT-OUT" : 15,
+ "PK6:LCD_B7" : 14,
+ "PK7:EVENT-OUT" : 15,
+ "PK7:LCD_DE" : 14,
+}
+
+ADC1_map = {
+ # format is PIN : ADC1_CHAN
+ "PF11" : 2,
+ "PA6" : 3,
+ "PC4" : 4,
+ "PB1" : 5,
+ "PF12" : 6,
+ "PA7" : 7,
+ "PC5" : 8,
+ "PB0" : 9,
+ "PC0" : 10,
+ "PC1" : 11,
+ "PC2" : 12,
+ "PC3" : 13,
+ "PA2" : 14,
+ "PA3" : 15,
+ "PA0" : 16,
+ "PA1" : 17,
+ "PA4" : 18,
+ "PA5" : 19,
+}
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp
index ce1f368c7c254..ab2cf93ea104d 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp
+++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp
@@ -33,6 +33,7 @@
#include "AP_InertialSensor_ExternalAHRS.h"
#include "AP_InertialSensor_Invensensev3.h"
#include "AP_InertialSensor_NONE.h"
+#include "AP_InertialSensor_SCHA63T.h"
/* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
* Output is on the debug console. */
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
index f6105c9830012..feba44b62a1ff 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
@@ -123,6 +123,8 @@ class AP_InertialSensor_Backend
DEVTYPE_BMI270 = 0x38,
DEVTYPE_INS_BMI085 = 0x39,
DEVTYPE_INS_ICM42670 = 0x3A,
+
+ DEVTYPE_INS_SCHA63T = 0x3C,
};
protected:
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp
new file mode 100644
index 0000000000000..652dd100ad5b8
--- /dev/null
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp
@@ -0,0 +1,484 @@
+/*
+ * This file is free software: you can redistribute it and/or modify it
+ * under the terms of the GNU General Public License as published by the
+ * Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This file is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License along
+ * with this program. If not, see .
+ *
+ * sensor information url
+ * .
+ */
+
+#include
+#include
+#include
+
+#include "AP_InertialSensor_SCHA63T.h"
+
+#if defined(HAL_GPIO_PIN_SCHA63T_RESET)
+#include
+#endif
+
+#define BACKEND_SAMPLE_RATE 1000
+#define BACKEND_SAMPLE_RATE_MAX 4000
+
+extern const AP_HAL::HAL& hal;
+
+#define SCHA63T_UNO 0
+#define SCHA63T_DUE 1
+#define G_FILT 0x2424 // Ry/Ry2 filter 300Hz 3rd order filter
+#define HW_RES 0x0001 // HardReset
+#define RES_EOI 0x0002 // End Of Initialization
+#define MODE_NORM 0x0000 // Mode
+#define A_FILT 0x0444 // Ax/Ay/Az filter 300Hz 3rd order filter
+
+static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
+{
+ return (msb << 8u) | lsb;
+}
+
+AP_InertialSensor_SCHA63T::AP_InertialSensor_SCHA63T(AP_InertialSensor &imu,
+ AP_HAL::OwnPtr _dev_uno,
+ AP_HAL::OwnPtr _dev_due,
+ enum Rotation _rotation)
+ : AP_InertialSensor_Backend(imu)
+ , dev_uno(std::move(_dev_uno))
+ , dev_due(std::move(_dev_due))
+ , rotation(_rotation)
+{
+}
+
+AP_InertialSensor_Backend* AP_InertialSensor_SCHA63T::probe(AP_InertialSensor &imu,
+ AP_HAL::OwnPtr dev_uno,
+ AP_HAL::OwnPtr dev_due,
+ enum Rotation rotation)
+{
+ if (!dev_uno || !dev_due) {
+ return nullptr;
+ }
+ auto sensor = new AP_InertialSensor_SCHA63T(imu, std::move(dev_uno), std::move(dev_due), rotation);
+
+ if (!sensor) {
+ return nullptr;
+ }
+
+#if defined(HAL_GPIO_PIN_SCHA63T_RESET)
+ palSetLine(HAL_GPIO_PIN_SCHA63T_RESET);
+#endif
+
+ if (!sensor->init()) {
+ delete sensor;
+ return nullptr;
+ }
+
+ return sensor;
+}
+
+void AP_InertialSensor_SCHA63T::start()
+{
+ if (!_imu.register_accel(accel_instance, BACKEND_SAMPLE_RATE, dev_uno->get_bus_id_devtype(DEVTYPE_INS_SCHA63T)) ||
+ !_imu.register_gyro(gyro_instance, BACKEND_SAMPLE_RATE, dev_due->get_bus_id_devtype(DEVTYPE_INS_SCHA63T))) {
+ return;
+ }
+
+ // set backend rate
+ uint16_t backend_rate_hz = BACKEND_SAMPLE_RATE;
+ if (enable_fast_sampling(accel_instance) && get_fast_sampling_rate() > 1) {
+ bool fast_sampling = dev_uno->bus_type() == AP_HAL::Device::BUS_TYPE_SPI;
+ if (fast_sampling) {
+ // constrain the gyro rate to be a 2^N multiple
+ uint8_t fast_sampling_rate = constrain_int16(get_fast_sampling_rate(), 1, 4);
+ // calculate rate we will be giving samples to the backend
+ backend_rate_hz = constrain_int16(backend_rate_hz * fast_sampling_rate, backend_rate_hz, BACKEND_SAMPLE_RATE_MAX);
+ }
+ }
+ uint32_t backend_period_us = 1000000UL / backend_rate_hz;
+
+ // setup sensor rotations from probe()
+ set_gyro_orientation(gyro_instance, rotation);
+ set_accel_orientation(accel_instance, rotation);
+
+ // setup callbacks
+ dev_uno->register_periodic_callback(backend_period_us, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SCHA63T::read_accel, void));
+ dev_due->register_periodic_callback(backend_period_us, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SCHA63T::read_gyro, void));
+}
+
+/*
+ probe and initialise accelerometer
+ */
+bool AP_InertialSensor_SCHA63T::init()
+{
+ WITH_SEMAPHORE(dev_uno->get_semaphore());
+ WITH_SEMAPHORE(dev_due->get_semaphore());
+
+ // wait 25ms for non-volatile memory (NVM) read
+ hal.scheduler->delay(25);
+
+ // set DUE operation mode on (must be less than 1ms)
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+
+ // set UNO operation mode on
+ write_register(SCHA63T_UNO, MODE, MODE_NORM);
+
+ // wait 70ms initial startup
+ hal.scheduler->delay(70);
+
+ // set UNO configuration (data filter, flag filter)
+ write_register(SCHA63T_UNO, G_FILT_DYN, G_FILT);
+ write_register(SCHA63T_UNO, A_FILT_DYN, A_FILT);
+
+ // reset DUE write (0001h) to register 18h
+ write_register(SCHA63T_DUE, RESCTRL, HW_RES);
+
+ // wait 25ms for non-volatile memory (NVM) read
+ hal.scheduler->delay(25);
+
+ // set DUE operation mode on (must be less than 1ms)
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+
+ // wait 1ms (50ms has already passed)
+ hal.scheduler->delay(1);
+
+ // set DUE configuration (data filter, flag filter)
+ write_register(SCHA63T_DUE, G_FILT_DYN, G_FILT);
+
+ // startup clear (startup_attempt = 0)
+ if (!check_startup()) {
+ // system in FAILURE mode (startup_attempt not equal 0 startup_attempt = 1)
+ // reset UNO write (0001h) to register 18h
+ write_register(SCHA63T_UNO, RESCTRL, HW_RES);
+ // reset DUE write (0001h) to register 18h
+ write_register(SCHA63T_DUE, RESCTRL, HW_RES);
+ // wait 25ms for non-volatile memory (NVM) read
+ hal.scheduler->delay(25);
+
+ // set DUE operation mode on (must be less than 1ms)
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+ write_register(SCHA63T_DUE, MODE, MODE_NORM);
+ // set UNO operation mode on
+ write_register(SCHA63T_UNO, MODE, MODE_NORM);
+ // wait 70ms initial startup
+ hal.scheduler->delay(50);
+
+ // set UNO configuration (data filter, flag filter)
+ write_register(SCHA63T_UNO, G_FILT_DYN, G_FILT);
+ write_register(SCHA63T_UNO, A_FILT_DYN, A_FILT);
+ // set DUE configuration (data filter, flag filter)
+ write_register(SCHA63T_DUE, G_FILT_DYN, G_FILT);
+
+ // wait 45ms (adjust restart duration to 500ms)
+ hal.scheduler->delay(45);
+
+ if (!check_startup()) {
+ // check FAILED
+ return false;
+ }
+ }
+
+ // check ok
+ return true;
+}
+
+bool AP_InertialSensor_SCHA63T::check_startup()
+{
+ uint8_t val[4] {};
+
+ // wait 405ms (300Hz filter)
+ hal.scheduler->delay(405);
+
+ // start EOI = 1
+ if (!write_register(SCHA63T_UNO, RESCTRL, RES_EOI)) {
+ return false;
+ }
+ if (!write_register(SCHA63T_DUE, RESCTRL, RES_EOI)) {
+ return false;
+ }
+
+ // ready summary status twice
+ for (uint8_t i=0; i<2; i++) {
+ if (!read_register(SCHA63T_UNO, S_SUM, val)) {
+ return false;
+ }
+ if (!read_register(SCHA63T_DUE, S_SUM, val)) {
+ return false;
+ }
+ // wait at least 2.5ms
+ hal.scheduler->delay(3);
+ }
+
+ // read summary status
+ if (!read_register(SCHA63T_UNO, S_SUM, val)) {
+ return false;
+ }
+ // check UNO summary status
+ if (!((val[1] & 0x9e) && (val[2] & 0xda))) {
+ return false;
+ }
+ if (!read_register(SCHA63T_DUE, S_SUM, val)) {
+ return false;
+ }
+ // check DUE summary status
+ if (!((val[1] & 0xf8) && (val[2] & 0x03))) {
+ return false;
+ }
+
+ // success if we got this far
+ return true;
+}
+
+/*
+ read accel fifo
+ */
+void AP_InertialSensor_SCHA63T::read_accel()
+{
+ uint8_t rsp_accl_x[4] {};
+ uint8_t rsp_accl_y[4] {};
+ uint8_t rsp_accl_z[4] {};
+ uint8_t rsp_temper[4] {};
+
+ int16_t accel_x = 0;
+ int16_t accel_y = 0;
+ int16_t accel_z = 0;
+ int16_t uno_temp = 0;
+
+ // ACCL_X Cmd Send (first response is undefined data)
+ if (!read_register(SCHA63T_UNO, ACC_X, rsp_accl_x)) {
+ return;
+ }
+ // ACCL_Y Cmd Send + ACCL_X Response Receive
+ if (!read_register(SCHA63T_UNO, ACC_Y, rsp_accl_x)) {
+ return;
+ }
+ // ACCL_Z Cmd Send + ACCL_Y Response Receive
+ if (!read_register(SCHA63T_UNO, ACC_Z, rsp_accl_y)) {
+ return;
+ }
+ // TEMPER Cmd Send + RATE_X Response Receive
+ if (!read_register(SCHA63T_UNO, TEMP, rsp_accl_z)) {
+ return;
+ }
+ // TEMPER Cmd Send + TEMPRE Response Receive
+ if (!read_register(SCHA63T_UNO, TEMP, rsp_temper)) {
+ return;
+ }
+
+ // response data address check
+ if (((rsp_accl_x[0] & 0x7C) >> 2) != ACC_X) {
+ return;
+ }
+ accel_x = combine(rsp_accl_x[1], rsp_accl_x[2]);
+
+ if (((rsp_accl_y[0] & 0x7C) >> 2) != ACC_Y) {
+ return;
+ }
+ accel_y = combine(rsp_accl_y[1], rsp_accl_y[2]);
+
+ if (((rsp_accl_z[0] & 0x7C) >> 2) != ACC_Z) {
+ return;
+ }
+ accel_z = combine(rsp_accl_z[1], rsp_accl_z[2]);
+
+ if (((rsp_temper[0] & 0x7C) >> 2) != TEMP) {
+ return;
+ }
+ uno_temp = combine(rsp_temper[1], rsp_temper[2]);
+ set_temperature(accel_instance, uno_temp);
+
+ // change coordinate system from left hand too right hand
+ accel_z = (accel_z == INT16_MIN) ? INT16_MAX : -accel_z;
+
+ Vector3f accel(accel_x, accel_y, accel_z);
+ accel *= (GRAVITY_MSS / 4905.f); // 4905 LSB/g, 0.20387 mg/LSB
+
+ _rotate_and_correct_accel(accel_instance, accel);
+ _notify_new_accel_raw_sample(accel_instance, accel);
+
+ AP_HAL::Device::checkreg reg;
+ if (!dev_uno->check_next_register(reg)) {
+ log_register_change(dev_uno->get_bus_id(), reg);
+ _inc_accel_error_count(accel_instance);
+ }
+}
+
+/*
+ read gyro fifo
+ */
+void AP_InertialSensor_SCHA63T::read_gyro()
+{
+ uint8_t rsp_rate_x[4];
+ uint8_t rsp_rate_y[4];
+ uint8_t rsp_rate_z[4];
+ uint8_t rsp_uno_temper[4];
+ uint8_t rsp_due_temper[4];
+
+ int16_t gyro_x = 0;
+ int16_t gyro_y = 0;
+ int16_t gyro_z = 0;
+ int16_t uno_temp = 0;
+ int16_t due_temp = 0;
+
+ // RATE_Y Cmd Send (first response is undefined data)
+ if (!read_register(SCHA63T_DUE, RATE_Y, rsp_rate_y)) {
+ return;
+ }
+
+ // RATE_Z Cmd Send + RATE_Y Response Receive
+ if (!read_register(SCHA63T_DUE, RATE_XZ, rsp_rate_y)) {
+ return;
+ }
+ // TEMPER Cmd Send + RATE_Z Response Receive
+ if (!read_register(SCHA63T_DUE, TEMP, rsp_rate_z)) {
+ return;
+ }
+ // TEMPER Cmd Send + TEMPRE Response Receive
+ if (!read_register(SCHA63T_DUE, TEMP, rsp_due_temper)) {
+ return;
+ }
+ // RATE_X Cmd Send + ACCL_Z Response Receive
+ if (!read_register(SCHA63T_UNO, RATE_XZ, rsp_rate_x)) {
+ return;
+ }
+ // TEMPER Cmd Send + TEMPRE Response Receive
+ if (!read_register(SCHA63T_UNO, TEMP, rsp_rate_x)) {
+ return;
+ }
+ // TEMPER Cmd Send + TEMPRE Response Receive
+ if (!read_register(SCHA63T_UNO, TEMP, rsp_uno_temper)) {
+ return;
+ }
+
+ // response data address check
+ if (((rsp_rate_x[0] & 0x7C) >> 2) != RATE_XZ) {
+ return;
+ }
+ gyro_x = combine(rsp_rate_x[1], rsp_rate_x[2]);
+
+ if (((rsp_rate_y[0] & 0x7C) >> 2) != RATE_Y) {
+ return;
+ }
+ gyro_y = combine(rsp_rate_y[1], rsp_rate_y[2]);
+
+ if (((rsp_rate_z[0] & 0x7C) >> 2) != RATE_XZ) {
+ return;
+ }
+ gyro_z = combine(rsp_rate_z[1], rsp_rate_z[2]);
+
+ if (((rsp_uno_temper[0] & 0x7C) >> 2) != TEMP) {
+ return;
+ }
+ uno_temp = combine(rsp_uno_temper[1], rsp_uno_temper[2]);
+
+ if (((rsp_due_temper[0] & 0x7C) >> 2) != TEMP) {
+ return;
+ }
+ due_temp = combine(rsp_due_temper[1], rsp_due_temper[2]);
+ set_temperature(gyro_instance, (uno_temp + due_temp) * 0.5);
+
+ // change coordinate system from left hand too right hand
+ gyro_z = (gyro_z == INT16_MIN) ? INT16_MAX : -gyro_z;
+
+ Vector3f gyro(gyro_x, gyro_y, gyro_z);
+ gyro *= radians(1.f / 80.f);
+
+ _rotate_and_correct_gyro(gyro_instance, gyro);
+ _notify_new_gyro_raw_sample(gyro_instance, gyro);
+
+ AP_HAL::Device::checkreg reg;
+ if (!dev_due->check_next_register(reg)) {
+ log_register_change(dev_due->get_bus_id(), reg);
+ _inc_gyro_error_count(gyro_instance);
+ }
+}
+
+void AP_InertialSensor_SCHA63T::set_temperature(uint8_t instance, uint16_t temper)
+{
+ const float temperature = 25.0f + ( temper / 30 );
+ const float temp_degc = (0.5f * temperature) + 23.0f;
+ _publish_temperature(instance, temp_degc);
+}
+
+bool AP_InertialSensor_SCHA63T::update()
+{
+ update_accel(accel_instance);
+ update_gyro(gyro_instance);
+ return true;
+}
+
+bool AP_InertialSensor_SCHA63T::read_register(uint8_t uno_due, reg_scha63t reg_addr, uint8_t* val)
+{
+ bool ret = false;
+ uint8_t cmd[4];
+ uint8_t bCrc;
+
+ cmd[1] = cmd[2] = 0;
+ cmd[0] = reg_addr << 2;
+ cmd[0] &= 0x7f;
+ cmd[3] = crc8_sae(cmd, 3);
+
+ uint8_t buf[4];
+ switch (uno_due) {
+ case SCHA63T_UNO:
+ memcpy(buf, cmd, 4);
+ ret = dev_uno->transfer(buf, 4, buf, 4);
+ memcpy(val, buf, 4);
+ break;
+ case SCHA63T_DUE:
+ memcpy(buf, cmd, 4);
+ ret = dev_due->transfer(buf, 4, buf, 4);
+ memcpy(val, buf, 4);
+ break;
+ default:
+ break;
+ }
+
+ if (ret) {
+ bCrc = crc8_sae(val, 3);
+ if (bCrc != val[3]) {
+ ret = false;
+ }
+ }
+
+ // true:OK. false:FAILED
+ return ret;
+}
+
+bool AP_InertialSensor_SCHA63T::write_register(uint8_t uno_due, reg_scha63t reg_addr, uint16_t val)
+{
+ bool ret = false;
+ uint8_t res[4];
+ uint8_t cmd[4];
+
+ cmd[0] = reg_addr << 2;
+ cmd[0] |= 0x80;
+ cmd[1] = (val >> 8);
+ cmd[2] = val;
+ cmd[3] = crc8_sae(cmd, 3);
+
+ uint8_t buf[4];
+ switch (uno_due) {
+ case SCHA63T_UNO:
+ memcpy(buf, cmd, 4);
+ ret = dev_uno->transfer(buf, 4, buf, 4);
+ memcpy(res, buf, 4);
+ break;
+ case SCHA63T_DUE:
+ memcpy(buf, cmd, 4);
+ ret = dev_due->transfer(buf, 4, buf, 4);
+ memcpy(res, buf, 4);
+ break;
+ default:
+ break;
+ }
+
+ // true:OK. false:FAILED
+ return ret;
+}
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h
new file mode 100644
index 0000000000000..3ffc203a26ece
--- /dev/null
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h
@@ -0,0 +1,90 @@
+/*
+ * This file is free software: you can redistribute it and/or modify it
+ * under the terms of the GNU General Public License as published by the
+ * Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This file is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License along
+ * with this program. If not, see .
+ */
+/*
+ the BMI055 is unusual as it has separate chip-select for accel and
+ gyro, which means it needs two SPIDevice pointers
+ */
+#pragma once
+
+#include
+
+#include "AP_InertialSensor.h"
+#include "AP_InertialSensor_Backend.h"
+
+class AP_InertialSensor_SCHA63T : public AP_InertialSensor_Backend
+{
+public:
+ static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
+ AP_HAL::OwnPtr dev_accel,
+ AP_HAL::OwnPtr dev_gyro,
+ enum Rotation rotation);
+
+ /**
+ * Configure the sensors and start reading routine.
+ */
+ void start() override;
+ bool update() override;
+
+ enum reg_scha63t {
+ RATE_XZ = 0x01,
+ RATE_Y = 0x03,
+ ACC_X = 0x04,
+ ACC_Y = 0x05,
+ ACC_Z = 0x06,
+ TEMP = 0x07,
+ S_SUM = 0x0E,
+ R_S1 = 0x10,
+ A_S1 = 0x12,
+ C_S1 = 0x14,
+ C_S2 = 0x15,
+ G_FILT_DYN = 0x16,
+ RESCTRL = 0x18,
+ MODE = 0x19,
+ A_FILT_DYN = 0x1A,
+ T_ID2 = 0x1C,
+ T_ID0 = 0x1D,
+ T_ID1 = 0x1E,
+ SEL_BANK = 0x1F,
+ };
+
+private:
+ AP_InertialSensor_SCHA63T(AP_InertialSensor &imu,
+ AP_HAL::OwnPtr dev_accel,
+ AP_HAL::OwnPtr dev_gyro,
+ enum Rotation rotation);
+
+ /*
+ initialise driver
+ */
+ bool init();
+
+ /*
+ read data from the FIFOs
+ */
+ void read_accel();
+ void read_gyro();
+
+ bool read_register(uint8_t tp, reg_scha63t reg, uint8_t* val);
+ bool write_register(uint8_t tp, reg_scha63t reg, uint16_t val);
+ void set_temperature(uint8_t instance, uint16_t temper);
+ bool check_startup();
+
+ AP_HAL::OwnPtr dev_uno;
+ AP_HAL::OwnPtr dev_due;
+
+ uint8_t accel_instance;
+ uint8_t gyro_instance;
+ enum Rotation rotation;
+};
diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp
index 90274771663de..868239c1aab1a 100644
--- a/libraries/AP_Math/crc.cpp
+++ b/libraries/AP_Math/crc.cpp
@@ -182,6 +182,39 @@ uint8_t crc8_maxim(const uint8_t *data, uint16_t length)
return crc;
}
+// CRC8-SAE J1850 (X8+X4+X3+X2+1) left move table
+static const uint8_t crc8_table_sae[256] = {
+ 0x00, 0x1D, 0x3A, 0x27, 0x74, 0x69, 0x4E, 0x53, 0xE8, 0xF5, 0xD2, 0xCF, 0x9C, 0x81, 0xA6, 0xBB,
+ 0xCD, 0xD0, 0xF7, 0xEA, 0xB9, 0xA4, 0x83, 0x9E, 0x25, 0x38, 0x1F, 0x02, 0x51, 0x4C, 0x6B, 0x76,
+ 0x87, 0x9A, 0xBD, 0xA0, 0xF3, 0xEE, 0xC9, 0xD4, 0x6F, 0x72, 0x55, 0x48, 0x1B, 0x06, 0x21, 0x3C,
+ 0x4A, 0x57, 0x70, 0x6D, 0x3E, 0x23, 0x04, 0x19, 0xA2, 0xBF, 0x98, 0x85, 0xD6, 0xCB, 0xEC, 0xF1,
+ 0x13, 0x0E, 0x29, 0x34, 0x67, 0x7A, 0x5D, 0x40, 0xFB, 0xE6, 0xC1, 0xDC, 0x8F, 0x92, 0xB5, 0xA8,
+ 0xDE, 0xC3, 0xE4, 0xF9, 0xAA, 0xB7, 0x90, 0x8D, 0x36, 0x2B, 0x0C, 0x11, 0x42, 0x5F, 0x78, 0x65,
+ 0x94, 0x89, 0xAE, 0xB3, 0xE0, 0xFD, 0xDA, 0xC7, 0x7C, 0x61, 0x46, 0x5B, 0x08, 0x15, 0x32, 0x2F,
+ 0x59, 0x44, 0x63, 0x7E, 0x2D, 0x30, 0x17, 0x0A, 0xB1, 0xAC, 0x8B, 0x96, 0xC5, 0xD8, 0xFF, 0xE2,
+ 0x26, 0x3B, 0x1C, 0x01, 0x52, 0x4F, 0x68, 0x75, 0xCE, 0xD3, 0xF4, 0xE9, 0xBA, 0xA7, 0x80, 0x9D,
+ 0xEB, 0xF6, 0xD1, 0xCC, 0x9F, 0x82, 0xA5, 0xB8, 0x03, 0x1E, 0x39, 0x24, 0x77, 0x6A, 0x4D, 0x50,
+ 0xA1, 0xBC, 0x9B, 0x86, 0xD5, 0xC8, 0xEF, 0xF2, 0x49, 0x54, 0x73, 0x6E, 0x3D, 0x20, 0x07, 0x1A,
+ 0x6C, 0x71, 0x56, 0x4B, 0x18, 0x05, 0x22, 0x3F, 0x84, 0x99, 0xBE, 0xA3, 0xF0, 0xED, 0xCA, 0xD7,
+ 0x35, 0x28, 0x0F, 0x12, 0x41, 0x5C, 0x7B, 0x66, 0xDD, 0xC0, 0xE7, 0xFA, 0xA9, 0xB4, 0x93, 0x8E,
+ 0xF8, 0xE5, 0xC2, 0xDF, 0x8C, 0x91, 0xB6, 0xAB, 0x10, 0x0D, 0x2A, 0x37, 0x64, 0x79, 0x5E, 0x43,
+ 0xB2, 0xAF, 0x88, 0x95, 0xC6, 0xDB, 0xFC, 0xE1, 0x5A, 0x47, 0x60, 0x7D, 0x2E, 0x33, 0x14, 0x09,
+ 0x7F, 0x62, 0x45, 0x58, 0x0B, 0x16, 0x31, 0x2C, 0x97, 0x8A, 0xAD, 0xB0, 0xE3, 0xFE, 0xD9, 0xC4,
+};
+
+uint8_t crc8_sae(const uint8_t *data, uint16_t length)
+{
+ uint8_t crc = 0xFF;
+
+ while (length--) {
+ crc = crc8_table_sae[crc ^ (*data & 0xFF)];
+ data++;
+ }
+ crc ^= 0xFF;
+
+ return crc;
+}
+
/*
xmodem CRC thanks to avr-liberty
https://github.com/dreamiurg/avr-liberty
diff --git a/libraries/AP_Math/crc.h b/libraries/AP_Math/crc.h
index dc8daaaf6d3d4..ecc606e0ca1ba 100644
--- a/libraries/AP_Math/crc.h
+++ b/libraries/AP_Math/crc.h
@@ -24,6 +24,7 @@ uint8_t crc8_dvb(uint8_t crc, uint8_t a, uint8_t seed);
uint8_t crc8_dvb_s2_update(uint8_t crc, const void *data, uint32_t length);
uint8_t crc8_dvb_update(uint8_t crc, const uint8_t* buf, const uint16_t buf_len);
uint8_t crc8_maxim(const uint8_t *data, uint16_t length);
+uint8_t crc8_sae(const uint8_t *data, uint16_t length);
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data);
uint16_t crc_xmodem(const uint8_t *data, uint16_t len);
uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size);