mirror of https://github.com/ArduPilot/ardupilot
66 lines
1.4 KiB
Plaintext
66 lines
1.4 KiB
Plaintext
include ../CubeRedPrimary/hwdef.dat
|
|
|
|
undef ROMFS
|
|
undef HAL_HAVE_SAFETY_SWITCH
|
|
undef HAL_WITH_IO_MCU_BIDIR_DSHOT
|
|
undef COMPASS
|
|
undef BARO
|
|
undef DEFAULT_SERIAL7_PROTOCOL
|
|
|
|
define AP_ADVANCEDFAILSAFE_ENABLED 0
|
|
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID AP_HW_CUBERED_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
|
|
|
|
# use amber LED
|
|
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_FMU_LED_AMBER
|
|
|
|
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
|
|
|
|
// add scripting for web interface
|
|
define AP_SCRIPTING_ENABLED 1
|
|
|
|
// ROMFS filesystem only
|
|
define AP_FILESYSTEM_ROMFS_ENABLED 1
|
|
|
|
// allow scripts to add parameters
|
|
define AP_PARAM_DYNAMIC_ENABLED 1
|
|
|
|
ROMFS_DIRECTORY Tools/AP_Periph/Web
|