AP_HAL_ESP32: bugfix RmtSigReader for idf - 4.4

This commit is contained in:
Simon 2024-03-14 14:20:01 +02:00 committed by Peter Barker
parent 41fc3a8dbb
commit 750ef597ff

View File

@ -13,6 +13,7 @@ void RmtSigReader::init()
config.clk_div = 80; //80MHZ APB clock to the 1MHZ target frequency config.clk_div = 80; //80MHZ APB clock to the 1MHZ target frequency
config.gpio_num = HAL_ESP32_RCIN; config.gpio_num = HAL_ESP32_RCIN;
config.mem_block_num = 2; //each block could store 64 pulses config.mem_block_num = 2; //each block could store 64 pulses
config.flags = 0;
config.rx_config.filter_en = true; config.rx_config.filter_en = true;
config.rx_config.filter_ticks_thresh = 8; config.rx_config.filter_ticks_thresh = 8;
config.rx_config.idle_threshold = idle_threshold; config.rx_config.idle_threshold = idle_threshold;