AP_HAL_ChibiOS: added PixPilot-C3

This commit is contained in:
Cedric0489 2023-11-07 06:32:59 -06:00 committed by Peter Barker
parent 125c8fa1fa
commit 95dbb7a3f5
5 changed files with 699 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 293 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

View File

@ -0,0 +1,401 @@
## PixPilot-C3 Flight Controller
The PixPilot-C3 flight controller is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com)
## Features
• STM32F427VIT6 and STM32F103C8T6 microcontroller
• two IMUs, two ICM42688-P(SPI)
• Two barometers, BMP388(SPI)
• builtin RAMTRON(SPI)
• microSD card slot
• 5 UARTs
• USB(Type-C)
• PPM, S.Bus & DSM input
• 14 PWM outputs
• tow I2C ports and two FDCAN ports
• one S.Bus output
• builtin Buzzer
• builtin LED
• two voltage & current monitoring
• servo rail BEC independent power input for servos
• external safety Switch
## Pinout
![PixPilot-C3](PixPilot-C3.png "PixPilot-C3")
![PixPilot-C3](PixPilot-C3_Pinout.png "PixPilot-C3_Pinout")
UART Mapping
============
- SERIAL0 -> console (primary mavlink, usually USB)
- SERIAL1 -> USART2 (telem1, DMA-enabled)
- SERIAL2 -> USART3 (Telem2, DMA-enabled)
- SERIAL3 -> UART4 (GPS1)
- SERIAL4 -> UART8 (GPS2, DMA-enabled)
- 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 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>
</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>
DSM 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>+3.3V</td>
</tr>
<tr>
<td>2</td>
<td>RX</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</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.
PWM Output
----------
The PixPilot-V3 supports up to 14 PWM outputs. First first 8 outputs (labelled S1 to S8) are controlled by a dedicated STM32F103 IO controller. These 8
outputs support all PWM output formats, but not DShot.
The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary"
outputs. These are directly attached to the STM32F427 and support all
PWM protocols as well as DShot.
All 14 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 6 auxiliary PWM outputs are in 2 groups:
- PWM 1, 2, 3 and 4 in group1
- PWM 5 and 6 in group2
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 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>` 2
:ref:`BATT_CURR_PIN<BATT_CURR_PIN>` 3
: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>` 14
:ref:`BATT2_CURR_PIN<BATT2_CURR_PIN>` 13
: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,71 @@
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# board ID for firmware load
APJ_BOARD_ID 1140
# crystal frequency
OSCILLATOR_HZ 24000000
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 2048
# location of application code
FLASH_BOOTLOADER_LOAD_KB 16
# bootloader loads at start of flash
FLASH_RESERVE_START_KB 0
# baudrate to run bootloader at on uarts
define BOOTLOADER_BAUDRATE 115200
# uarts and USB to run bootloader protocol on
SERIAL_ORDER OTG1 USART2 USART3 UART7
# this is the pin that senses USB being connected. It is an input pin
# setup as OPENDRAIN
PA9 VBUS INPUT OPENDRAIN
# 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
# Another USART, this one for telem1
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
# the telem2 USART, also with RTS/CTS available
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters)
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# define a LED
PE12 LED_BOOTLOADER OUTPUT
define HAL_LED_ON 1
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PC14 BARO_EXT_CS CS
PE4 42688_EXT_CS CS
PC2 42688_CS CS
PD7 BARO_CS CS
PC1 MAG_CS CS
PB1 SDCARD_CS CS

View File

