forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
AP_HAL_ChibiOS/hwdef: JFB110 board definition
- Loading branch information
1 parent
d808133
commit 79c5cae
Showing
15 changed files
with
2,629 additions
and
4 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file not shown.
Large diffs are not rendered by default.
Oops, something went wrong.
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 Pin12 -> ADC SPARE 1 | ||
- ADC Pin13 -> 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. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,47 @@ | ||
# board setting | ||
BRD_VBUS_MIN 4.9 | ||
|
||
# setup SERIAL0(OTG1) to Mavlink2 | ||
SERIAL0_BAUD 1500 | ||
SERIAL0_PROTOCOL 2 | ||
# setup SERIAL1 to telem1 | ||
SERIAL1_BAUD 921 | ||
SERIAL1_PROTOCOL 2 | ||
SERIAL1_OPTIONS 0 | ||
# setup SERIAL2 to telem2 | ||
SERIAL2_BAUD 921 | ||
SERIAL2_PROTOCOL 2 | ||
SERIAL2_OPTIONS 0 | ||
# setup SERIAL3 to GPS | ||
SERIAL3_BAUD 57 | ||
SERIAL3_PROTOCOL 5 | ||
SERIAL3_OPTIONS 0 | ||
# setup SERIAL4 for BPort | ||
SERIAL4_BAUD 57 | ||
SERIAL4_PROTOCOL -1 | ||
SERIAL4_OPTIONS 0 | ||
# setup SERIAL5 to RCIN | ||
SERIAL5_BAUD 100 | ||
SERIAL5_PROTOCOL 23 | ||
SERIAL5_OPTIONS 3 | ||
# setup SERIAL6 to SBUS OUT | ||
SERIAL6_BAUD 100 | ||
SERIAL6_PROTOCOL 15 | ||
SERIAL6_OPTIONS 3 | ||
# setup SERIAL7 for debug console | ||
SERIAL7_BAUD 921 | ||
SERIAL7_PROTOCOL 0 | ||
SERIAL7_OPTIONS 0 | ||
# setup SERIAL8(OTG2) to SLCAN | ||
SERIAL8_BAUD 1500 | ||
SERIAL8_PROTOCOL 22 | ||
SERIAL8_OPTIONS 0 | ||
|
||
#Three IMU Setting | ||
EK3_IMU_MASK 7 | ||
INS_ENABLE_MASK 7 | ||
|
||
#RSSI Setting | ||
RSSI_TYPE 1 | ||
RSSI_ANA_PIN 10 | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,140 @@ | ||
# hw definition file for processing by chibios_hwdef.py | ||
# for the JFB110 hardware | ||
# define AP_CUSTOM_FIRMWARE_STRING "(JFB110 V1.1.0)" | ||
|
||
# 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 |
Oops, something went wrong.