diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405.png b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405.png new file mode 100644 index 0000000000..0c8afbe3d6 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405_wiring.png b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405_wiring.png new file mode 100644 index 0000000000..825008ccf5 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/CSKY405_wiring.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/Readme.md new file mode 100644 index 0000000000..d33f147cb8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/Readme.md @@ -0,0 +1,102 @@ +# CSKY405 Flight Controller + +The CSKY405 is a flight controller produced by [ClearSky](http://csky.space/products/csky_405). + + +## Features + Processor + STM32F405 168Mhz, 1MB 32-bit processor + AT7456E OSD + Sensors + BMI088 Acc/Gyro + BMP390 barometer + Power + 2S - 6S Lipo input voltage with voltage monitoring + 90A Cont., 215A peak current monitor + 12V, 2A BEC for powering Video Transmitter controlled by GPIO + 5V, 2.5A BEC for internal and peripherals + Interfaces + 10x PWM outputs DShot capable + 1x RC input + 6x UARTs/serial for GPS and other peripherals + I2C port for external compass, airspeed, etc. + microSDCard for logging, etc. + USB-C port + +## Overview + +![CSKY405](CSKY405.png) + +## Wiring Diagram + +![CSKY405 Wiring](CSKY405_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 -> UART4 (MAVLink2 telem) + - SERIAL2 -> USART1 (Serial RC input) (DMA capable) + - SERIAL3 -> UART5 (GPS) + - SERIAL4 -> USART3 (User) (TX DMA capable) + - SERIAL5 -> USART6 (User) (TX DMA capable) + - SERIAL6 -> USART2(DMA Capable) (RX2 normally only used for single wire RC inputs (SBUS)PPM,etc.)t, but can be used as normal UART if :ref:`BRD_ALT_CONFIG<>` =1) + + +## RC Input + +RC input is configured on the RX2 pin (inverted and sent to UART2_RX). It supports all single wire RC +protocols except serial protocols such as CRSF, ELRS, etc. Instead, these devices can be connected using both TX2 and RX2 if if :ref:`BRD_ALT_CONFIG` =1 and :ref:`SERIAL6_PROTOCOL` set to "23". + + +## OSD Support + +The CSKY405 supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such as DJI or DisplayPort is supported using USART6 or any other free Uaet. See :ref:`common-msp-osd-overview-4.2` for more info. + +## PWM Output + +The CSKY405 supports up to 10 PWM outputs. All outputs support DShot. + +The PWM is in 5 groups: + + - PWM 1 in group1 + - PWM 2 in group2 + - PWM 3,4 in group3 + - PWM 5,6,10 in group4 + - PWM 7 in group5 + - PWM 8,9 in group6 + +## Battery Monitoring + +The board has a builting voltage and current sensors. 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 14 + - BATT_CURR_PIN 7 + - BATT_VOLT_MULT 21.0 + - BATT_AMP_PERVLT 10.35 + +## Compass + +The CSKY405 does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## VTX power control + +GPIO 84 controls the VTX BEC output to pins marked "12V". Setting this GPIO high removes voltage supply to pins. + +## Loading Firmware +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled CSKY405. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "CSKY405_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/CSKY405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef-bl.dat new file mode 100644 index 0000000000..40c084283a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef-bl.dat @@ -0,0 +1,36 @@ +# hw definition file for CSKY405 + +USB_STRING_MANUFACTURER "CSKY" + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID 1158 + +FLASH_RESERVE_START_KB 0 +FLASH_SIZE_KB 1024 +FLASH_BOOTLOADER_LOAD_KB 48 + +PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue +PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # Green +define HAL_LED_ON 0 + +# order of UARTs +SERIAL_ORDER OTG1 USART1 + +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Add CS pins to ensure they are high in bootloader +PC14 BMI088_A_CS CS +PA4 BMI088_G_CS CS +PB12 OSD_CS CS +PC13 FLASH_CS CS +PC1 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat new file mode 100644 index 0000000000..d7f74cc7ba --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat @@ -0,0 +1,190 @@ +# hw definition file for CSKY405 + +USB_STRING_MANUFACTURER "CSKY" + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# bootloader starts firmware at 48k +FLASH_RESERVE_START_KB 48 +FLASH_SIZE_KB 1024 + +# store parameters in pages 11 and 12 +STORAGE_FLASH_PAGE 1 +define HAL_STORAGE_SIZE 15360 + +# board ID for firmware load +APJ_BOARD_ID 1158 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# crystal frequency +OSCILLATOR_HZ 8000000 + + +# --------------------- LED ----------------------- +PA14 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT +PA13 LED1 OUTPUT LOW GPIO(91) # green marked as B/E +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# --------------------- PWM ----------------------- +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) // S1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) // S2 +PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) // S3 +PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) // S4 + +PB11 TIM2_CH4 TIM2 PWM(5) GPIO(54) // S5 +PB10 TIM2_CH3 TIM2 PWM(6) GPIO(55) // S6 +PB9 TIM4_CH4 TIM4 PWM(7) GPIO(57) NODMA // S7 +PB15 TIM12_CH2 TIM12 PWM(8) GPIO(58) NODMA // S8 + +PB14 TIM12_CH1 TIM12 PWM(9) GPIO(59) NODMA // S9 +PA5 TIM2_CH1 TIM2 PWM(10) GPIO(60) NODMA // S10 + +define STM32_PWM_USE_ADVANCED TRUE + +# Beeper +PC13 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# GPIOs +PB2 PINIO1 OUTPUT GPIO(81) LOW +PB8 PINIO2 OUTPUT GPIO(82) LOW +PC15 PINIO3 OUTPUT GPIO(83) LOW +PC0 PINIO4 OUTPUT GPIO(84) HIGH # BEC 12V enable + +# --------------------- SPI1 ----------------------- +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PB5 SPI1_MOSI SPI1 + +PC14 BMI088_A_CS CS +PA4 BMI088_G_CS CS + +# --------------------- SPI2 ----------------------- +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +PB12 OSD_CS CS +PC1 SDCARD_CS CS + +# -------------------- I2C bus -------------------- +I2C_ORDER I2C1 + +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +define HAL_I2C_INTERNAL_MASK 0 + +# --------------------- UARTs --------------------------- +SERIAL_ORDER OTG1 UART4 USART1 UART5 USART3 USART6 USART2 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 (RCIN with inverter) +# alternative using USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 ALT(1) + +# default to timer for RC input +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW + +# USART3 +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 + +# UART4 +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA + +# UART5, for GPS +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS +define HAL_SERIAL3_BAUD AP_SERIALMANAGER_GPS_BAUD + +# USART6 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 NODMA + +# ------------------- DMA assignment ------------------- +DMA_PRIORITY SPI1* UART2* TIM1* TIM8* TIM3* SPI2* ADC1 + +# ------------------- IMU BMI088 --------------------- +SPIDEV bmi088_g SPI1 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI1 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270 +#define HAL_DEFAULT_INS_FAST_SAMPLE 1 + + +# ------------------ OSD AT7456E ---------------------- +SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + + +# --------------------- SD & FLASH ---------------------- +SPIDEV sdcard SPI2 DEVID3 SDCARD_CS MODE3 104*MHZ 104*MHZ + +#define HAL_LOGGING_DATAFLASH_ENABLED 1 + +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# ----------------- I2C compass & Baro ----------------- +# 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 + +# built-in barometer +BARO BMP388 I2C:0:0x77 + +# --------------------- ADC --------------------------- +PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA7 BATT_CURRENT_SENS ADC1 SCALE(1) +PC5 RSSI_ADC_PIN ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 4 + +define HAL_BATT_VOLT_PIN 14 +define HAL_BATT_VOLT_SCALE 21.0 + +define HAL_BATT_CURR_PIN 7 +define HAL_BATT_CURR_SCALE 10.35 + +define BOARD_RSSI_ANA_PIN 15 +define HAL_DEFAULT_AIRSPEED_PIN 10 + +# -------reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 +define HAL_GYROFFT_ENABLED 0 + +# --------------------- save flash ---------------------- +# save some flash +include ../include/minimize_fpv_osd.inc +include ../include/no_bootloader_DFU.inc + +define HAL_PARACHUTE_ENABLED 1 +define HAL_SPRAYER_ENABLED 0 +define AP_GRIPPER_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 +define HAL_PICCOLO_CAN_ENABLE 0 \ No newline at end of file