mirror of https://github.com/ArduPilot/ardupilot
hwdef: added MFE_PDB_CAN
This commit is contained in:
parent
f08a9e7203
commit
cdfef59697
Binary file not shown.
After Width: | Height: | Size: 864 KiB |
|
@ -0,0 +1,174 @@
|
|||
|
||||
## MFE_PDB_CAN
|
||||
|
||||
The MFE_PDB_CAN is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com)
|
||||
|
||||
## Features
|
||||
|
||||
• STM32L431CCU6 microcontroller
|
||||
|
||||
• two power for autopilot(5.5V 5A)
|
||||
|
||||
• one power for servo(5.3V 5A)
|
||||
|
||||
• one power for load(12V 5A)
|
||||
|
||||
• Battery monitoring (power1 can, power2 adc)
|
||||
|
||||
|
||||
|
||||
## Picture
|
||||
|
||||
![MFE_PDB_CAN](MFE_PDB_CAN-1.png "MFE_PDB_CAN-1")
|
||||
|
||||
|
||||
Connector pin assignments
|
||||
=========================
|
||||
|
||||
power1 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>+5.5V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>2</td>
|
||||
<td>VCC</td>
|
||||
<td>+5.5V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>3</td>
|
||||
<td>CAN_H</td>
|
||||
<td>SINGAL</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>4</td>
|
||||
<td>CAN_L</td>
|
||||
<td>SINGAL</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>
|
||||
|
||||
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>+5.5V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>2</td>
|
||||
<td>VCC</td>
|
||||
<td>+5.5V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>3</td>
|
||||
<td>CURRENT</td>
|
||||
<td>SINGAL</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>4</td>
|
||||
<td>VALTAGE</td>
|
||||
<td>SINGAL</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>
|
||||
|
||||
power3 pad
|
||||
---------------
|
||||
|
||||
<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>+5.3V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>2</td>
|
||||
<td>GND</td>
|
||||
<td>+GND</td>
|
||||
</tr>
|
||||
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
power4 pad
|
||||
---------------
|
||||
|
||||
<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>+12V</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>2</td>
|
||||
<td>GND</td>
|
||||
<td>+GND</td>
|
||||
</tr>
|
||||
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
Connector pin assignments
|
||||
=========================
|
||||
|
||||
BATT_VOLT_MULT 17.93387
|
||||
|
||||
BATT_AMP_PERVLT 22.0
|
||||
|
||||
|
||||
Where to Buy
|
||||
============
|
||||
|
||||
[www.makeflyeasy.com](www.makeflyeasy.com)
|
||||
|
|
@ -0,0 +1,6 @@
|
|||
#Default Parameters for the MFE_PDB_CAN
|
||||
|
||||
BATT_AMP_OFFSET 0.01
|
||||
BATT_CAPACITY 22000
|
||||
|
||||
|
|
@ -0,0 +1,55 @@
|
|||
# MCU class and specific type
|
||||
MCU STM32L431 STM32L431xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 6100
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 36
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# reserve some space for params
|
||||
APP_START_OFFSET_KB 4
|
||||
|
||||
# ---------------------------------------------
|
||||
PB3 LED_BOOTLOADER OUTPUT LOW # blue
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
# ---------------------------------------------
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
define HAL_USE_SERIAL FALSE
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 32
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA4 MAG_CS CS
|
||||
PB2 SPARE_CS CS
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
|
@ -0,0 +1,110 @@
|
|||
# MCU class and specific type
|
||||
MCU STM32L431 STM32L431xx
|
||||
|
||||
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
||||
FLASH_RESERVE_START_KB 40
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# store parameters in pages 18 and 19
|
||||
STORAGE_FLASH_PAGE 18
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 15
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 6100
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
env AP_PERIPH 1
|
||||
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
# MAIN_STACK is stack for ISR handlers
|
||||
MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
# we setup a small defaults.parm
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
# blue LED0 marked as ACT
|
||||
PC13 LED OUTPUT HIGH
|
||||
|
||||
define HAL_LED_ON 1
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
|
||||
|
||||
# ---------------------- CAN bus -------------------------
|
||||
CAN_ORDER 1
|
||||
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
define HAL_CAN_POOL_SIZE 6000
|
||||
|
||||
# ---------------------- UARTs ---------------------------
|
||||
# | sr0 | MSP | GPS |
|
||||
SERIAL_ORDER USART1 USART2 USART3
|
||||
|
||||
# USART1 for debug
|
||||
PB6 USART1_TX USART1 SPEED_HIGH
|
||||
PB7 USART1_RX USART1 SPEED_HIGH
|
||||
|
||||
# USART2 for MSP
|
||||
PA2 USART2_TX USART2 SPEED_HIGH
|
||||
PA3 USART2_RX USART2 SPEED_HIGH
|
||||
|
||||
# USART3 for GPS
|
||||
PB10 USART3_TX USART3 SPEED_HIGH NODMA
|
||||
PB11 USART3_RX USART3 SPEED_HIGH NODMA
|
||||
|
||||
# allow for reboot command for faster development
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
# keep ROMFS uncompressed as we don't have enough RAM
|
||||
# to uncompress the bootloader at runtime
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
||||
define HAL_RCIN_THREAD_ENABLED 1
|
||||
|
||||
# ------------------ BATTERY Monitor -----------------------
|
||||
define HAL_PERIPH_ENABLE_BATTERY
|
||||
|
||||
define HAL_USE_ADC TRUE
|
||||
define STM32_ADC_USE_ADC1 TRUE
|
||||
|
||||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 5
|
||||
define HAL_BATT_VOLT_SCALE 17.93387
|
||||
define HAL_BATT_CURR_PIN 6
|
||||
define HAL_BATT_CURR_SCALE 22.0
|
||||
#define HAL_BATT_AMP_OFFSET 0.02
|
||||
#define HAL_BATT_CAPACITY 22000
|
||||
|
||||
|
||||
PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PB1 BATT2_CURRENT_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT2_MONITOR_DEFAULT 0
|
||||
define HAL_BATT2_VOLT_PIN 15
|
||||
define HAL_BATT2_VOLT_SCALE 17.93387
|
||||
define HAL_BATT2_CURR_PIN 16
|
||||
define HAL_BATT2_CURR_SCALE 22.0
|
Loading…
Reference in New Issue