Browse Source

hwdef: 增加zr-mrover板,拷贝Pixhawk4和Pixhawk6C

apm_2208-rover
Brown.Z 2 years ago
parent
commit
c076595b69
  1. 393
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/README.md
  2. 4
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/defaults.parm
  3. 4
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/hwdef-bl.dat
  4. 19
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/hwdef.dat
  5. BIN
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/pixhawk4-pinout.jpg
  6. 5
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/defaults.parm
  7. 72
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/hwdef-bl.dat
  8. 264
      libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/hwdef.dat

393
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/README.md

@ -0,0 +1,393 @@ @@ -0,0 +1,393 @@
# Pixhawk4 Flight Controller
The Pixhawk4 flight controller is sold by [Holybro](http://www.holybro.com/product/pixhawk-4)
## Features
- STM32F765 microcontroller
- Two IMUs: ICM20689 and BMI055
- MS5611 SPI barometer
- builtin I2C IST8310 magnetometer
- microSD card slot
- 6 UARTs plus USB
- 16 PWM outputs
- Four I2C and two CAN ports
- External Buzzer
- external safety Switch
- voltage monitoring for servo rail and Vcc
- two dedicated power input ports for external power bricks
## Pinout
![Pixhawk4 Board](pixhawk4-pinout.jpg "Pixhawk4")
## UART Mapping
- SERIAL0 -> USB
- SERIAL1 -> UART2 (Telem1)
- SERIAL2 -> UART3 (Telem2)
- SERIAL3 -> UART1 (GPS)
- SERIAL4 -> UART4 (GPS2, marked UART/I2CB)
- SERIAL5 -> UART6 (spare)
- SERIAL6 -> UART7 (spare, debug)
The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not
have RTS/CTS.
The UART7 connector is labelled debug, but is available as a general
purpose UART with ArduPilot.
### TELEM1, TELEM2 ports
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin </th>
<th>Signal </th>
<th>Volt </th>
</tr>
<tr>
<td>1 (red)</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>TX (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>RX (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>CTS</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5 (blk)</td>
<td>RTS</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
### GPS port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin </th>
<th>Signal </th>
<th>Volt </th>
</tr>
<tr>
<td>1 (red)</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>SERIAL3 TX (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>SERIAL3 RX (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>SCL</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>5 (blk)</td>
<td>SDA</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>6 (blk)</td>
<td>SafetyButton</td>
<td>+3.3V</td>
</tr>
<tr>
<td>7 (blk)</td>
<td>SafetyLED</td>
<td>+3.3V</td>
</tr>
<tr>
<td>8 (blk)</td>
<td>VDD 3.3 (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>9 (blk)</td>
<td>Buzzer</td>
<td>+3.3V</td>
</tr>
<tr>
<td>10 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
## 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 Pixhawk4 supports up to 16 PWM outputs. First first 8 outputs (labelled
"MAIN") are controlled by a dedicated STM32F100 IO controller. These 8
outputs support all PWM output formats, but not DShot.
The remaining 8 outputs (labelled AUX1 to AUX8) are the "auxiliary"
outputs. These are directly attached to the STM32F765 and support all
PWM protocols. The first 4 of the auxiliary PWM outputs support DShot.
The 8 main PWM outputs are in 3 groups:
- PWM 1 and 2 in group1
- PWM 3 and 4 in group2
- PWM 5, 6, 7 and 8 in group3
The 8 auxiliary PWM outputs are in 3 groups:
- PWM 1, 2, 3 and 4 in group1
- PWM 5 and 6 in group2
- PWM 7 and 8 in group3
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 6 pin
connectors. The correct battery setting parameters are dependent on
the type of power brick which is connected.
## Compass
The Pixhawk4 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 6 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:
- AUX1 50
- AUX2 51
- AUX3 52
- AUX4 53
- AUX5 54
- AUX6 55
## Analog inputs
The Pixhawk4 has 7 analog inputs
- ADC Pin0 -> Battery Voltage
- ADC Pin1 -> Battery Current Sensor
- ADC Pin2 -> Battery Voltage 2
- ADC Pin3 -> Battery Current Sensor 2
- ADC Pin4 -> ADC port pin 2
- ADC Pin14 -> ADC port pin 3
- ADC Pin10 -> ADC 5V Sense
- ADC Pin11 -> ADC 3.3V Sense
- ADC Pin103 -> RSSI voltage monitoring
## I2C Buses
- the internal I2C port is bus 0 in ArduPilot (I2C3 in hardware)
- the port labelled I2CA is bus 3 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)
### Pinout for I2CA
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1 (red)</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>SCL</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>SDA</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
### Pinout for I2CB+UART
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1 (red)</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>SERIAL4 TX (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>SERIAL4 RX (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>SCL</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>5 (blk)</td>
<td>SDA</td>
<td>+3.3 (pullups)</td>
</tr>
<tr>
<td>6 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
## CAN
The Pixhawk4 has two independent CAN buses, with the following pinouts.
### CAN1&2
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1 (red)</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>CAN_H</td>
<td>+12V</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>CAN_L</td>
<td>+12V</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
## Debug
The Pixhawk4 supports SWD debugging on the debug port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin </th>
<th>Signal </th>
<th>Volt </th>
</tr>
<tr>
<td>1 (red)</td>
<td>FMU VDD 3.3</td>
<td>+3.3V</td>
</tr>
<tr>
<td>2 (blk)</td>
<td>UART TX Debug (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3 (blk)</td>
<td>UART RX Debug (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4 (blk)</td>
<td>SWDIO</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5 (blk)</td>
<td>SWCLK</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6 (blk)</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
## 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.
## Acknowledgements
Thanks to
[PX4](https://docs.px4.io/en/flight_controller/pixhawk4.html) for
images used under the [CC-BY 4.0 license](https://creativecommons.org/licenses/by/4.0/)

4
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/defaults.parm

@ -0,0 +1,4 @@ @@ -0,0 +1,4 @@
# Pixhawk4 does not have hw flow control on radios
BRD_SER1_RTSCTS 0
BRD_SER2_RTSCTS 0

4
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/hwdef-bl.dat

@ -0,0 +1,4 @@ @@ -0,0 +1,4 @@
# hw definition file for processing by chibios_hwdef.py
# for Pixhawk4 bootloader
include ../fmuv5/hwdef-bl.dat

19
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/hwdef.dat

@ -0,0 +1,19 @@ @@ -0,0 +1,19 @@
# hw definition file for processing by chibios_hwdef.py
# for Holybro Pixhawk4 hardware.
include ../fmuv5/hwdef.dat
# red and blue LEDs swapped vs fmuv5
# red LED marked as B/E
undef PB1
PB1 LED_RED OUTPUT OPENDRAIN GPIO(92)
# blue LED marked as ACT
undef PC7
PC7 LED_BLUE OUTPUT GPIO(90) HIGH
# setup for supplied power brick
undef HAL_BATT_VOLT_SCALE
define HAL_BATT_VOLT_SCALE 18.182
undef HAL_BATT_CURR_SCALE
define HAL_BATT_CURR_SCALE 36.364

BIN
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v1/pixhawk4-pinout.jpg

Binary file not shown.

After

Width:  |  Height:  |  Size: 358 KiB

5
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/defaults.parm

@ -0,0 +1,5 @@ @@ -0,0 +1,5 @@
# setup correct defaults for battery monitoring for holybro power brick
BATT_MONITOR 4
BATT2_CURR_PIN 14
BATT2_VOLT_PIN 5

72
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/hwdef-bl.dat

@ -0,0 +1,72 @@ @@ -0,0 +1,72 @@
# hw definition file for processing by chibios_hwdef.py
# for the HolybroV6C hardware
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 16000000
# USB setup
USB_VENDOR 0x3162 # ONLY FOR USE BY Holybro
USB_PRODUCT 0x0053
USB_STRING_MANUFACTURER "Holybro"
# board ID for firmware load
APJ_BOARD_ID 56
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 128
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN
# pins for SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# CS pins
PC13 ICM42688_CS CS
PC14 BMI055_G_CS CS
PC15 BMI055_A_CS CS
PD4 FRAM_CS CS
# telem1
PE8 UART7_TX UART7
PE7 UART7_RX UART7
# telem2
PC12 UART5_TX UART5
PD2 UART5_RX UART5
# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# start peripheral power off
PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH
PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH
# LEDs
PD10 LED_ACTIVITY OUTPUT OPENDRAIN GPIO(90) HIGH # red
PD11 LED_BOOTLOADER OUTPUT OPENDRAIN GPIO(92) HIGH # blue
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

264
libraries/AP_HAL_ChibiOS/hwdef/zr-mrover_v2/hwdef.dat

@ -0,0 +1,264 @@ @@ -0,0 +1,264 @@
# hw definition file for processing by chibios_hwdef.py
# for the HolybroV6C hardware
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 16000000
# ChibiOS system timer
STM32_ST_USE_TIMER 2
# USB setup
USB_VENDOR 0x3162 # ONLY FOR USE BY AUSV
USB_PRODUCT 0x0053
USB_STRING_MANUFACTURER "AUSV"
# board ID for firmware load
APJ_BOARD_ID 56
FLASH_RESERVE_START_KB 128
# to be compatible with the px4 bootloader we need
# to use a different RAM_MAP
env USE_ALT_RAM_MAP 1
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -O2
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 USART3 OTG2
# default the 2nd interface to MAVLink2
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN
# pins for SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# telem1
PE8 UART7_TX UART7
PE7 UART7_RX UART7
PE9 UART7_RTS UART7
PE10 UART7_CTS UART7
# telem2
PC12 UART5_TX UART5
PD2 UART5_RX UART5
PC8 UART5_RTS UART5
PC9 UART5_CTS UART5
# GPS1
PB6 USART1_TX USART1
PA10 USART1_RX USART1
# GPS2
PE1 UART8_TX UART8
PE0 UART8_RX UART8
# uart2 telem3
PD5 USART2_TX USART2
PA3 USART2_RX USART2
# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# USART6 is for IOMCU
PC6 USART6_TX USART6
PC7 USART6_RX USART6
IOMCU_UART USART6
# ADC
PC5 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC4 BATT_CURRENT_SENS ADC1 SCALE(1)
PB1 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
PA2 BATT2_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 8
define HAL_BATT_CURR_PIN 4
define HAL_BATT_VOLT_SCALE 18.18
define HAL_BATT_CURR_SCALE 36.36
PA4 VDD_5V_SENS ADC1 SCALE(2)
# SPI1 - IMUs
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PC13 ICM42688_CS CS
PC14 BMI055_G_CS CS
PC15 BMI055_A_CS CS
PE4 BMI055_DRDY_A INPUT
PE5 BMI055_DRDY_G INPUT
PE6 ICM42688_DRDY INPUT
# SPI2 - FRAM
PD3 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
PD4 FRAM_CS CS
# PWM output pins
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50)
PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51)
PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52)
PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53)
PD14 TIM4_CH3 TIM4 PWM(5) GPIO(54)
PD15 TIM4_CH4 TIM4 PWM(6) GPIO(55)
PA0 TIM5_CH1 TIM5 PWM(7) GPIO(56)
PA1 TIM5_CH2 TIM5 PWM(8) GPIO(57)
# CAN bus
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PB5 CAN2_RX CAN2
PB13 CAN2_TX CAN2
# I2C buses
# I2C1, GPS+MAG
PB7 I2C1_SDA I2C1
PB8 I2C1_SCL I2C1
# I2C2, GPS2+MAG
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# I2C4 internal
PD12 I2C4_SCL I2C4
PD13 I2C4_SDA I2C4
# order of I2C buses
I2C_ORDER I2C4 I2C1 I2C2
define HAL_I2C_INTERNAL_MASK 1
# this board is tight on DMA channels. To allow for more UART DMA we
# disable DMA on I2C. This also prevents a problem with DMA on I2C
# interfering with IMUs
NODMA I2C*
define STM32_I2C_USE_DMA FALSE
# heater
PB9 HEATER_EN OUTPUT LOW GPIO(80)
define HAL_HEATER_GPIO_PIN 80
# Setup the IMU heater
define HAL_HAVE_IMU_HEATER 1
define HAL_IMU_TEMP_DEFAULT 45
define HAL_IMUHEAT_P_DEFAULT 50
define HAL_IMUHEAT_I_DEFAULT 0.07
# power enable pins
PB2 VDD_3V3_SENSORS1_EN OUTPUT HIGH
# start peripheral power off, then enable after init
# this prevents a problem with radios that use RTS for
# bootloader hold
PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH
PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH
# Control of Spektrum power pin
PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73)
define HAL_GPIO_SPEKTRUM_PWR 73
# Spektrum Power is Active High
define HAL_SPEKTRUM_PWR_ENABLED 1
# power sensing
PE3 VDD_5V_PERIPH_nOC INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
PA15 VDD_BRICK_nVALID INPUT PULLUP
PB12 VDD_BRICK2_nVALID INPUT PULLUP
# microSD support
PD6 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2
# LEDs
PD10 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH
PD11 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH
# setup for BoardLED2
define HAL_GPIO_A_LED_PIN 90
define HAL_GPIO_B_LED_PIN 92
define HAL_GPIO_LED_ON 0
# ID pins
PE12 HW_VER_REV_DRIVE OUTPUT LOW
# PC0 HW_REV_SENS ADC1 SCALE(1)
# PC1 HW_VER_SENS ADC1 SCALE(1)
# PWM output for buzzer
PB0 TIM3_CH3 TIM3 GPIO(77) ALARM
# barometers
BARO MS56XX I2C:0:0x76
BARO MS56XX I2C:0:0x77
BARO BMP388 I2C:0:0x77
# prototypes may have no baro
define HAL_BARO_ALLOW_INIT_NO_BARO 1
# compass
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
COMPASS IST8310 I2C:0:0x0C false ROTATION_NONE
# compensate for magnetic field generated by the heater on 6C IST8310
define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xc,0xa),Vector3f(17,14,0)}
# we need to stop the probe of an IST8310 as an internal compass with PITCH_180
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
# SPI devices
SPIDEV bmi055_g SPI1 DEVID1 BMI055_G_CS MODE3 10*MHZ 10*MHZ
SPIDEV bmi055_a SPI1 DEVID2 BMI055_A_CS MODE3 10*MHZ 10*MHZ
SPIDEV icm42688 SPI1 DEVID3 ICM42688_CS MODE3 2*MHZ 8*MHZ
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
# 2 IMUs
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90
IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_PITCH_180
define HAL_DEFAULT_INS_FAST_SAMPLE 3
# enable RAMTROM parameter storage
define HAL_STORAGE_SIZE 32768
define HAL_WITH_RAMTRON 1
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
Loading…
Cancel
Save