hwdef: added MFE_POS3_GPS

This commit is contained in:
mikefenghao 2024-11-02 15:25:47 +08:00 committed by Peter Barker
parent 7cbc4bd4e3
commit 22cec990e5
4 changed files with 250 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 356 KiB

View File

@ -0,0 +1,66 @@
## MFE_POS3_CAN
The MFE_POS3_CAN is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com)
## Features
• STM32F427VIT6 microcontroller
• RM3100 compass
• NEO-M9N
• one CAN port
• Blue led
## Picture
![MFE_POS3_CAN](MFE_POS3_CAN-1.png "MFE_POS3_CAN-1")
## Pinout
Connector pin assignments
=========================
CAN1 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>
Where to Buy
============
`makeflyeasy <http://www.makeflyeasy.com>`

View File

@ -0,0 +1,76 @@
# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32F4xx STM32F427xx
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 32
# reserve some space for params
APP_START_OFFSET_KB 4
# 128k flash part
FLASH_SIZE_KB 2048
# board ID for firmware load
APJ_BOARD_ID AP_HW_MFE_POS3_CAN
# setup build for a peripheral firmware
env AP_PERIPH 1
# debug on USART1
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# crystal frequency
OSCILLATOR_HZ 8000000
define CH_CFG_ST_FREQUENCY 1000000
# order of UARTs
SERIAL_ORDER
# blue LED
PC6 LED_BOOTLOADER OUTPUT HIGH
define HAL_LED_ON 1
#PA0 LED_RED OUTPUT LOW
#PA2 LED_GREEN OUTPUT LOW
#PA3 LED_SAFETY OUTPUT LOW
#PA4 VDD_3V3_SENSORS_EN OUTPUT LOW
# USART1
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
# avoid timer and RCIN threads to save memory
define HAL_NO_TIMER_THREAD
define DMA_RESERVE_SIZE 0
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a smaller bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 2500
# Add CS pins to ensure they are high in bootloader
PA4 MAG_CS CS

View File

@ -0,0 +1,108 @@
# hw definition file for processing by chibios_pins.py
# MCU class and specific type
#AUTOBUILD_TARGETS None
# MCU class and specific type
MCU STM32F4xx STM32F427xx
FLASH_RESERVE_START_KB 36
STORAGE_FLASH_PAGE 16
define HAL_STORAGE_SIZE 8192
# board ID for firmware load
APJ_BOARD_ID AP_HW_MFE_POS3_CAN
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 8000000
define CH_CFG_ST_FREQUENCY 1000000
FLASH_SIZE_KB 2048
# order of UARTs
SERIAL_ORDER USART1 USART2
# LEDs
PC6 LED OUTPUT LOW
define HAL_GPIO_LED_ON 1
# USART2, GPS
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# USART1, debug, disabled to save flash
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# I2C2 bus
PB11 I2C2_SDA I2C2
PB10 I2C2_SCL I2C2
# I2C buses
I2C_ORDER I2C2
# one SPI bus
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI CS
PA4 MAG_CS CS
# GPS PPS
PA10 GPS_PPS_IN INPUT
# SPI devices
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE3 1*MHZ 1*MHZ
# compass
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
COMPASS IST8310 I2C:0:0x0C false ROTATION_NONE
define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
define HAL_NO_GPIO_IRQ
define HAL_USE_RTC FALSE
define DMA_RESERVE_SIZE 0
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_DEVICE_THREAD_STACK 768
# we setup a small defaults.parm
define AP_PARAM_MAX_EMBEDDED_PARAM 256
# disable dual GPS and GPS blending to save flash space
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
# add support for moving baseline yaw
define GPS_MOVING_BASELINE 1
# GPS+MAG+BARO+LEDs
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
# GPS on 1st port
define HAL_PERIPH_GPS_PORT_DEFAULT 1
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True