mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: added RadiolinkPIX6 support
This commit is contained in:
parent
0e10db2510
commit
ddd2f2d732
Binary file not shown.
After Width: | Height: | Size: 2.5 MiB |
|
@ -0,0 +1,296 @@
|
|||
# RadiolinkPIX6 Flight Controller
|
||||
|
||||
![RadiolinkPIX6](http://www.radiolink.com.cn/firmware/wiki/RadiolinkPIX6/RadiolinkPIX6.png)
|
||||
|
||||
Featuring STM32F7 cpu, vibration isolation of IMUs, redundant IMUs, integrated OSD chip, IMU heating, and DShot.
|
||||
|
||||
## Specifications
|
||||
|
||||
- Processor
|
||||
- 32-bit ARM Cortex M7 core with DPFPU - STM32F765VIT6
|
||||
- 216 MHz/512 KB RAM/2 MB Flash
|
||||
- 32-bit IOMCU co-processor - STM32F100
|
||||
- 32KB FRAM - FM25V02A
|
||||
- AT7456E OSD
|
||||
- Sensors
|
||||
- Bosh BMI088 IMU (accel, gyro)
|
||||
- InvenSense ICM-42688 IMU (accel, gyro)
|
||||
- SPL06 barometer
|
||||
- IST8310 magnetometer
|
||||
- Power
|
||||
- SMBUS/I2C Power Module Inputs(I2C)
|
||||
- voltage and current monitor inputs(Analog)
|
||||
- Interfaces
|
||||
- 16 PWM Outputs with independent power rail for external power source
|
||||
- 5x UART serial ports, 2 with HW flow control
|
||||
- Camera Input and Video Output
|
||||
- PPM/SBUS input, DSM/SBUS input
|
||||
- RSSI (PWM or voltage) input
|
||||
- I2C, SPI, 2x CAN, USB
|
||||
- 3.3V and 6.6V ADC inputs
|
||||
- Buzzer and Safety Switch
|
||||
- microSD card
|
||||
- Dimensions
|
||||
- Weight 80g
|
||||
- Size 94mm x 51.5mm x 14.5mm
|
||||
|
||||
## Connector assignments
|
||||
|
||||
### Top View
|
||||
|
||||
<img src="http://www.radiolink.com.cn/firmware/wiki/RadiolinkPIX6/Top_View.png" alt="Top_View" style="zoom: 50%;" />
|
||||
|
||||
### Left View
|
||||
|
||||
<img src="http://www.radiolink.com.cn/firmware/wiki/RadiolinkPIX6/Left_View.png" alt="Right_View" style="zoom: 67%;" />
|
||||
|
||||
### Right View
|
||||
|
||||
<img src="http://www.radiolink.com.cn/firmware/wiki/RadiolinkPIX6/Right_View.png" alt="Left_View" style="zoom: 67%;" />
|
||||
|
||||
### Rear View
|
||||
|
||||
<img src="http://www.radiolink.com.cn/firmware/wiki/RadiolinkPIX6/Rear_View.png" alt="Rear" style="zoom: 50%;" />
|
||||
|
||||
## Pinouts
|
||||
|
||||
### TELEM1, TELEM2 ports
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| ---- | ------- | ----- |
|
||||
| <span style="display:inline-block;width:30px"> 1 </span> | <span style="display:inline-block;width:120px"> VCC </span> | <span style="display:inline-block;width:600px"> +5V </span> |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | CTS | +3.3V |
|
||||
| 5 | RTS | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### OSD
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | GND | GND |
|
||||
| 2 | VOUT | +3.3V |
|
||||
| 3 | VCC | +5V |
|
||||
| 4 | GND | GND |
|
||||
| 5 | VCC | +5V |
|
||||
| 6 | VIN | +3.3V |
|
||||
|
||||
### I2C port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SCL | +3.3V (pullups) |
|
||||
| 3 | SDA | +3.3V (pullups) |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### CAN1, CAN2 ports
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | CAN_H | +12V |
|
||||
| 3 | CAN_L | +12V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### GPS1 port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | SCL | +3.3V |
|
||||
| 5 | SDA | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### GPS2 Port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | SCL | +3.3V |
|
||||
| 5 | SDA | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### SPI
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SPI_SCK | +3.3V |
|
||||
| 3 | SPI_MISO | +3.3V |
|
||||
| 4 | SPI_MOSI | +3.3V |
|
||||
| 5 | !SPI_NSS1 | +3.3V |
|
||||
| 6 | !SPI_NSS2 | +3.3V |
|
||||
| 7 | DRDY | +3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
### POWER1
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | VCC | +5V |
|
||||
| 3 | CURRENT | up to +3.3V |
|
||||
| 4 | VOLTAGE | up to +3.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### POWER2
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | VCC | +5V |
|
||||
| 3 | SCL | +3.3V |
|
||||
| 4 | SDA | +3.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### ADC 3.3V
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | ADC IN1 | up to +3.3V |
|
||||
| 3 | GND | GND |
|
||||
| 4 | ADC IN2 | up to +3.3v |
|
||||
| 5 | GND | GND |
|
||||
|
||||
### ADC 6.6V
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | ADC IN | up to 6.6V |
|
||||
| 3 | GND | GND |
|
||||
|
||||
### USB remote port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | USB VDD | +5V |
|
||||
| 2 | DM | +3.3V |
|
||||
| 3 | DP | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### SWITCH
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +3.3V |
|
||||
| 2 | !IO_LED_SAFETY | GND |
|
||||
| 3 | SAFETY | GND |
|
||||
|
||||
### Buzzer port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | BUZZER- | +5V |
|
||||
|
||||
### Spektrum/DSM Port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +3.3V |
|
||||
| 2 | GND | GND |
|
||||
| 3 | Signal | +3.3V |
|
||||
|
||||
### Debug port
|
||||
|
||||
| <span style="display:inline-block;width:30px"> Pin </span> | <span style="display:inline-block;width:120px"> Signal </span> | <span style="display:inline-block;width:600px"> Volt </span> |
|
||||
| ---------------------------------------------------------- | ------------------------------------------------------------ | ------------------------------------------------------------ |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | FMU_SWCLK | +3.3V |
|
||||
| 3 | FMU_SWDIO | +3.3V |
|
||||
| 4 | TX(UART7) | +3.3V |
|
||||
| 5 | RX(UART7) | +3.3V |
|
||||
| 6 | IO_SWCLK | +3.3V |
|
||||
| 7 | IO_SWDIO | +3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> USART2 (Telem1) RTS/CTS pins, RX DMA capable
|
||||
- SERIAL2 -> USART3 (Telem2) RTS/CTS pins, TX/RX DMA capable
|
||||
- SERIAL3 -> USART1 (GPS1), TX/RX DMA capable
|
||||
- SERIAL4 -> UART4 (GPS2), No DMA
|
||||
- SERIAL5 -> UART7 (User), No DMA
|
||||
|
||||
## RC Input
|
||||
|
||||
The RCIN pin, which by default is mapped to a timer input, can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, will only provide RC without telemetry.
|
||||
|
||||
To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART, such as SERIAL1 (USART2) would need to be used for receiver connections. Below are setups using Serial6.
|
||||
|
||||
- [SERIAL1_PROTOCOL](https://ardupilot.org/copter/docs/parameters.html#serial1-protocol) should be set to “23”.
|
||||
- FPort would require [SERIAL1_OPTIONS](https://ardupilot.org/copter/docs/parameters.html#serial1-options) be set to “15”.
|
||||
- CRSF would require [SERIAL1_OPTIONS](https://ardupilot.org/copter/docs/parameters.html#serial1-options) be set to “0”.
|
||||
- SRXL2 would require [SERIAL1_OPTIONS](https://ardupilot.org/copter/docs/parameters.html#serial1-options) be set to “4” and connects only the TX pin.
|
||||
|
||||
Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See [Radio Control Systems](https://ardupilot.org/copter/docs/common-rc-systems.html#common-rc-systems) for details.
|
||||
|
||||
## OSD Support
|
||||
|
||||
The RadiolinkPIX6 support using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such as DJI or DisplayPort is supported using UART3 or any other free UART. See [MSP OSD](https://ardupilot.org/copter/docs/common-msp-osd-overview-4.2.html#common-msp-osd-overview-4-2) for more info.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The RadiolinkPIX6 supports up to 16 PWM outputs. All 16 outputs support all normal PWM output formats. All FMU outputs also support DShot.
|
||||
|
||||
The 8 FMU PWM outputs are in 4 groups:
|
||||
|
||||
- Outputs 1, 2, 3 and 4 in group1
|
||||
- Outputs 5 and 8 in group2
|
||||
- Outputs 6 and 7 in group3
|
||||
|
||||
FMU outputs within the same group need to use the same output rate and protocol. If any output in a group uses DShot then all channels in that group need to use DShot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has 2 dedicated power monitor ports with a 6 pin connector. One is the Analog power monitor(Power1), and the others is the I2C power monitor(Power2).
|
||||
|
||||
### Power1 port(Analog)
|
||||
|
||||
The parameters should be set:
|
||||
|
||||
[BATT_MONITOR](https://ardupilot.org/copter/docs/parameters.html#batt-monitor) =4
|
||||
|
||||
[BATT_VOLT_PIN](https://ardupilot.org/copter/docs/parameters.html#batt-volt-pin) 2
|
||||
|
||||
[BATT_CURR_PIN](https://ardupilot.org/copter/docs/parameters.html#batt-curr-pin) 5
|
||||
|
||||
[BATT_VOLT_MULT](https://ardupilot.org/copter/docs/parameters.html#batt-volt-mult) 18
|
||||
|
||||
[BATT_AMP_PERVLT](https://ardupilot.org/copter/docs/parameters.html#batt-amp-pervlt) 24
|
||||
|
||||
### Power2 port(I2C)
|
||||
|
||||
The parameters should be set.:
|
||||
|
||||
- [BATT_MONITOR](https://ardupilot.org/copter/docs/parameters.html#batt-monitor) = 21
|
||||
- [BATT_I2C_BUS](https://ardupilot.org/copter/docs/parameters.html#batt-i2c-bus-ap-battmonitor-ina2xx) = 1
|
||||
- [BATT_I2C_ADDR](https://ardupilot.org/copter/docs/parameters.html#batt-i2c-addr-ap-battmonitor-ina2xx) = 65
|
||||
|
||||
## Compass
|
||||
|
||||
The RadiolinkPIX6 has a built-in compass. Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination.
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The RadiolinkPIX6 has 3 analog inputs, one 6V tolerant and two 3.3V tolerant
|
||||
|
||||
- ADC Pin12 -> ADC 6.6V Sense
|
||||
- ADC Pin4 -> ADC IN1 3.3V Sense
|
||||
- ADC Pin13 -> ADC IN2 3.3V Sense
|
||||
- Analog 3.3V RSSI input pin = 103
|
||||
|
||||
## Connectors
|
||||
|
||||
Unless noted otherwise all connectors are JST GH
|
|
@ -0,0 +1,42 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for F765 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1410
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
PC13 LED_BOOTLOADER OUTPUT HIGH
|
||||
PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
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
|
|
@ -0,0 +1,240 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for the RadiolinkPIX6 hardware
|
||||
|
||||
# MCU class and specific type.
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1410
|
||||
|
||||
FLASH_RESERVE_START_KB 32
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 - internal sensors
|
||||
PB3 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - FRAM
|
||||
PA9 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
# SPI4 - sensors2
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# sensor CS
|
||||
PB12 BMI088_A_CS CS
|
||||
PB4 ICM42688_CS CS SPEED_VERYLOW
|
||||
PD10 FRAM_CS CS SPEED_VERYLOW
|
||||
PA8 AT7456_CS CS
|
||||
PE12 BMI088_G_CS CS
|
||||
PC14 EXTERNAL1_CS1 CS
|
||||
PC15 EXTERNAL1_CS2 CS
|
||||
|
||||
# I2C buses
|
||||
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# enable pins
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
PD13 nVDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
PC4 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
# drdy pins
|
||||
PD15 DRDY7_EXTERNAL1 INPUT
|
||||
|
||||
# Control of Spektrum power pin
|
||||
PE4 SPEKTRUM_PWR OUTPUT HIGH GPIO(73)
|
||||
define HAL_GPIO_SPEKTRUM_PWR 73
|
||||
|
||||
# Spektrum Power is Active High
|
||||
define HAL_SPEKTRUM_PWR_ENABLED 1
|
||||
|
||||
# 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
|
||||
PB6 USART1_TX USART1
|
||||
|
||||
# USART3 is telem2
|
||||
PD9 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
PD11 USART3_CTS USART3
|
||||
PD12 USART3_RTS USART3
|
||||
|
||||
# UART4 GPS2
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
|
||||
# UART7 is debug
|
||||
PE7 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)
|
||||
PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54)
|
||||
PA7 TIM3_CH2 TIM3 PWM(6) GPIO(55)
|
||||
PC6 TIM3_CH1 TIM3 PWM(7) GPIO(56)
|
||||
PA3 TIM2_CH4 TIM2 PWM(8) GPIO(57)
|
||||
|
||||
# PWM output for buzzer
|
||||
PE5 TIM9_CH1 TIM9 GPIO(77) ALARM
|
||||
|
||||
# analog in
|
||||
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA5 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PC3 SPARE1_ADC1 ADC1 SCALE(1)
|
||||
PA4 SPARE2_ADC1 ADC1 SCALE(1)
|
||||
|
||||
PC0 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC2 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
# setup scaling defaults for PixHackV5 power brick
|
||||
define HAL_BATT_VOLT_SCALE 18.0
|
||||
define HAL_BATT_CURR_SCALE 24.0
|
||||
define HAL_BATT_VOLT_PIN 0
|
||||
define HAL_BATT_CURR_PIN 1
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
PB5 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
# GPIOs
|
||||
PC5 VDD_BRICK_nVALID INPUT PULLUP
|
||||
PB1 VDD_BRICK2_nVALID INPUT PULLUP
|
||||
PB2 VBUS_nVALID INPUT PULLUP
|
||||
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
||||
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
|
||||
|
||||
|
||||
# SPI devices
|
||||
SPIDEV bmi088_a SPI1 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_g SPI1 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV imu2 SPI1 DEVID3 ICM42688_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV osd SPI2 DEVID2 AT7456_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# up to 2 IMUs
|
||||
IMU Invensensev3 SPI:imu2 ROTATION_YAW_90
|
||||
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# probe external I2C compasses plus some internal IST8310
|
||||
# we also probe some external IST8310 with a non-standard orientation
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# we need to stop the probe of an IST8310 as an internal compass with PITCH_180
|
||||
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
|
||||
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180
|
||||
|
||||
# one baro
|
||||
BARO SPL06 I2C:0:0x76
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC_D0 SDMMC1
|
||||
PC9 SDMMC_D1 SDMMC1
|
||||
PC10 SDMMC_D2 SDMMC1
|
||||
PC11 SDMMC_D3 SDMMC1
|
||||
PC12 SDMMC_CK SDMMC1
|
||||
PD2 SDMMC_CMD SDMMC1
|
||||
|
||||
# red LED marked as B/E
|
||||
PD14 LED_RED OUTPUT GPIO(90)
|
||||
|
||||
# green LED marked as PWR. We leave this solid on, but allow
|
||||
# for it to be controlled as a relay if needed
|
||||
PC1 LED_GREEN OUTPUT GPIO(91)
|
||||
|
||||
# blue LED marked as ACT
|
||||
PC7 LED_BLUE OUTPUT GPIO(92)
|
||||
|
||||
# setup for "pixracer" RGB LEDs
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 91
|
||||
define HAL_GPIO_C_LED_PIN 92
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# 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
|
||||
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
DMA_PRIORITY SDMMC* UART8* ADC* USART3_RX TIM1_UP USART2_RX USART1_RX TIM1_CH3 SPI4* SPI1_RX SPI2* TIM1_CH1 SPI1_TX 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
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
Loading…
Reference in New Issue