mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ChibiOS: add and use AP_RCPROTOCOL_ENABLED
This commit is contained in:
parent
b7f3d25bed
commit
2d7123fcff
@ -21,6 +21,8 @@
|
||||
#include "hwdef/common/ppm.h"
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
||||
#include <AP_RCProtocol/AP_RCProtocol_config.h>
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_IOMCU/AP_IOMCU.h>
|
||||
@ -38,7 +40,7 @@ using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
void RCInput::init()
|
||||
{
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
AP::RC().init();
|
||||
#endif
|
||||
|
||||
@ -153,7 +155,7 @@ void RCInput::_timer_tick(void)
|
||||
RCSource source = last_source;
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
AP_RCProtocol &rcprot = AP::RC();
|
||||
|
||||
#if HAL_USE_ICU == TRUE
|
||||
@ -176,16 +178,19 @@ void RCInput::_timer_tick(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // AP_RCPROTOCOL_ENABLED
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
uint32_t now = AP_HAL::millis();
|
||||
const bool have_iocmu_rc = (_rcin_last_iomcu_ms != 0 && now - _rcin_last_iomcu_ms < 400);
|
||||
if (!have_iocmu_rc) {
|
||||
_rcin_last_iomcu_ms = 0;
|
||||
}
|
||||
#else
|
||||
#elif AP_RCPROTOCOL_ENABLED || HAL_RCINPUT_WITH_AP_RADIO
|
||||
const bool have_iocmu_rc = false;
|
||||
#endif
|
||||
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
if (rcprot.new_input() && !have_iocmu_rc) {
|
||||
WITH_SEMAPHORE(rcin_mutex);
|
||||
_rcin_timestamp_last_signal = AP_HAL::micros();
|
||||
@ -199,7 +204,7 @@ void RCInput::_timer_tick(void)
|
||||
source = rcprot.using_uart() ? RCSource::RCPROT_BYTES : RCSource::RCPROT_PULSES;
|
||||
#endif
|
||||
}
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
#endif // AP_RCPROTOCOL_ENABLED
|
||||
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
if (radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc) {
|
||||
@ -259,7 +264,7 @@ bool RCInput::rc_bind(int dsmMode)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
// ask AP_RCProtocol to start a bind
|
||||
AP::RC().start_bind();
|
||||
#endif
|
||||
|
@ -3110,6 +3110,12 @@ INCLUDE common.ld
|
||||
#define AP_RC_CHANNEL_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_ENABLED
|
||||
#define AP_RCPROTOCOL_ENABLED 0
|
||||
#endif
|
||||
|
||||
#define HAL_CRSF_TELEM_ENABLED 0
|
||||
|
||||
/*
|
||||
* GPS Backends - we selectively turn backends on.
|
||||
* Note also that f103-GPS explicitly disables some of these backends.
|
||||
@ -3223,6 +3229,18 @@ INCLUDE common.ld
|
||||
#define AP_WINCH_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_VIDEOTX_ENABLED
|
||||
#define AP_VIDEOTX_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_FRSKY_TELEM_ENABLED
|
||||
#define AP_FRSKY_TELEM_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef HAL_SPEKTRUM_TELEM_ENABLED
|
||||
#define HAL_SPEKTRUM_TELEM_ENABLED 0
|
||||
#endif
|
||||
|
||||
// end AP_Periph defaults
|
||||
''')
|
||||
|
||||
@ -3289,6 +3307,8 @@ INCLUDE common.ld
|
||||
|
||||
#define HAL_DSHOT_ALARM_ENABLED 0
|
||||
|
||||
#define HAL_LOGGING_ENABLED 0
|
||||
|
||||
// IOMCUs *definitely* don't use the FFT library:
|
||||
#ifndef HAL_GYROFFT_ENABLED
|
||||
#define HAL_GYROFFT_ENABLED 0
|
||||
|
@ -170,8 +170,8 @@ define AP_WINCH_ENABLED 0
|
||||
define AP_CAMERA_BACKEND_DEFAULT_ENABLED 0
|
||||
define AP_CAMERA_MAVLINK_ENABLED 1
|
||||
|
||||
// remove RC Protocol support:
|
||||
define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0
|
||||
# SkyViper uses AP_Radio, which does its own RC protocol decoding:
|
||||
define AP_RCPROTOCOL_ENABLED 0
|
||||
|
||||
// few prelcnad backends are applicable
|
||||
define AC_PRECLAND_BACKEND_DEFAULT_ENABLED 0
|
||||
|
Loading…
Reference in New Issue
Block a user