-
Notifications
You must be signed in to change notification settings - Fork 18.2k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
5 changed files
with
325 additions
and
0 deletions.
There are no files selected for viewing
116 changes: 116 additions & 0 deletions
116
libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405AIO/README.md
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,116 @@ | ||
# SpeedyBee F405 AIO 40A Bluejay | ||
|
||
https://www.speedybee.com/speedybee-f405-aio-40a-bluejay-25-5x25-5-3-6s-flight-controller | ||
|
||
The SpeedyBee F405 AIO is a flight controller produced by [SpeedyBee](https://www.speedybee.com/). | ||
|
||
## Features | ||
|
||
- MCU: STM32F405 32-bit processor. 1024Kbytes Flash | ||
- IMU: ICM-42688P (SPI) | ||
- Barometer: SPA06-003 | ||
- USB VCP Driver (all UARTs usable simultaneously; USB does not take up a UART) | ||
- 6 UARTS (UART1 tied internally to BT module which is not currently supported by ArduPilot) | ||
- 8MBytes for logging | ||
- 5V Power Out: 2.0A max | ||
- Dimensions: 33x33mm | ||
- Mounting Holes: Standard 25.5/25.5mm square to center of holes | ||
- Weight: 13.6g | ||
|
||
- Built-in 40A BlueJay 4in1 ESC | ||
- Supports Oneshot125, Oneshot42, Multishot, Dshot150, Dshot300, Dshot600 | ||
- Input Voltage: 3S-6S Lipo | ||
- Continuous Current: 40A | ||
- Bluejay JH-40 48kHz | ||
|
||
## Pinout | ||
|
||
data:image/s3,"s3://crabby-images/83014/830142a3c6122139626234fc78db73336ea2d87e" alt="SpeedyBee F405 AIO" | ||
|
||
.. note:: S pin for "Meteor LED" does not work with this firmware | ||
|
||
## UART Mapping | ||
|
||
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the | ||
receive pin for UARTn. The Tn pin is the transmit pin for UARTn. | ||
|Name|Pin|Function| | ||
|:-|:-|:-| | ||
|SERIAL0|COMPUTER|USB| | ||
|SERIAL1|RX1/TX1|USART1 (WiFi, not usable by ArduPilot)| | ||
|SERIAL2|RX2|USART2 (USER, RX tied to SBUS pin, Inverted)| | ||
|SERIAL3|TX3/RX3|USART3 (DisplayPort)| | ||
|SERIAL4|TX4/RX4|UART4 (User)| | ||
|SERIAL5|TX5/RX5|UART5 (GPS)| | ||
|SERIAL6|TX6/RX6|UART6 (RCin, DMA-enabled)| | ||
|
||
USART6 supports RX and TX DMA. | ||
|
||
## RC Input | ||
|
||
RC input is configured on UART6. It supports all RC protocols except PPM, FPort, and SBUS. See:ref:`[Radio Control Systems<common-rc-systems>` for details for a specific RC system. :ref:`SERIAL6_PROTOCOL<SERIAL6_PROTOCOL>` is set to “23”, by default, to enable this. | ||
* FPort requires an external bi-directional inverter and connects to TX 6 with :ref:`SERIAL6_OPTIONS<SERIAL6_OPTIONS>` set to "7". | ||
* CRSF requires a TX6 connection, in addition to RX6, and automatically provides telemetry. | ||
* SRXL2 requires a connection to TX6 and automatically provides telemetry. Set :ref:`SERIAL6_OPTIONS<SERIAL6_OPTIONS>` set to "4". | ||
|
||
* SBUS can be directly connected to the SBUS pin which ties through an inverter to the RX2 pin. :ref:`SERIAL2_PROTOCOL<SERIAL2_PROTOCOL>` must be set to "23" and :ref:`SERIAL6_PROTOCOL<SERIAL6_PROTOCOL>` must be changed to something else than "23" | ||
|
||
Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See [Radio Control Systems](https://ardupilot.org/plane/docs/common-rc-systems.html#common-rc-systems) for details. | ||
|
||
## OSD Support | ||
|
||
The SpeedyBee F405 AIO supports OSD using :ref:`OSD_TYPE<OSD_TYPE>` = 1 (MAX7456 driver). The defaults are also setup to allow DJI Goggle OSD support on UART3. Both the internal analog OSD and the DisplayPort OSD can be used simultaneously by setting :ref:`OSD_TYPE2<OSD_TYPE2>`= 5 | ||
|
||
## PWM Output | ||
|
||
The SpeedyBee F405 AIO supports up to 5 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are the first 4 outputs.All 5 outputs support DShot. | ||
|
||
The PWM are in 3 groups: | ||
|
||
PWM 1-2: Group 1 | ||
PWM 3-4: Group 2 | ||
LED: Group 3 | ||
|
||
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. PWM 1-4 support bidirectional dshot. | ||
|
||
## Battery Monitoring | ||
|
||
The board has a builtin voltage sensor. The voltage sensor can handle 2S to 6S | ||
LiPo batteries. | ||
|
||
The correct battery setting parameters are: | ||
|
||
- BATT_MONITOR 4 | ||
- BATT_VOLT_PIN 10 | ||
- BATT_VOLT_MULT around 11 | ||
- BATT_CURR_PIN 12 | ||
- BATT_AMP_PERVLT 39.4 | ||
|
||
These are set by default in the firmware and shouldn't need to be adjusted | ||
|
||
## Compass | ||
|
||
The SpeedyBee F405 AIO does not have a builtin compass but an external compass can be attached using the SDA/SCL pins. | ||
|
||
## Camera Control | ||
|
||
The CC pin is a GPIO (pin 70) and is assigned by default to RELAY2 functionality. This pin can be controlled via GCS or by RC transmitter using the :ref:`Auxiliary Function<common-auxiliary-functions>` feature. | ||
|
||
## NeoPixel LED | ||
|
||
The board includes a NeoPixel LED pad. | ||
|
||
## Firmware | ||
|
||
Firmware for this board can be found: `here <https://firmware.ardupilot.org>`__ in sub-folders labeled “SpeedyBeeF405AIO”. | ||
|
||
## Loading Firmware (you will need to compile your own firmware) | ||
|
||
Initial firmware load can be done with DFU by plugging in USB with the | ||
bootloader button pressed. Then you should load the "with_bl.hex" | ||
firmware, using your favourite DFU loading tool. | ||
|
||
Once the initial firmware is loaded you can update the firmware using | ||
any ArduPilot ground station software. Updates should be done with the | ||
*.apj firmware files. |
Binary file added
BIN
+211 KB
libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405AIO/SpeedyBeeF405AIO_Pinout.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
12 changes: 12 additions & 0 deletions
12
libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405AIO/defaults.parm
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,12 @@ | ||
# WS2812 LED | ||
SERVO5_FUNCTION 120 | ||
|
||
NTF_LED_TYPES 257 | ||
|
||
# Bluejay installed by default | ||
SERVO_BLH_BDMASK 15 | ||
SERVO_DSHOT_ESC 4 | ||
SERVO_BLH_AUTO 1 | ||
MOT_PWM_TYPE 6 | ||
|
||
GPS_DRV_OPTIONS 4 |
43 changes: 43 additions & 0 deletions
43
libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405AIO/hwdef-bl.dat
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,43 @@ | ||
|
||
# hw definition file for processing by chibios_hwdef.py | ||
# for SPEEDYBEEF405AIO hardware. | ||
# thanks to betaflight for pin information | ||
|
||
# MCU class and specific type | ||
MCU STM32F4xx STM32F405xx | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 5271 | ||
|
||
# crystal frequency, setup to use external oscillator | ||
OSCILLATOR_HZ 8000000 | ||
|
||
FLASH_SIZE_KB 1024 | ||
|
||
# bootloader starts at zero offset | ||
FLASH_RESERVE_START_KB 0 | ||
|
||
# the location where the bootloader will put the firmware | ||
FLASH_BOOTLOADER_LOAD_KB 48 | ||
|
||
# order of UARTs (and USB) | ||
SERIAL_ORDER OTG1 | ||
|
||
# PA10 IO-debug-console | ||
PA11 OTG_FS_DM OTG1 | ||
PA12 OTG_FS_DP OTG1 | ||
|
||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# default to all pins low to avoid ESD issues | ||
DEFAULTGPIO OUTPUT LOW PULLDOWN | ||
|
||
|
||
# Chip select pins | ||
PB12 FLASH1_CS CS | ||
PD5 OSD1_CS CS | ||
PA4 GYRO1_CS CS | ||
|
||
PA8 LED_BOOTLOADER OUTPUT LOW | ||
define HAL_LED_ON 0 |
154 changes: 154 additions & 0 deletions
154
libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405AIO/hwdef.dat
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,154 @@ | ||
|
||
# hw definition file for processing by chibios_hwdef.py | ||
# for SPEEDYBEEF405AIO hardware. | ||
# thanks to betaflight for pin information | ||
|
||
# MCU class and specific type | ||
MCU STM32F4xx STM32F405xx | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 5271 | ||
|
||
# crystal frequency, setup to use external oscillator | ||
OSCILLATOR_HZ 8000000 | ||
|
||
FLASH_SIZE_KB 1024 | ||
|
||
# bootloader takes first sector | ||
FLASH_RESERVE_START_KB 48 | ||
|
||
define HAL_STORAGE_SIZE 16384 | ||
define STORAGE_FLASH_PAGE 1 | ||
|
||
STM32_ST_USE_TIMER 4 | ||
define CH_CFG_ST_RESOLUTION 16 | ||
|
||
# SPI devices | ||
|
||
# SPI1 | ||
PA5 SPI1_SCK SPI1 | ||
PA6 SPI1_MISO SPI1 | ||
PA7 SPI1_MOSI SPI1 | ||
|
||
# SPI2 | ||
PB13 SPI2_SCK SPI2 | ||
PB14 SPI2_MISO SPI2 | ||
PB15 SPI2_MOSI SPI2 | ||
|
||
# SPI3 | ||
PB3 SPI3_SCK SPI3 | ||
PB4 SPI3_MISO SPI3 | ||
PB5 SPI3_MOSI SPI3 | ||
|
||
# Chip select pins | ||
PB12 FLASH1_CS CS | ||
PD5 OSD1_CS CS | ||
PA4 GYRO1_CS CS | ||
|
||
# Beeper | ||
PD11 BUZZER OUTPUT GPIO(80) LOW | ||
define HAL_BUZZER_PIN 80 | ||
|
||
# SERIAL ports | ||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 | ||
# PA10 IO-debug-console | ||
PA11 OTG_FS_DM OTG1 | ||
PA12 OTG_FS_DP OTG1 | ||
|
||
# USART1 - WiFi | ||
PA10 USART1_RX USART1 NODMA | ||
PA9 USART1_TX USART1 NODMA | ||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None | ||
|
||
# USART2 - SBUS | ||
PD6 USART2_RX USART2 NODMA | ||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None | ||
|
||
# USART3 - VTX / DJI | ||
PD8 USART3_TX USART3 NODMA | ||
PD9 USART3_RX USART3 NODMA | ||
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort | ||
|
||
# UART4 | ||
PC10 UART4_TX UART4 NODMA | ||
PC11 UART4_RX UART4 NODMA | ||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None | ||
|
||
# UART5 - GPS | ||
PC12 UART5_TX UART5 NODMA | ||
PD2 UART5_RX UART5 NODMA | ||
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS | ||
|
||
# USART6 - RX | ||
PC6 USART6_TX USART6 | ||
PC7 USART6_RX USART6 | ||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN | ||
|
||
# I2C ports | ||
I2C_ORDER I2C1 | ||
# I2C1 | ||
PB8 I2C1_SCL I2C1 | ||
PB9 I2C1_SDA I2C1 | ||
|
||
# Servos | ||
PD15 CAMERA1 OUTPUT GPIO(70) LOW | ||
define RELAY2_PIN_DEFAULT 70 | ||
|
||
# ADC ports | ||
|
||
# ADC1 | ||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) | ||
define HAL_BATT_VOLT_PIN 10 | ||
define HAL_BATT_VOLT_SCALE 11.0 | ||
PC2 BATT_CURRENT_SENS ADC1 SCALE(1) | ||
define HAL_BATT_CURR_PIN 12 | ||
define HAL_BATT_CURR_SCALE 39.4 | ||
define HAL_BATT_MONITOR_DEFAULT 4 | ||
|
||
# MOTORS | ||
PA1 TIM2_CH2 TIM2 PWM(1) GPIO(50) BIDIR # M1 | ||
PA0 TIM2_CH1 TIM2 PWM(2) GPIO(51) # M2 | ||
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR # M3 | ||
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4 | ||
|
||
# LEDs | ||
PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5 | ||
|
||
PD7 LED0 OUTPUT LOW GPIO(90) | ||
define HAL_GPIO_A_LED_PIN 90 | ||
|
||
# Dataflash setup | ||
SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ | ||
|
||
define HAL_LOGGING_DATAFLASH_ENABLED 1 | ||
|
||
# OSD setup | ||
SPIDEV osd SPI3 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ | ||
|
||
define OSD_ENABLED 1 | ||
define HAL_OSD_TYPE_DEFAULT 1 | ||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin | ||
|
||
# IMU setup | ||
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ | ||
IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_135 | ||
DMA_NOSHARE TIM5* TIM2* SPI1* | ||
DMA_PRIORITY TIM5* TIM2* SPI1* I2C1* | ||
|
||
# Barometer setup | ||
define AP_BARO_BACKEND_DEFAULT_ENABLED 0 | ||
define AP_BARO_SPL06_ENABLED 1 | ||
BARO SPL06 I2C:0:0x76 | ||
|
||
# no built-in compass, but probe the i2c bus for all possible | ||
# external compass types | ||
define ALLOW_ARM_NO_COMPASS | ||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES | ||
define HAL_I2C_INTERNAL_MASK 0 | ||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2 | ||
define HAL_DEFAULT_INS_FAST_SAMPLE 1 | ||
# Motor order implies Betaflight/X for standard ESCs | ||
define HAL_FRAME_TYPE_DEFAULT 12 | ||
|
||
# minimal drivers to reduce flash usage | ||
include ../include/minimize_fpv_osd.inc |