mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: CarbonixL496 crystal hwdef changes
This commit is contained in:
parent
6fe9090367
commit
8d64d5215e
|
@ -15,8 +15,8 @@ APJ_BOARD_ID 1053
|
|||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# crystal frequency set to 0 to use internal clock
|
||||
OSCILLATOR_HZ 0
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 12000000
|
||||
|
||||
# assume 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
@ -28,7 +28,7 @@ STDOUT_BAUDRATE 57600
|
|||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
# a fault LED
|
||||
PA15 LED_BOOTLOADER OUTPUT HIGH # blue
|
||||
PA13 LED_BOOTLOADER OUTPUT HIGH # blue
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# USART1
|
||||
|
@ -60,9 +60,9 @@ define HAL_DISABLE_LOOP_DELAY
|
|||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
# debugger support, disabled as PA13 used for LED
|
||||
# PA13 JTMS-SWDIO SWD
|
||||
# PA14 JTCK-SWCLK SWD
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
|
|
@ -18,8 +18,8 @@ env AP_PERIPH 1
|
|||
|
||||
# enable watchdog
|
||||
|
||||
# crystal frequency set to 0 to use internal clock
|
||||
OSCILLATOR_HZ 0
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 12000000
|
||||
|
||||
# assume the 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
@ -55,7 +55,7 @@ PA11 OTG_FS_DM OTG1
|
|||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# LED, active low
|
||||
PA15 LED OUTPUT HIGH GPIO(1)
|
||||
PA13 LED OUTPUT HIGH GPIO(1)
|
||||
|
||||
# spi2
|
||||
PB10 SPI2_SCK SPI2
|
||||
|
@ -78,9 +78,9 @@ I2C_ORDER I2C4
|
|||
# allow for reboot command for faster development
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
# debugger support (disabled as conflicts with LED)
|
||||
#PA13 JTMS-SWDIO SWD
|
||||
#PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
|
@ -138,9 +138,4 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
|||
define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
|
||||
|
||||
BARO MS56XX I2C:0:0x76
|
||||
COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180
|
||||
|
|
Loading…
Reference in New Issue