-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathardupilot_revo_alt_hwdef.dat
139 lines (103 loc) · 3.03 KB
/
ardupilot_revo_alt_hwdef.dat
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
# custom hw definition file for processing by chibios_pins.py
# for Revo(Mini) hardware
# RC input (PPM/sBus) on PWM input Ch1
# GPS rx/tx on PWM input Ch 3/4
# telem1 on mainport
# I2C2 on flexiport
# MCU class and specific type
MCU STM32F4xx STM32F405xx
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_REVOMINI
# board ID for firmware load
APJ_BOARD_ID 124
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
define STM32_ST_USE_TIMER 5
FLASH_SIZE_KB 1024
# board voltage
STM32_VDD 330U
# use USB for stdout, so no STDOUT_SERIAL
# STDOUT_SERIAL SD3
# STDOUT_BAUDRATE 57600
# I2C bus order
I2C_ORDER I2C1 I2C2
# order of UARTs (USB, GPS1, telem1), flexiport used for I2C2
UART_ORDER OTG1 USART6 USART1
# rcinput is PB14 = PWM input ch 1
PB14 TIM12_CH1 TIM12 RCININT FLOAT LOW
# analog pins
PC3 VDD_5V_SENS ADC1
PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
PC5 USB_SENSE ADC1
# define default battery setup
define HAL_BATT_VOLT_PIN 12
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
PC0 SBUS_INVERT OUTPUT LOW
# LEDs
PB5 LED_BLUE OUTPUT LOW GPIO(0)
PB6 LED_YELLOW OUTPUT LOW GPIO(1) # optional
PB4 LED_RED OUTPUT LOW GPIO(2)
# GPS on PWM input Ch3 / 4
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# flexi port UART disabled for I2C use
#PB10 USART3_TX USART3
#PB11 USART3_RX USART3
# main port, for telem1
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# I2C on flexiport
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# spi bus for IMU
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# spi bus for dataflash
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
# IRQ for MPU6000
PC4 EXTI_MPU6000 INPUT
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# onboard I2C baro
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# SPI chip selects
PA4 MPU_CS CS
PB3 FLASH_CS CS
# PWM out pins
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
PA0 TIM2_CH1 TIM2 PWM(6) GPIO(55)
PC8 TIM8_CH3 TIM2 PWM(7) GPIO(56)
PC9 TIM8_CH4 TIM2 PWM(8) GPIO(57)
PB7 DRDY_HMC5883 INPUT PULLUP
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 2
# reserve 32k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 64
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_180
define HAL_COMPASS_DEFAULT HAL_COMPASS_HMC5843
define HAL_COMPASS_HMC5843_I2C_BUS 0
define HAL_COMPASS_HMC5843_I2C_ADDR 0x1E
define HAL_COMPASS_HMC5843_ROTATION ROTATION_YAW_270
define HAL_BARO_DEFAULT HAL_BARO_MS5611_I2C
define HAL_BARO_MS5611_I2C_BUS 0
define HAL_BARO_MS5611_I2C_ADDR 0x77
# SPI devices
SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 8*MHZ
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 1*MHZ 8*MHZ
# 8 PWM available by default
define BOARD_PWM_COUNT_DEFAULT 8