diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md new file mode 100644 index 0000000000..7f53b54bd9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md @@ -0,0 +1,102 @@ +# SpeedyBeeF405WING Flight Controller + +The SpeedyBeeF405WING is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + Processor + STM32F405 168Mhz, 1MB 32-bit processor + AT7456E OSD + Sensors + ICM42688P Acc/Gyro + SPL006 barometer + Power + 2S - 6S Lipo input voltage with voltage monitoring + 90A Cont., 215A peak current monitor + 9V/12/5V, 1.8A BEC for powering Video Transmitter + 4.9V/6V/7.2V, 4.5A BEC for servos + 5V, 2.4A BEC for internal and peripherals + Interfaces + 12x PWM outputs DShot capable (Serail LED output is PWM12) + 1x RC input + 5x UARTs/serial for GPS and other peripherals, 6th UART internally tied to Wireless board) + I2C port for external compass, airspeed, etc. + microSDCard for logging, etc. + USB-C port + + +## Pinout + +![SpeedyBeeF405WING](SpeedyBeeF405WING.png) + +## Wiring Diagram + +![SpeedyBeeF405WING Wiring](SpeedyBeeF405WING_wiring.png) + +## 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. + + - SERIAL0 -> USB + - SERIAL1 -> USART1 (Serial RC input) (DMA capable) + - SERIAL2 -> USART2 (RX tied to inverted SBUS RC input, but can be used as normal UART if :ref:`BRD_ALT_CONFIG<>` =1) + - SERIAL3 -> UART3 (GPS) (TX DMA capable) + - SERIAL4 -> UART4 (User) (TX DMA capable) + - SERIAL5 -> UART5 (User, available on DJI air unit connector) (TX DMA capable) + - SERIAL6 -> UART6 (tied to internal wireless module, MAVLink2 telem) + + +## RC Input + +RC input is configured on the SBUS pin (inverted and sent to UART2_RX). It supports all RC +protocols except serial protocols such as CRSF, ELRS, etc. Those devices can be connected to USART1 TX and RX, instead. +Fport can be connected to USART1 TX also, but will require an external bi-directional inverter and the ref:`SERIAL1_OPTION' = 4 (HalfDuplex) set. + +## OSD Support + +The SpeedyBeeF405Wing supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such as DJI or DisplayPort is supported using UART5 or any other free UART5. See :ref:`common-msp-osd-overview-4.2` for more info. + +## PWM Output + +The SpeedyBeeF405Wing supports up to 12 PWM outputs (PWM12 is the serial LED output, by default). All outputs support DShot. + +The PWM is in 5 groups: + + - PWM 1,2 in group1 + - PWM 2,4 in group2 + - PWM 5-7 in group3 + - PWM 8-10 in group4 + - PWM 11,12 in group5 Note: PWM12 is setup for LED use by default, if PWM11 is used, you must re-assign PMW12 to a normal PWM output or nothing + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in that group would need +to use DShot. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 90A continuosly, 215 Amps peak. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are set by default and are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.5 + - BATT_AMP_PERVLT 50 + +## Compass + +The SpeedyBeeF405Wing does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “SpeedyBeeF405Wing”. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "SpeedyBeeF405Wing_bl.hex" +firmware, using your favourite DFU loading tool. + +Subsequently, you can update firmware with Mission Planner. + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png new file mode 100644 index 0000000000..ac32c47e9d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING_wiring.png b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING_wiring.png new file mode 100644 index 0000000000..e2f8a47030 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING_wiring.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/defaults.parm new file mode 100644 index 0000000000..fe1e4e7096 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/defaults.parm @@ -0,0 +1,9 @@ +# WS2812 LED +NTF_LED_LEN,4 +NTF_LED_TYPES 257 +SERVO12_FUNCTION,120 + +#Serial Port defaults +SERIAL1_PROTOCOL 23 +SERIAL4_PROTOCOL -1 +SERIAL6_PROTOCOL 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat new file mode 100644 index 0000000000..84d03b16a6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat @@ -0,0 +1,37 @@ +# hw definition file for processing by chibios_pins.py +# for speedybeef4 bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1106 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + +# LEDs +PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) +PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) +define HAL_LED_ON 0 + +# order of UARTs +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# Add CS pins to ensure they are high in bootloader +PA4 MPU_CS CS +PB12 OSD_CS CS +PC14 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat new file mode 100644 index 0000000000..0c0604d55b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat @@ -0,0 +1,224 @@ +# hw definition file for SpeedyBee F4 WING hardware +# tested on the Speedybee F405 WING board +# + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1106 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# reserve 16k for bootloader, 16k for OSD and 32k for flash storage +FLASH_RESERVE_START_KB 64 +FLASH_SIZE_KB 1024 + +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# only one I2C bus +I2C_ORDER I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 + +# LEDs +PA13 LED_GREEN OUTPUT LOW GPIO(0) +PA14 LED_BLUE OUTPUT LOW GPIO(1) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 + +# buzzer +PC15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +# spi1 bus for IMU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 MPU_CS CS + +# spi2 for OSD +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PB12 OSD_CS CS + +# spi3 for sdcard +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 +PC14 SDCARD_CS CS + +# only one I2C bus in normal config +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# analog pins +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC4 RSSI_ADC_PIN ADC1 SCALE(1) + +PC5 PRESSURE_SENS ADC1 SCALE(1) +define HAL_DEFAULT_AIRSPEED_PIN 15 + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 11.05 # matched to PDB board +define HAL_BATT_CURR_SCALE 50 # matched to PDB board + +# analog rssi pin +define BOARD_RSSI_ANA_PIN 14 + +# USART1 (ELRS) +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + + +# USART2 (RCIN with inverter) + +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW + +# alternative with PA3 as USART2_RX +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) + +# USART3 (GPS) +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 NODMA + +# UART4 serial4 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA + +# USART5 (DJI / VTX) +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 NODMA + +# UART6 (onboard Telemetry) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define HAL_SERIAL6_BAUD 115 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# PWM out pins. Note that channel order follows the ArduPilot motor +# order conventions +PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) +PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51) +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) +PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) +PB14 TIM8_CH2N TIM8 PWM(7) GPIO(56) + +PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) +PB10 TIM2_CH3 TIM2 PWM(9) GPIO(58) +PB11 TIM2_CH4 TIM2 PWM(10) GPIO(59) + +PB15 TIM1_CH3N TIM1 PWM(11) GPIO(60) +PA8 TIM1_CH1 TIM1 PWM(12) GPIO(61)# LED + +# one IMU +IMU Invensensev3 SPI:icm42605 ROTATION_ROLL_180_YAW_270 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# one baro +BARO SPL06 I2C:0:0x76 +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_SPL06_ENABLED 1 + +# 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 + +# ICM42688P on SPI1 +SPIDEV icm42605 SPI1 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ + +# OSD on SPI2 +SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ + +# SD Card on SPI3 +SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + +define STM32_PWM_USE_ADVANCED TRUE + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 +define HAL_WITH_DSP FALSE + +# save some flash + +# disable SMBUS and fuel battery monitors to save flash +define AP_BATTMON_SMBUS_ENABLE 0 +define AP_BATTMON_FUEL_ENABLE 0 +define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0 +define HAL_BATTMON_INA2XX_ENABLED 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 +define AP_GRIPPER_ENABLED 0 +define HAL_GENERATOR_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +#define LANDING_GEAR_ENABLED 0 +define WINCH_ENABLED 0 +define HAL_ADSB_ENABLED 0 + +define AC_OAPATHPLANNER_ENABLED 0 +define PRECISION_LANDING 0 +#define HAL_BARO_WIND_COMP_ENABLED 0 +define AP_OPTICALFLOW_ENABLED 0 + + +# Disable un-needed hardware drivers +define HAL_WITH_ESC_TELEM 0 +define AP_FETTEC_ONEWIRE_ENABLED 0 + +define AP_VOLZ_ENABLED 0 +define AP_ROBOTISSERVO_ENABLE 0 +define HAL_PICCOLO_CAN_ENABLE 0 +define HAL_TORQEEDO_ENABLED 0 +define HAL_RUNCAM_ENABLED 0 +define HAL_HOTT_TELEM_ENABLED 0 +define HAL_NMEA_OUTPUT_ENABLED 0 +define HAL_BUTTON_ENABLED 0 +define AP_NOTIFY_OREOLED_ENABLED 0 + +#only support MS4525 ANALOG ASP5033 driver +define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0 +define AP_AIRSPEED_MS4525_ENABLED 1 +define AP_AIRSPEED_ANALOG_ENABLED 1 +define AP_AIRSPEED_ASP5033_ENABLED 1 + +#only support UBLOX and NMEA GPS driver +define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 +define AP_GPS_NMEA_ENABLED 1 + +define AP_TRAMP_ENABLED 1