diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md index 8d0ed4a6d42a6..e6a704a67342c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md @@ -8,14 +8,14 @@ The SkySakura H743 is a flight controller produced by [SkySakuraRC] - Gyro1: ICM42688 - Gyro2: IIM42652 - SD Card support - - BEC output: 5V 5A & 12V 5A (MAX 60W total) + - BEC output: 5V 5A & 12V 5A (MAX 60W total) (switchable 12V) - Barometer1: DPS310 - Barometer2: ICP20100 - Magnometer: IST8310 - CAN bus support - 7 UARTS: (USART1, USART2, USART3, UART4, USART6, UART7 with flow control, UART8) - 2 I2C, I2C1 is used internally. - - 13 PWM outputs (12 motor outputs, and 1 led) + - 13 PWM outputs (12 motor outputs, 1 led) - 4-12s wide voltage support ## Pinout @@ -34,25 +34,31 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn. |SERIAL3|TX2/RX2|UART2 (USER)| |SERIAL4|TX3/RX3|UART3 (GPS1, DMA-enabled)| |SERIAL5|TX4/RX4|UART4 (RCIN, DMA-enabled)| -|SERIAL6|TX6/RX6|UART6 (VTX, DMA-enabled)| -|SERIAL7|TX8/RX8|UART8 (ESC-Telemetry)| +|SERIAL6|TX6/RX6|UART6 (DisplayPort, DMA-enabled)| +|SERIAL7|TX8/RX8|UART8 (ESC-Telemetry, RX8 on ESC connectors, TX8 can be used if protocol is change from ESC telem)| +|SERIAL8|COMPUTER|USB| ## Safety Button + SkySakura H743 supports safety button, with connection to sh1.0 6 pin connector, with buzzer and safety led on the same connector. -Safety button is default to be disabled and can be enabled by setting the following parameter: +Safety button is defaulted to be disabled but can be enabled by setting the following parameter: - BRD_SAFETY_DEFLT 1 ## RC Input -RC input is configured on the on UART4 with sh1.0 connector. It supports all serial RC protocols. DJI sbus needs solder connection for the solder pad and are connected to UART4, inversion for UART4 needs to be configured. +RC input is configured on UART4 with an sh1.0 connector. It supports all RC protocols except PPM. The SBUS pin on the HD VTX connector is tied directly the UART4 RX. If ELRS is used on UART4, then the SBUS lead from a DJI VTX must not be connected to the SBUS to prevent ELRS lock up on boot. ## OSD Support -SkySakura H743 only supports HD OSD through uart connection. However, external spi is provided and an external AT7456E can be connected to enable analog OSD. +SkySakura H743 supports HD OSD through UART6 by default. + +## VTX Power Control + +The 12VSW output voltage on the HD VTX connector is controlled by GPIO 85, via RELAY1 by default. Low activates the voltage. ## PWM Output -The SkySakura H743 has 13 PWM outputs. M1-M8 are linked to sh1.0 8 pin connectors. All 8 outputs support bi-directional DShot and DShot. Output 9-13 support normal Dshot and 13 is configured as LED. +The SkySakura H743 has 13 PWM outputs. M1-M8 are linked to sh1.0 8 pin connectors. The first 8 outputs support bi-directional DShot and DShot. Output 9-13 only support non-DShot protocols and 13 is configured as NEOPIXEL LED by default. The PWM are in in two groups: @@ -69,31 +75,35 @@ to use DShot. ## Battery Monitoring -The board has a builtin voltage sensor. The voltage sensor can handle up to 12S LiPo batteries. Current sensor and BATT2 moniter is present. -BATT2 voltage input is 6.6V capable, voltage divider resistor is 10k/10k so maximum input on batt2 pad is 13.2V. -ADC3 pad is BATT2 current input, ADC4 pad is BATT2 voltage input. +The board has a builtin voltage sensor and external current monitor inputs. The voltage sensor can handle up to 12S LiPo batteries. The current sensor scale's default range is 120A, but will need to be adjusted according to which sensor is used. These inputs are present on the first ESC connector. +A second battery monitor can be also used. Its voltage sensor is capable of reading up to 6.6V maximum and is available on the A3 solder pad. Its current monitor input is on the A4 solder pad. -The correct battery setting parameters are: +The default battery setting parameters are: - BATT_MONITOR 4 - BATT_VOLT_PIN 10 - BATT_VOLT_MULT 34 - BATT_CURR_PIN 11 - - BATT2_MONITOR 4 + - set BATT2_MONITOR 4 - BATT2_VOLT_PIN 12 - BATT2_CURR_PIN 13 - BATT2_VOLT_MULT 10 - -These are set by default in the firmware and shouldn't need to be adjusted + - set BATT2_AMP_PERVLT to appropriate value for second current sensor ## Compass -The SkySakura H743 have a builtin IST8310 compass. +The SkySakura H743 have a builtin IST8310 compass. Due to motor interference, users often disable this compass and use an external compass attached via the external SDA/SCL pins. ## NeoPixel LED PWM13 provides external NeoPixel LED support. + +## Firmware + +Firmware can bee found on the `firmware server < https://firmware.ardupilot.org`__ in the "SkySakuraH743" folders + + ## Loading Firmware Initial firmware load can be done with DFU by plugging in USB with the @@ -102,4 +112,4 @@ 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. +\*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743-bottom.png b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743-bottom.png new file mode 100644 index 0000000000000..e516cbdf9dab8 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743-bottom.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743.png b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743_top.png similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743.png rename to libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743_top.png diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm index acb9701c258e2..7200b83a92dda 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm @@ -1,23 +1,2 @@ -# SERIAL1 is MAVLink2 by default -SERIAL1_PROTOCOL 2 -SERIAL1_BAUD 57 -# SERIAL2 is MAVLink2 by default -SERIAL2_PROTOCOL 2 -SERIAL2_BAUD 57 -# SERIAL4 is GPS by default -SERIAL4_PROTOCOL 5 -SERIAL4_BAUD 230 -# SERIAL5 is ESC-telemetry by default -SERIAL5_PROTOCOL 23 -SERIAL5_BAUD 115 -# SERIAL6 is VTX-DisplayPort by default -SERIAL6_PROTOCOL 42 -SERIAL6_BAUD 115 -# SERIAL7 is ESC-telemetry by default -SERIAL7_PROTOCOL 16 -SERIAL7_BAUD 115 -# Disable safety button by default -BRD_SAFETY_DEFLT 0 -# Default FRAME -FRAME_CLASS 1 -FRAME_TYPE 12 \ No newline at end of file +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat index d1ef66c794899..0c6bc0d525d7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat @@ -50,3 +50,28 @@ PA4 IMU1_CS CS PE11 IMU2_CS CS PC5 BARO2_CS CS PB12 EXT_CS CS + + +# enable DFU by default +ENABLE_DFU_BOOT 1 + +# enable flashing from SD card: +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat index 9650e6e00964d..4e56a5673c956 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat @@ -48,6 +48,8 @@ PA14 JTCK-SWCLK SWD define HAL_HAVE_SAFETY_SWITCH 1 PD10 LED_SAFETY OUTPUT LOW PD11 SAFETY_IN INPUT PULLDOWN +#disable safety button by default +define BOARD_SAFETY_ENABLE_DEFAULT 0 # SPI1 for IMU1 (IIM42652) PA5 SPI1_SCK SPI1 @@ -111,13 +113,14 @@ define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 81 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART4 USART6 UART8 OTG2 -# USART1 (SPARE) +# USART1 (TELEM2) PA10 USART1_RX USART1 PA9 USART1_TX USART1 -# USART2 (SPARE) +# USART2 (USER) PD5 USART2_TX USART2 NODMA PD6 USART2_RX USART2 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None # USART3 (GPS1) PD9 USART3_RX USART3 @@ -126,10 +129,12 @@ PD8 USART3_TX USART3 # UART4 (RCIN) PB9 UART4_TX UART4 PB8 UART4_RX UART4 +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_RCIN -# USART6 (VTX) +# USART6 (DisplayPort) PC7 USART6_RX USART6 PC6 USART6_TX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_MSP_DisplayPort # UART7 (telem1) PE7 UART7_RX UART7 NODMA @@ -140,6 +145,8 @@ PE9 UART7_RTS UART7 # UART8 (ESC Telemetry) PE0 UART8_RX UART8 NODMA PE1 UART8_TX UART8 NODMA +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry + # CAN bus PD0 CAN1_RX CAN1 @@ -176,7 +183,8 @@ PC12 SDMMC1_CK SDMMC1 PD2 SDMMC1_CMD SDMMC1 # GPIOs -PE15 PINIO1 OUTPUT GPIO(85) LOW +PE15 VTX_PWR OUTPUT LOW GPIO(85) +define RELAY1_PIN_DEFAULT 85 define HAL_STORAGE_SIZE 32768 @@ -213,4 +221,9 @@ BARO DPS310 SPI:dps310 define HAL_OS_FATFS_IO 1 define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN -define HAL_FRAME_TYPE_DEFAULT 12 \ No newline at end of file +define HAL_FRAME_TYPE_DEFAULT 12 + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 \ No newline at end of file