ardupilot/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

58 lines
1.2 KiB
Plaintext
Raw Normal View History

2024-01-11 23:24:55 -04:00
include ../Pixhawk6X/hwdef.dat
undef IOMCU_UART
undef USART6
undef ROMFS
undef HAL_HAVE_SAFETY_SWITCH
undef HAL_WITH_IO_MCU_BIDIR_DSHOT
undef COMPASS
undef BARO
define AP_ADVANCEDFAILSAFE_ENABLED 0
# board ID for firmware load
APJ_BOARD_ID AP_HW_PIXHAWK6X_PERIPH
# setup build for a peripheral firmware
env AP_PERIPH 1
define AP_CAN_SLCAN_ENABLED 0
define HAL_PERIPH_ENABLE_NETWORKING
define HAL_PERIPH_ENABLE_SERIAL_OPTIONS
define AP_NETWORKING_BACKEND_PPP 1
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define HAL_NO_RCIN_THREAD
define AP_SCRIPTING_ENABLED 0
# use blue LED
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE
undef HAL_OS_FATFS_IO
undef SDMMC1
MAIN_STACK 0x2000
PROCESS_STACK 0x6000
define HAL_CAN_DRIVER_DEFAULT 1
# listen for reboot command from uploader.py script
# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
// use main fw bootloader
define AP_BOOTLOADER_FLASHING_ENABLED 0
define AP_PERIPH_NET_PPP_PORT_DEFAULT 1
define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000