@ -0,0 +1,227 @@
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# board ID for firmware load
APJ_BOARD_ID 1140
# crystal frequency
OSCILLATOR_HZ 24000000
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -O2
# serial port for stdout, disabled so console is on USB
#STDOUT_SERIAL SD7
#STDOUT_BAUDRATE 57600
# order of I2C buses
I2C_ORDER I2C1 I2C2
# now the UART order. These map to the hal.uartA to hal.uartF
# objects. If you use a shorter list then HAL_Empty::UARTDriver
# objects are substituted for later UARTs, or you can leave a gap by
# listing one or more of the uarts as EMPTY
# 1) SERIAL0: console (primary mavlink, usually USB)
# 2) SERIAL3: primary GPS
# 3) SERIAL1: telem1
# 4) SERIAL2: telem2
# 5) SERIAL4: GPS2
# 6) SERIAL5: extra UART (usually RTOS debug console)
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7
# UART for IOMCU
IOMCU_UART USART6
# UART4 is GPS
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
PA2 BATT_VOLTAGE_SENS ADC1
PA3 BATT_CURRENT_SENS ADC1
PA4 VDD_5V_SENS ADC1 SCALE(2)
# SPI1 is sensors bus
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA9 VBUS INPUT
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# PWM output for buzzer
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
PB2 BOOT1 INPUT
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# SPI2 is FRAM
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PB12 CAN2_RX CAN2
PB6 CAN2_TX CAN2
PC0 VBUS_nVALID INPUT PULLUP
PC3 AUX_POWER ADC1 SCALE(1)
PC4 AUX_ADC2 ADC1 SCALE(1)
# USART6 to IO
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# USART2 serial2 telem1
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD10 FRAM_CS CS
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
# UART8 serial4 FrSky
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# allow this uart to be inverted for transmit under user control
# the polarity is the value to use on the GPIO to change the polarity
# to the opposite of the default
PA10 UART8_TXINV OUTPUT HIGH GPIO(78) POL(0)
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
# Now setup SPI bus4.
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# start peripheral power off, then enable after init
# this prevents a problem with radios that use RTS for
# bootloader hold
PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
# UART7 is debug
PE7 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
# SPI1 CS pins
PE4 42688_EXT_CS CS
PC14 BARO_EXT_CS CS
PC2 42688_CS CS
PD7 BARO_CS CS
PC1 MAG_CS CS
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
# 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.
PB5 VDD_BRICK_nVALID INPUT PULLUP
PG5 VDD_BRICK2_nVALID INPUT PULLUP
PA8 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH
PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH
PC15 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 12
define HAL_GPIO_C_LED_PIN 13
define HAL_HAVE_PIXRACER_LED
# SPI device table
SPIDEV BMP388 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV BMP388_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
SPIDEV ICM42688_ext SPI4 DEVID5 42688_EXT_CS MODE3 2*MHZ 4*MHZ
SPIDEV ICM42688 SPI1 DEVID6 42688_CS MODE3 2*MHZ 4*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
define HAL_DEFAULT_INS_FAST_SAMPLE 3
IMU Invensensev3 SPI:ICM42688 ROTATION_NONE
IMU Invensensev3 SPI:ICM42688_ext ROTATION_NONE
BARO BMP388 SPI:BMP388
BARO BMP388 SPI:BMP388_ext
#COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1
# enable FAT filesystem support (needs a microSD defined via SDIO)
define HAL_OS_FATFS_IO 1
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
PC11 SDIO_D3 SDIO
PC12 SDIO_CK SDIO
PD2 SDIO_CMD SDIO
# battery setup
define HAL_BATT_VOLT_PIN 2
define HAL_BATT_CURR_PIN 3
define HAL_BATT_VOLT_SCALE 18
define HAL_BATT_CURR_SCALE 24
define HAL_BATT2_VOLT_PIN 14
define HAL_BATT2_CURR_PIN 13
define HAL_BATT2_VOLT_SCALE 18.0
define HAL_BATT2_CURR_SCALE 24.0
PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3)
define HAL_GPIO_PWM_VOLT_PIN 3
define HAL_GPIO_PWM_VOLT_3v3 1
# We can't share the IO UART (USART6).
DMA_NOSHARE USART6_TX USART6_RX ADC1
DMA_PRIORITY USART6*
ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin