diff --git a/Tools/bootloaders/JFB-X_bl.bin b/Tools/bootloaders/JFB-X_bl.bin new file mode 100644 index 0000000000000..06d3969c94474 Binary files /dev/null and b/Tools/bootloaders/JFB-X_bl.bin differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/README.md b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/README.md new file mode 100644 index 0000000000000..a5f52fdd550d8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/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/JFB-X/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/defaults.parm new file mode 100644 index 0000000000000..4207e693ce825 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/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/JFB-X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/hwdef-bl.dat new file mode 100644 index 0000000000000..f357c1b03e916 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/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 + +PE3 LED_BOOTLOADER OUTPUT HIGH +PE4 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/JFB-X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/hwdef.dat new file mode 100644 index 0000000000000..e341e05b4fb60 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB-X/hwdef.dat @@ -0,0 +1,368 @@ +# 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 +PA3 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 +PD5 USART2_TX USART2 + +# 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 +PG9 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 +PA4 BATT_CURRENT_SENS ADC1 SCALE(1) # ADC1_18 +PF5 BATT2_VOLTAGE_SENS ADC3 SCALE(1) # ADC3_4 +PF12 BATT2_CURRENT_SENS ADC1 SCALE(1) # ADC1_6 + +# 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 18 +define HAL_BATT2_VOLT_PIN 4 +define HAL_BATT2_CURR_PIN 6 + +# Now the VDD sense pin. This is used to sense primary board voltage. +PH4 VDD_5V_SENS ADC3 SCALE(2) # ADC3_15 +define ANALOG_VCC_5V_PIN 15 +define HAL_HAVE_BOARD_VOLTAGE 1 +PA9 VBUS_RESERVED INPUT + +# JFB110 has SERVORAIL ADC +PF11 SCALED_V3V3 ADC1 SCALE(2) # ADC1_2 +#PA3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(2) # ADC1_15 + +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 +PJ5 VDD_3V3_SENSORS2_EN OUTPUT LOW +PJ4 VDD_3V3_SENSORS3_EN OUTPUT LOW +PG8 VDD_3V3_SENSORS4_EN OUTPUT LOW +#VDD_3V3_SD_CARD_EN OUTPUT LOW + +# controlled manually +PK5 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW +PK4 GPIO_CAN2_SILENT OUTPUT PUSHPULL LOW + +# Control of Spektrum power pin +# no SPEKTRUM_RC pin so this is controlled +# manually +PJ14 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 +PJ15 VDD_5V_PERIPH_nOC INPUT +PF13 VDD_5V_HIPOWER_nOC INPUT + +# ID pins +PG0 HW_VER_REV_DRIVE OUTPUT LOW SPEED_VERYLOW +PF4 HW_VER_SENS ADC3 SCALE(1) # ADC3_9 +PF3 HW_REV_SENS ADC3 SCALE(1) # ADC3_5 + +# SPI1 - IMU1(murata),MS5611(BARO),EEPROM +PA5 SPI1_SCK SPI1 SPEED_VERYLOW +PB5 SPI1_MOSI SPI1 SPEED_VERYLOW +PA6 SPI1_MISO SPI1 SPEED_VERYLOW +PJ2 SCHA63T_A_CS CS SPEED_VERYLOW # SPI1_CS1 +PJ3 SCHA63T_G_CS CS SPEED_VERYLOW # SPI1_CS2 +PH15 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 +PE6 SPI4_MOSI SPI4 SPEED_VERYLOW +PE13 SPI4_MISO SPI4 SPEED_VERYLOW +PG15 MS5611_2_CS CS SPEED_VERYLOW # SPI4_CS1 +PH5 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 +#PJ10 SPI5_MOSI SPI5 SPEED_VERYLOW +#PE2 SPI5_CS1 CS SPEED_VERYLOW +#PD11 SPI5_CS2 CS + +# IMU Device Ready Signal Input +PA15 DRDY1_IIM42652_1 INPUT +PF2 DRDY2_IIM42652_1 INPUT +PK3 DRDY1_IIM42652_2 INPUT +PK7 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 +PI5 TIM8_CH1 TIM8 PWM(1) GPIO(50) SPEED_VERYLOW +PE14 TIM1_CH4 TIM1 PWM(2) GPIO(51) SPEED_VERYLOW +PC7 TIM3_CH2 TIM3 PWM(3) GPIO(52) SPEED_VERYLOW +PC6 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 +PI7 TIM8_CH3 TIM8 PWM(7) GPIO(56) SPEED_VERYLOW +PI2 TIM8_CH4 TIM8 PWM(8) GPIO(57) SPEED_VERYLOW +PA10 TIM1_CH3 TIM1 PWM(9) GPIO(58) SPEED_VERYLOW +PJ11 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 +PB1 TIM3_CH4 TIM3 PWM(14) GPIO(63) SPEED_VERYLOW +PI6 TIM8_CH2 TIM8 PWM(15) GPIO(64) SPEED_VERYLOW +PB0 TIM3_CH3 TIM3 PWM(16) GPIO(65) SPEED_VERYLOW +PK2 PWM_OE OUTPUT HIGH +PJ12 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 +PB3 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 +PJ13 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 +PK6 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) +PH6 TIM12_CH1 TIM12 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 + +# 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 + + +# Ethernet +PA1 ETH_RMII_REF_CLK ETH1 +PA2 ETH_MDIO ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PC1 ETH_MDC ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PG11 ETH_RMII_TX_EN ETH1 +PG13 ETH_RMII_TXD0 ETH1 +PG14 ETH_RMII_TXD1 ETH1 + +define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_RMII \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py index 2e29865e1cd52..939e1e19b0d52 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H755xx.py @@ -1285,3 +1285,40 @@ "PA4" : 18, "PA5" : 19, } + +ADC2_map = { + "PF13" : 2, + "PA6" : 3, + "PC4" : 4, + "PB1" : 5, + "PF14" : 6, + "PA7" : 7, + "PC5" : 8, + "PB0" : 9, + "PC0" : 10, + "PC1" : 11, + "PC2" : 12, + "PC3" : 13, + "PA2" : 14, + "PA3" : 15, + "PA4" : 18, + "PA5" : 19, +} + +ADC3_map = { + "PF9" : 2, + "PF7" : 3, + "PF5" : 4, + "PF3" : 5, + "PF10" : 6, + "PF8" : 7, + "PF6" : 8, + "PF4" : 9, + "PC0" : 10, + "PC1" : 11, + "PC2" : 12, + "PH2" : 13, + "PH3" : 14, + "PH4" : 15, + "PH5" : 16, +}