AP_HAL_ChibiOS: added PixPilot-V6

This commit is contained in:
xiao 2022-11-21 19:12:27 +11:00 committed by Randy Mackay
parent 12b6fa0948
commit 7cdb15d2a7
5 changed files with 674 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

View File

@ -0,0 +1,367 @@
## PixPilot-V6 Flight Controller
The PixPilot-V6 flight controller is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com)
## Features
• STM32H743VIT6 and STM32F103C8T6 microcontroller
• Three IMUs, two ICM42688-P(SPI), one ICM40605(SPI)
• internal heater for IMUs temperature control
• internal Soft Rubber Damping Ball isolation for All interna IMUs
• Two barometers, MS5611(SPI)
• builtin IST8310 magnetometer(internal I2C)
• builtin RAMTRON(SPI)
• microSD card slot
• 5 UARTs
• USB(Type-C)
• PPM & S.Bus input
• 14 PWM outputs
• tow I2C ports and two FDCAN ports
• one S.Bus output
• External Buzzer
• builtin RGB LED
• two voltage & current monitoring
• servo rail BEC independent power input for servos
• external safety Switch
## Pinout
![PixPilot-V6](PixPilot-V6.png "PixPilot-V6")
![PixPilot-V6](PixPilot-V6_2.png "PixPilot-V6_2")
UART Mapping
============
- SERIAL0 -> console (primary mavlink, usually USB)
- SERIAL1 -> USART2 (telem1)
- SERIAL2 -> USART3 (Telem2)
- SERIAL3 -> UART4 (GPS1)
- SERIAL4 -> UART8 (GPS2)
- SERIAL5 -> UART7 (USER)
Connector pin assignments
=========================
TELEM1, TELEM2 ports
--------------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>TX (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</td>
<td>RX (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
I2C1, I2C2 ports
---------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>PIN</th>
<th>SIGNAL</th>
<th>VOLT</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>SCL</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</td>
<td>SDA</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
CAN1, CAN2 ports
---------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>PIN</th>
<th>SIGNAL</th>
<th>VOLT</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>CAN_H</td>
<td>+12V</td>
</tr>
<tr>
<td>3</td>
<td>CAN_L</td>
<td>+12V</td>
</tr>
<tr>
<td>4</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
Safety and buzzer port
-----------
<table border="1" class="docutils">
<tbody>
<tr>
<th>PIN</th>
<th>SIGNAL</th>
<th>VOLT</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>LED</td>
<td>+5V</td>
</tr>
<tr>
<td>3</td>
<td>SAFKEY</td>
<td>+5V</td>
</tr>
<tr>
<td>4</td>
<td>BUZZER</td>
<td>+5V</td>
</tr>
<tr>
<td>5</td>
<td>3V+</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
GPS1/I2C1, GPS2/I2C2 ports
--------------------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>PIN</th>
<th>SIGNAL</th>
<th>VOLT</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>TX</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</td>
<td>RX</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>SCL</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>SDA</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
Serial5 port
--------------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>TX (OUT)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</td>
<td>RX (IN)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
Power1, Power2 ports
--------------------
<table border="1" class="docutils">
<tbody>
<tr>
<th>PIN</th>
<th>SIGNAL</th>
<th>VOLT</th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>VCC</td>
<td>+5V</td>
</tr>
<tr>
<td>3</td>
<td>CURRENT</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>VOLTAGE</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>6</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
RC Input
--------
All compatible RC protocols can be decoded by attaching the Receiver's output to the SBUS input pin next to the Servo/Output VCC input connector. Note that some protocols such as CRSF or FPort including telemetry, require connection to, and setup of, one of the UARTs instead of this pin.
Battery Monitor Settings
========================
These should already be set by default. However, if lost or changed:
Enable Battery monitor with these parameter settings :
:ref:`BATT_MONITOR<BATT_MONITOR>` =4
Then reboot.
:ref:`BATT_VOLT_PIN<BATT_VOLT_PIN>` 14
:ref:`BATT_CURR_PIN<BATT_CURR_PIN>` 15
:ref:`BATT_VOLT_MULT<BATT_VOLT_MULT>` 18.0
:ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT>` 24.0
:ref:`BATT2_VOLT_PIN<BATT2_VOLT_PIN>` 13
:ref:`BATT2_CURR_PIN<BATT2_CURR_PIN>` 4
:ref:`BATT2_VOLT_MULT<BATT2_VOLT_MULT>` 18.0
:ref:`BATT2_AMP_PERVLT<BATT2_AMP_PERVLT>` 24.0
DroneCAN capability
===================
There are 2 CAN ports which allow connecting two independant CAN bus outputs. Each of these can have multiple CAN peripheral devices connected.
Where to Buy
============
`makeflyeasy <http://www.makeflyeasy.com>`_
[copywiki destination="plane,copter,rover,blimp"]

View File

@ -0,0 +1,60 @@
# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1083
FLASH_SIZE_KB 2048
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 128
env OPTIMIZE -Os
PB3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red
PE12 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue
define HAL_LED_ON 0
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART2 USART3 UART7
# telem1
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# Add CS pins to ensure they are high in bootloader
PC2 42688_EXT_CS CS
PD7 BARO_EXT_CS CS
PC13 40605_EXT_CS CS
PE4 42688_CS CS
PC14 BARO_CS CS
PD10 FRAM_CS CS
PD2 SDCARD_CS CS
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 32768

View File

@ -0,0 +1,247 @@
# hw definition file for processing by chibios_hwdef.py
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1083
FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed
env OPTIMIZE -O2
FLASH_RESERVE_START_KB 128
define HAL_STORAGE_SIZE 32768
# order of I2C buses
I2C_ORDER I2C3 I2C2 I2C1
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
#DEFAULTGPIO OUTPUT LOW PULLDOWN
# USB.
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN
PC0 VBUS_nVALID INPUT PULLUP
# telem1
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD3 EXTERN_GPIO4 OUTPUT GPIO(4) ALT(1)
PD4 EXTERN_GPIO5 OUTPUT GPIO(5) ALT(1)
# telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
# GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4 NODMA
# GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8 NODMA
# UART7
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# UART for IOMCU
IOMCU_UART USART6
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
# Now the VDD sense pin. This is used to sense primary board voltage.
PA4 VDD_5V_SENS ADC1 SCALE(2)
# This defines an output pin which will default to output HIGH. It is
# a pin that enables peripheral power on this board. It starts in the
# off state, then is pulled low to enable peripherals in
# peripheral_power_enable()
#PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
# SWD debug
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# PWM output for buzzer
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
# CAN1
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# CAN2
PB6 CAN2_TX CAN2
PB12 CAN2_RX CAN2
# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# I2C2
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# I2C3 for onboard mag
PA8 I2C3_SCL I2C3
PC9 I2C3_SDA I2C3
# SPI1.
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI4.
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# SPI2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# This defines more ADC inputs.
PC3 AUX_POWER ADC1 SCALE(1)
PC4 AUX_ADC2 ADC1 SCALE(1)
# And the analog input for airspeed (rarely used these days).
PC5 PRESSURE_SENS ADC1 SCALE(2)
# More CS pins for more sensors. The labels for all CS pins need to
# match the SPI device table later in this file.
PC2 42688_EXT_CS CS
PD7 BARO_EXT_CS CS
PC13 40605_EXT_CS CS
PE4 42688_CS CS
PC14 BARO_CS CS
PD10 FRAM_CS CS
PD2 SDCARD_CS CS
PC1 42688_EXT_DRDY INPUT
PC15 40605_EXT_DRDY INPUT
PD15 42688_DRDY INPUT
# Now we start defining some PWM pins. We also map these pins to GPIO
# values, so users can set SERVOx_FUNCTION=-1 to determine which
# PWM outputs on the primary MCU are set up as GPIOs.
# To match HAL_PX4 we number the GPIOs for the PWM outputs
# starting at 50.
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE13 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)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
PB4 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH
PB3 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH
PB5 LED_BLUE OUTPUT OPENDRAIN GPIO(13) HIGH
define HAL_GPIO_LED_ON 0
define HAL_GPIO_LED_OFF 1
define HAL_GPIO_A_LED_PIN 11
define HAL_GPIO_B_LED_PIN 13
define HAL_GPIO_C_LED_PIN 12
define HAL_HAVE_PIXRACER_LED
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB2 VDD_BRICK_nVALID INPUT PULLUP
PB7 VDD_BRICK2_nVALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
SPIDEV ms5611 SPI1 DEVID5 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
SPIDEV ICM40605_ext SPI4 DEVID4 40605_EXT_CS MODE3 2*MHZ 8*MHZ
SPIDEV ICM42688_ext SPI4 DEVID5 42688_EXT_CS MODE3 2*MHZ 8*MHZ
SPIDEV ICM42688 SPI1 DEVID6 42688_CS MODE3 2*MHZ 8*MHZ
#SPIDEV iim42652 SPI1 DEVID6 42688_CS MODE3 2*MHZ 8*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV sdcard SPI2 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
# IMUs
IMU Invensensev3 SPI:ICM42688 ROTATION_NONE
IMU Invensensev3 SPI:ICM42688_ext ROTATION_NONE
IMU Invensensev3 SPI:ICM40605_ext ROTATION_NONE
#IMU Invensensev3 SPI:iim42652 ROTATION_NONE
define HAL_DEFAULT_INS_FAST_SAMPLE 7
# two baros
BARO MS56XX SPI:ms5611
BARO MS56XX SPI:ms5611_ext
# probe external I2C compasses plus some internal IST8310
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 1
undef AP_FEATURE_SBUS_OUT
# Enable FAT filesystem support.
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
# Enable RAMTROM parameter storage.
define HAL_WITH_RAMTRON 1
define HAL_STORAGE_SIZE 32768
# 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
define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5
# Enable all IMUs to be used and therefore three active EKF Lanes
define HAL_EKF_IMU_MASK_DEFAULT 7
# Now setup the default battery pins driver analog pins and default
# scaling for the power brick.
define HAL_BATT_VOLT_PIN 14
define HAL_BATT_CURR_PIN 15
define HAL_BATT_VOLT_SCALE 18.0
define HAL_BATT_CURR_SCALE 24.0
define HAL_GPIO_PWM_VOLT_PIN 3
define HAL_GPIO_PWM_VOLT_3v3 1
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
DMA_NOSHARE SPI1* SPI4* USART6*