mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed fmuv3 build with no ICU
This commit is contained in:
parent
f87668c15c
commit
ccb85c2707
|
@ -214,7 +214,7 @@ void RCInput::_timer_tick(void)
|
|||
|
||||
bool RCInput::rc_bind(int dsmMode)
|
||||
{
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
#ifdef HAL_RCINPUT_WITH_AP_RADIO
|
||||
if (radio) {
|
||||
radio->start_recv_bind();
|
||||
}
|
||||
|
|
|
@ -69,7 +69,7 @@ private:
|
|||
uint32_t last_radio_us;
|
||||
#endif
|
||||
|
||||
#ifdef HAL_USE_ICU
|
||||
#if HAL_USE_ICU == TRUE
|
||||
ChibiOS::SoftSigReader sig_reader;
|
||||
AP_RCProtocol rcin_prot;
|
||||
#endif
|
||||
|
|
|
@ -22,6 +22,8 @@
|
|||
using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if HAL_USE_ICU == TRUE
|
||||
|
||||
bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel)
|
||||
{
|
||||
if (chan > ICU_CHANNEL_2) {
|
||||
|
@ -115,5 +117,6 @@ bool SoftSigReader::set_bounce_buf_size(uint16_t buf_size)
|
|||
return true;
|
||||
}
|
||||
|
||||
#endif // HAL_USE_ICU
|
||||
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include "AP_HAL_ChibiOS.h"
|
||||
|
||||
#if HAL_USE_ICU == TRUE
|
||||
|
||||
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
|
||||
#define MAX_SIGNAL_TRANSITIONS 256
|
||||
#define DEFAULT_BOUNCE_BUF_SIZE 32
|
||||
|
@ -41,3 +43,6 @@ private:
|
|||
ICUConfig icucfg;
|
||||
uint16_t _bounce_buf_size = DEFAULT_BOUNCE_BUF_SIZE;
|
||||
};
|
||||
|
||||
#endif // HAL_USE_ICU
|
||||
|
||||
|
|
Loading…
Reference in New Issue