From 7846cccdaaf32ef9816180abceed801b49eb4475 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Fri, 6 Sep 2024 09:47:19 +1000 Subject: [PATCH] AP_HAL_ESP32: fix RMT on s3by using channel thats compatible with both . --- libraries/AP_HAL_ESP32/RmtSigReader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/RmtSigReader.cpp b/libraries/AP_HAL_ESP32/RmtSigReader.cpp index c0b1e2c1a5..54d1d42fb3 100644 --- a/libraries/AP_HAL_ESP32/RmtSigReader.cpp +++ b/libraries/AP_HAL_ESP32/RmtSigReader.cpp @@ -9,7 +9,7 @@ void RmtSigReader::init() { rmt_config_t config; config.rmt_mode = RMT_MODE_RX; - config.channel = RMT_CHANNEL_0; + config.channel = RMT_CHANNEL_4; // On S3, Channel 0 ~ 3 (TX channel) are dedicated to sending signals. Channel 4 ~ 7 (RX channel) are dedicated to receiving signals, so this pin choice is compatible with both. config.clk_div = 80; //80MHZ APB clock to the 1MHZ target frequency config.gpio_num = HAL_ESP32_RCIN; config.mem_block_num = 2; //each block could store 64 pulses