mirror of https://github.com/ArduPilot/ardupilot
hwdef: added SIYI NY flight controller
This commit is contained in:
parent
f7a9eb37b1
commit
9c43cde3d5
|
@ -0,0 +1,403 @@
|
|||
# SIYI N7 Flight Controller
|
||||
|
||||
The SIYI N7 flight controller is sold by a range of
|
||||
resellers, linked from https://siyi.biz
|
||||
|
||||
## Features
|
||||
|
||||
- STM32H743 microcontroller
|
||||
- ICM20689 and BMI088 IMUs
|
||||
- internal heater for IMU temperature control
|
||||
- internal vibration isolation for IMUs
|
||||
- MS5611 SPI barometer
|
||||
- builtin IST8310 compass
|
||||
- microSD card slot
|
||||
- 4 UARTs plus USB
|
||||
- 13 PWM outputs
|
||||
- I2C and CAN ports
|
||||
- RCIN port
|
||||
- external safety Switch
|
||||
- voltage monitoring for servo rail and Vcc
|
||||
- power input port for external power bricks
|
||||
|
||||
## Pinout
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART2 (Telem1)
|
||||
- SERIAL2 -> unused
|
||||
- SERIAL3 -> UART1 (GPS)
|
||||
- SERIAL4 -> UART4 (GPS2, Telem4/I2C)
|
||||
- SERIAL5 -> unused
|
||||
- SERIAL6 -> UART7 (debug port)
|
||||
- SERIAL7 -> USB2 (virtual port on same connector)
|
||||
|
||||
The Telem1 port has RTS/CTS pins, the other UARTs do not have RTS/CTS.
|
||||
|
||||
## Connectors
|
||||
|
||||
Unless noted otherwise all connectors are JST GH
|
||||
|
||||
### TELEM1 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>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>
|
||||
|
||||
|
||||
### GPS1 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>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>SCL I2C1</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>5 (blk)</td>
|
||||
<td>SDA I2C1</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>6 (blk)</td>
|
||||
<td>Button</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>7 (blk)</td>
|
||||
<td>button LED</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>8 (blk)</td>
|
||||
<td>3.3V</td>
|
||||
<td>3.3</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>9 (blk)</td>
|
||||
<td>buzzer</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td> (blk)</td>
|
||||
<td>GND</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
|
||||
|
||||
### GPS2, Telem4/I2C 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>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>SCL I2C2</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>5 (blk)</td>
|
||||
<td>SDA I2C2</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>6 (blk)</td>
|
||||
<td>GND</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
### I2C
|
||||
|
||||
<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>
|
||||
|
||||
|
||||
### CAN1
|
||||
|
||||
<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>
|
||||
|
||||
|
||||
### POWER1
|
||||
|
||||
<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 (red)</td>
|
||||
<td>VCC</td>
|
||||
<td>+5V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>3 (blk)</td>
|
||||
<td>CURRENT</td>
|
||||
<td>up to +3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>4 (blk)</td>
|
||||
<td>VOLTAGE</td>
|
||||
<td>up to +3.3V</td>
|
||||
</tr>
|
||||
<td>5 (blk)</td>
|
||||
<td>GND</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<td>6 (blk)</td>
|
||||
<td>GND</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
|
||||
### USB
|
||||
|
||||
<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>D_minus</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>3 (blk)</td>
|
||||
<td>D_plus</td>
|
||||
<td>+3.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>4 (blk)</td>
|
||||
<td>GND</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on the RCIN pin, at one end of the servo rail,
|
||||
marked RCIN in the above diagram. This pin supports all RC
|
||||
protocols.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The SIYI N7 supports up to 13 PWM outputs. First first 8 outputs
|
||||
(labelled "MAIN") are controlled by a dedicated STM32F103 IO
|
||||
controller. These 8 outputs support all PWM output formats, but not
|
||||
DShot.
|
||||
|
||||
The remaining 5 outputs (labelled AUX1 to AUX5) are the "auxiliary"
|
||||
outputs. These are directly attached to the STM32H743 and support all
|
||||
PWM protocols as well as DShot.
|
||||
|
||||
All 13 PWM outputs have GND on the top row, 5V on the middle row and
|
||||
signal on the bottom row.
|
||||
|
||||
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 4 auxiliary PWM outputs are in 2 groups:
|
||||
|
||||
- PWM 1, 2, 3 and 4 in group4
|
||||
- PWM 5 in group5
|
||||
|
||||
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 a dedicated power monitor ports on a 6 pin
|
||||
connector. The correct battery setting parameters are dependent on
|
||||
the type of power brick which is connected.
|
||||
|
||||
## Compass
|
||||
|
||||
The SIYI N7 has one builtin IST8310 compass.
|
||||
|
||||
## GPIOs
|
||||
|
||||
The 5 AUX PWM ports can be used as GPIOs (relays, buttons, RPM etc).
|
||||
|
||||
The numbering of the GPIOs for PIN variables in ArduPilot is:
|
||||
|
||||
- PWM1 50
|
||||
- PWM2 51
|
||||
- PWM3 52
|
||||
- PWM4 53
|
||||
- PWM5 54
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The SIYI N7 has 7 analog inputs
|
||||
|
||||
- ADC Pin16 -> Battery Voltage
|
||||
- ADC Pin17 -> Battery Current Sensor
|
||||
|
||||
## IMU Heater
|
||||
|
||||
The IMU heater in the SIYI N7 can be controlled with the
|
||||
BRD_HEAT_TARG parameter, which is in degrees C.
|
||||
|
||||
## 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.
|
|
@ -0,0 +1,46 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for H743 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1123
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
PB1 LED_RED OUTPUT LOW # red
|
||||
PC6 LED_ACTIVITY OUTPUT LOW # green
|
||||
PC7 LED_BOOTLOADER OUTPUT LOW # blue
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# pullup buzzer for no sound in bootloader
|
||||
PE5 BUZZER OUTPUT LOW PULLDOWN
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PF10 MS5611_CS CS
|
||||
PF2 ICM20689_CS CS
|
||||
PF4 BMI055_G_CS CS
|
||||
PG10 BMI055_A_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
|
@ -0,0 +1,242 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1123
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 EMPTY USART1 UART4 EMPTY UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# debug pins
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 - internal sensors
|
||||
PG11 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - FRAM
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI4 - sensors2
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# sensor CS
|
||||
PF10 MS5611_CS CS
|
||||
PF2 ICM20689_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PG10 BMI088_A_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
|
||||
# I2C buses
|
||||
|
||||
# I2C1 is on GPS port
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
# I2C on uart4 connector
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
|
||||
# I2C for onboard mag
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
# I2C4 is on external2
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C3 I2C1 I2C2 I2C4
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# enable pins
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# drdy pins
|
||||
PB4 DRDY_ICM20689 INPUT
|
||||
PB14 DRDY_BMI088_GYRO INPUT
|
||||
PB15 DRDY_BMI088_ACC INPUT
|
||||
|
||||
PD15 DRDY7_EXTERNAL INPUT
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART1 is GPS1
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
|
||||
# UART4 GPS2
|
||||
PD0 UART4_RX UART4 NODMA
|
||||
PD1 UART4_TX UART4 NODMA
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# UART8 is for IOMCU
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# UART for IOMCU
|
||||
IOMCU_UART UART8
|
||||
|
||||
# PWM AUX channels
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
||||
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||
|
||||
# PWM output for buzzer
|
||||
PE5 TIM15_CH1 TIM15 GPIO(77) ALARM
|
||||
|
||||
# analog in
|
||||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PC0 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
# voltage divider 1/(16.9/(33+16.9))
|
||||
define HAL_IOMCU_VSERVO_SCALAR 1 / (16.9 / (33 + 16.9))
|
||||
|
||||
# CAN bus
|
||||
PI9 CAN1_RX CAN1
|
||||
PH13 CAN1_TX CAN1
|
||||
|
||||
PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
|
||||
# GPIOs
|
||||
PA7 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
|
||||
define HAL_HAVE_IMU_HEATER 1
|
||||
define HAL_IMU_TEMP_DEFAULT 45
|
||||
|
||||
PH5 AUX_CS CS
|
||||
|
||||
PG1 VDD_BRICK_nVALID INPUT PULLUP
|
||||
PG2 VDD_BRICK2_nVALID INPUT PULLUP
|
||||
PA9 VBUS INPUT
|
||||
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
||||
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
|
||||
PB10 nSPI5_RESET_EXTERNAL OUTPUT HIGH
|
||||
|
||||
# SPI devices
|
||||
SPIDEV ms5611 SPI4 DEVID1 MS5611_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV bmi088_g SPI1 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_a SPI1 DEVID4 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# Two IMUs
|
||||
IMU Invensense SPI:icm20689 ROTATION_NONE
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# red LED
|
||||
PB1 LED_RED OUTPUT GPIO(90)
|
||||
|
||||
# green LED
|
||||
PC6 LED_GREEN OUTPUT GPIO(91) LOW
|
||||
|
||||
# blue LED
|
||||
PC7 LED_BLUE OUTPUT GPIO(92) HIGH
|
||||
|
||||
# setup for 2 LEDs
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 92
|
||||
define HAL_GPIO_LED_ON 0
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# safety switch pin
|
||||
PE10 LED_SAFETY OUTPUT
|
||||
PE12 SAFETY_IN INPUT PULLDOWN
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
|
||||
# one baro
|
||||
BARO MS56XX SPI:ms5611
|
||||
|
||||
# one builtin compass, plus one on the default GPS that is external with
|
||||
# a non-default orientation
|
||||
COMPASS IST8310 I2C:0:0x0e false ROTATION_PITCH_180_YAW_270
|
||||
|
||||
define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_PITCH_180_YAW_270
|
||||
|
||||
# compensate for magnetic field generated by the heater on the internal IST8310
|
||||
define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xe,0x0a),Vector3f(15,35,-6)}
|
||||
|
||||
# also probe for external compasses
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
# don't share IOMCU DMA
|
||||
DMA_NOSHARE UART8* SPI1* TIM*UP*
|
||||
|
||||
DMA_PRIORITY UART8* ADC* SPI1*
|
||||
|
||||
# battery setup
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 16
|
||||
define HAL_BATT_CURR_PIN 17
|
||||
define HAL_BATT_VOLT_SCALE 18.182
|
||||
define HAL_BATT_CURR_SCALE 36.364
|
||||
|
||||
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…
Reference in New Issue