mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
We will reserve BOARD_FLASH_SIZE for the internal flash on stm32 flash processors, use HAL_PROGRAM_SIZE_LIMIT_KB in the general code base. Notable change here is that boards with external flash will start to get features only available with more than 2MB of program storage
98 lines
3.0 KiB
C
98 lines
3.0 KiB
C
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
|
#include <GCS_MAVLink/GCS_config.h>
|
|
#include <AP_Radio/AP_Radio_config.h>
|
|
|
|
#ifndef AP_RCPROTOCOL_ENABLED
|
|
#define AP_RCPROTOCOL_ENABLED 1
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED AP_RCPROTOCOL_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_CRSF_ENABLED
|
|
#define AP_RCPROTOCOL_CRSF_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_DRONECAN_ENABLED
|
|
#define AP_RCPROTOCOL_DRONECAN_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_DSM_ENABLED
|
|
#define AP_RCPROTOCOL_DSM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_EMLID_RCIO_ENABLED
|
|
#define AP_RCPROTOCOL_EMLID_RCIO_ENABLED 0
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
|
|
#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
#ifndef AP_RCPROTOCOL_FPORT2_ENABLED
|
|
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_IBUS_ENABLED
|
|
#define AP_RCPROTOCOL_IBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED
|
|
#define AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED defined(SFML_JOYSTICK)
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_PPMSUM_ENABLED
|
|
#define AP_RCPROTOCOL_PPMSUM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_RADIO_ENABLED
|
|
#define AP_RCPROTOCOL_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RADIO_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_SBUS_ENABLED
|
|
#define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_SRXL_ENABLED
|
|
#define AP_RCPROTOCOL_SRXL_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_SRXL2_ENABLED
|
|
#define AP_RCPROTOCOL_SRXL2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_ST24_ENABLED
|
|
#define AP_RCPROTOCOL_ST24_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_SUMD_ENABLED
|
|
#define AP_RCPROTOCOL_SUMD_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_SBUS_NI_ENABLED
|
|
#define AP_RCPROTOCOL_SBUS_NI_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RCPROTOCOL_SBUS_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED
|
|
#define AP_RCPROTOCOL_FASTSBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RCPROTOCOL_SBUS_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_GHST_ENABLED
|
|
#define AP_RCPROTOCOL_GHST_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
|
#define AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_PROGRAM_SIZE_LIMIT_KB > 1024 && HAL_GCS_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_UDP_ENABLED
|
|
#define AP_RCPROTOCOL_UDP_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_FDM_ENABLED
|
|
#define AP_RCPROTOCOL_FDM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
|
#endif
|