2022-04-16 23:54:08 -03:00
|
|
|
#pragma once
|
|
|
|
|
2023-03-14 08:18:29 -03:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
2022-04-16 23:54:08 -03:00
|
|
|
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
|
|
|
|
2023-03-14 08:18:29 -03:00
|
|
|
#ifndef AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
|
|
#define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 1
|
|
|
|
#endif
|
|
|
|
|
2023-04-26 10:46:08 -03:00
|
|
|
#ifndef AP_RCPROTOCOL_CRSF_ENABLED
|
|
|
|
#define AP_RCPROTOCOL_CRSF_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
|
|
#endif
|
|
|
|
|
2023-03-18 23:00:34 -03:00
|
|
|
#ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED
|
|
|
|
#define AP_RCPROTOCOL_FASTSBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
|
|
#endif
|
|
|
|
|
2022-04-16 23:54:08 -03:00
|
|
|
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
|
2023-03-14 08:18:29 -03:00
|
|
|
#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
|
|
|
#ifndef AP_RCPROTOCOL_FPORT2_ENABLED
|
2023-03-14 08:18:29 -03:00
|
|
|
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef AP_RCPROTOCOL_SRXL_ENABLED
|
|
|
|
#define AP_RCPROTOCOL_SRXL_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
2023-04-26 04:19:07 -03:00
|
|
|
|
|
|
|
#ifndef AP_RCPROTOCOL_SRXL2_ENABLED
|
|
|
|
#define AP_RCPROTOCOL_SRXL2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
|
|
|
#endif
|