diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp index db464cd40ece4dfccfeecd8235fcf0e1cddfbafa..8b44a472a483ba6822533c5a91c1f143c6d43b28 100644 --- a/src/entrypoints/sx1278-serial.cpp +++ b/src/entrypoints/sx1278-serial.cpp @@ -62,7 +62,7 @@ using rxen = Gpio<GPIOD_BASE, 4>; #define SX1278_SPI SPI4 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl -#define SX1278_IRQ_DIO1 EXTI2_IRQHandlerImpl +#define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl #elif defined _BOARD_STM32F429ZI_SKYWARD_RIG @@ -79,8 +79,8 @@ using sck = radio::sck; using miso = radio::miso; using mosi = radio::mosi; -using txen = radio::txEn; -using rxen = radio::rxEn; +using txen = radio::txEn; +using rxen = radio::rxEn; #define SX1278_SPI SPI4 @@ -132,24 +132,6 @@ void initBoard() rxen::low(); txen::low(); #endif - -#ifdef SX1278_IRQ_DIO0 - GpioPin dio0_pin = dio0::getPin(); - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_EDGE); -#endif - -#ifdef SX1278_IRQ_DIO1 - GpioPin dio1_pin = dio1::getPin(); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_EDGE); -#endif - -#ifdef SX1278_IRQ_DIO3 - GpioPin dio3_pin = dio3::getPin(); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_EDGE); -#endif } void recvLoop() @@ -185,7 +167,6 @@ int main() initBoard(); SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); #if defined SX1278_IS_EBYTE printf("[sx1278] Confuring Ebyte frontend...\n"); @@ -204,8 +185,9 @@ int main() SX1278Lora::Config config; SX1278Lora::Error err; - sx1278 = - new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278 lora...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) @@ -220,13 +202,14 @@ int main() SX1278Fsk::Config config; SX1278Fsk::Error err; - sx1278 = - new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278 fsk...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) { - // FIXME: Why does clang-format put this line up here? + // FIXME: Why does clang-format put this line up here? printf("[sx1278] sx1278->init error\n"); return -1; } diff --git a/src/shared/radio/SX1278/SX1278Common.cpp b/src/shared/radio/SX1278/SX1278Common.cpp index 91d3b0b914dc89ff183f2efcf83d9d6652454a7e..a815363c73d24140323201f86528f45b2262e675 100644 --- a/src/shared/radio/SX1278/SX1278Common.cpp +++ b/src/shared/radio/SX1278/SX1278Common.cpp @@ -45,11 +45,18 @@ void SX1278Common::handleDioIRQ() } } +void SX1278Common::enableIrqs() { + enableExternalInterrupt(dio0.getPort(), dio0.getNumber(), InterruptTrigger::RISING_EDGE); + enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), InterruptTrigger::RISING_EDGE); + enableExternalInterrupt(dio3.getPort(), dio3.getNumber(), InterruptTrigger::RISING_EDGE); +} + void SX1278Common::setDefaultMode(Mode mode, DioMapping mapping, + InterruptTrigger dio1_trigger, bool tx_frontend, bool rx_frontend) { mutex.lock(); - enterMode(mode, mapping, tx_frontend, rx_frontend); + enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend); mutex.unlock(); } @@ -163,13 +170,14 @@ ISX1278Frontend &SX1278Common::getFrontend() { return *frontend; } SPISlave &SX1278Common::getSpiSlave() { return slave; } SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping, + InterruptTrigger dio1_trigger, bool tx_frontend, bool rx_frontend) { // Store previous state DeviceState old_state = state; - enterMode(mode, mapping, tx_frontend, rx_frontend); + enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend); state.irq_wait_thread = nullptr; return old_state; @@ -179,8 +187,8 @@ void SX1278Common::unlockMode(DeviceState old_state) { // Do this copy manually, we want stuff to be copied in a specific order state.irq_wait_thread = old_state.irq_wait_thread; - enterMode(old_state.mode, old_state.mapping, old_state.is_tx_frontend_on, - old_state.is_rx_frontend_on); + enterMode(old_state.mode, old_state.mapping, old_state.dio1_trigger, + old_state.is_tx_frontend_on, old_state.is_rx_frontend_on); } void SX1278Common::lock() { mutex.lock(); } @@ -188,6 +196,7 @@ void SX1278Common::lock() { mutex.lock(); } void SX1278Common::unlock() { mutex.unlock(); } void SX1278Common::enterMode(Mode mode, DioMapping mapping, + InterruptTrigger dio1_trigger, bool set_tx_frontend_on, bool set_rx_frontend_on) { // disable - enable in order to avoid having both RX/TX frontends active at @@ -218,13 +227,19 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping, state.is_tx_frontend_on = set_tx_frontend_on; state.is_rx_frontend_on = set_rx_frontend_on; - // Check if necessary if (mode != state.mode) { setMode(mode); state.mode = mode; } + // Change DIO1 interrupt kind + if (dio1_trigger != state.dio1_trigger) + { + enableExternalInterrupt(dio1.getPort(), dio1.getNumber(), dio1_trigger); + state.dio1_trigger = dio1_trigger; + } + // Finally setup DIO mapping if (mapping != state.mapping) { diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h index 744f3f7cd4813358555af57806811c67a994aee7..2ac8cc60748473ad249192fcea54b43d77351491 100644 --- a/src/shared/radio/SX1278/SX1278Common.h +++ b/src/shared/radio/SX1278/SX1278Common.h @@ -22,6 +22,7 @@ #pragma once +#include <drivers/interrupt/external_interrupts.h> #include <drivers/spi/SPIDriver.h> #include <miosix.h> #include <radio/Transceiver.h> @@ -114,6 +115,8 @@ private: bool is_rx_frontend_on = false; // True if the TX frontend is enabled bool is_tx_frontend_on = false; + // Mode of trigger for dio1 + InterruptTrigger dio1_trigger = InterruptTrigger::RISING_EDGE; }; public: @@ -123,12 +126,14 @@ public: void handleDioIRQ(); protected: - explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, + explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0, + miosix::GpioPin dio1, miosix::GpioPin dio3, SPI::ClockDivider clock_divider, std::unique_ptr<ISX1278Frontend> frontend) - : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))), - frontend(std::move(frontend)) + : slave(SPISlave(bus, cs, getSpiBusConfig(clock_divider))), dio0(dio0), + dio1(dio1), dio3(dio3), frontend(std::move(frontend)) { + enableIrqs(); } /** @@ -152,13 +157,14 @@ protected: { public: LockMode(SX1278Common &driver, Lock &lock, Mode mode, - DioMapping mapping, bool set_tx_frontend_on = false, + DioMapping mapping, InterruptTrigger dio1_trigger, + bool set_tx_frontend_on = false, bool set_rx_frontend_on = false) : driver(driver), lock(lock) { // cppcheck-suppress useInitializationList - old_state = driver.lockMode(mode, mapping, set_tx_frontend_on, - set_rx_frontend_on); + old_state = driver.lockMode(mode, mapping, dio1_trigger, + set_tx_frontend_on, set_rx_frontend_on); } ~LockMode() { driver.unlockMode(old_state); } @@ -174,7 +180,8 @@ protected: * * WARNING: This will lock the mutex. */ - void setDefaultMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on, + void setDefaultMode(Mode mode, DioMapping mapping, + InterruptTrigger dio1_trigger, bool set_tx_frontend_on, bool set_rx_frontend_on); /** @@ -209,21 +216,27 @@ protected: SPISlave &getSpiSlave(); private: + void enableIrqs(); + void waitForIrqInner(LockMode &guard, bool unlock); - DeviceState lockMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on, + DeviceState lockMode(Mode mode, DioMapping mapping, + InterruptTrigger dio1_trigger, bool set_tx_frontend_on, bool set_rx_frontend_on); void unlockMode(DeviceState old_state); void lock(); void unlock(); - void enterMode(Mode mode, DioMapping mapping, bool set_tx_frontend_on, - bool set_rx_frontend_on); + void enterMode(Mode mode, DioMapping mapping, InterruptTrigger dio1_trigger, + bool set_tx_frontend_on, bool set_rx_frontend_on); miosix::FastMutex mutex; DeviceState state; SPISlave slave; + miosix::GpioPin dio0; + miosix::GpioPin dio1; + miosix::GpioPin dio3; std::unique_ptr<ISX1278Frontend> frontend; }; diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp index d7cd936d76a382cf496fb04a3caadb4f77807363..58dcca41b8cc0bc5b4ffb394f1e199f5d218d0da 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.cpp +++ b/src/shared/radio/SX1278/SX1278Fsk.cpp @@ -74,12 +74,14 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config) // Set default mode to standby, that way we reset the fifo every time we // enter receive - setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false); + setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, + InterruptTrigger::RISING_EDGE, false, false); miosix::Thread::sleep(1); // Lock the bus Lock guard(*this); - LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING); + LockMode guard_mode(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING, + InterruptTrigger::RISING_EDGE); // The datasheet lies, this IRQ is unreliable, it doesn't always trigger // if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 0, 1000)) @@ -230,7 +232,7 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len) { Lock guard(*this); LockMode guard_mode(*this, guard, RegOpMode::MODE_RX, DEFAULT_MAPPING, - false, true); + InterruptTrigger::RISING_EDGE, false, true); // Save the packet locally, we always want to read it all uint8_t tmp_pkt[MTU]; @@ -311,8 +313,8 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len) rateLimitTx(); Lock guard(*this); - LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING, true, - false); + LockMode guard_mode(*this, guard, RegOpMode::MODE_TX, DEFAULT_MAPPING, + InterruptTrigger::FALLING_EDGE, true, false); waitForIrq(guard_mode, RegIrqFlags::TX_READY, 0); diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h index 994de6ddb65d7e2d0f3598c96229dce3b756c2ea..b67f6c202eb45fa1a5425d4cf2b4424d011b1b53 100644 --- a/src/shared/radio/SX1278/SX1278Fsk.h +++ b/src/shared/radio/SX1278/SX1278Fsk.h @@ -135,10 +135,12 @@ public: /** * @brief Construct a new SX1278 */ - explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, + explicit SX1278Fsk(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0, + miosix::GpioPin dio1, miosix::GpioPin dio3, SPI::ClockDivider clock_divider, std::unique_ptr<SX1278::ISX1278Frontend> frontend) - : SX1278Common(bus, cs, clock_divider, std::move(frontend)), + : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider, + std::move(frontend)), crc_enabled(false) { } diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp index 744f8d06720cfa657a0d04a19ff49b3597193b5c..de7c3ecfdccddf5ba8df6fb292f7d9d0dc9dd2f1 100644 --- a/src/shared/radio/SX1278/SX1278Lora.cpp +++ b/src/shared/radio/SX1278/SX1278Lora.cpp @@ -163,11 +163,12 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config) enterLoraMode(); // Then make sure the device remains in standby and not in sleep - setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false); + setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, InterruptTrigger::RISING_EDGE, false, false); // Lock the bus Lock guard(*this); - LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING); + LockMode mode_guard(*this, guard, RegOpMode::MODE_STDBY, DEFAULT_MAPPING, + InterruptTrigger::RISING_EDGE); RegModemConfig1::Bw bw = static_cast<RegModemConfig1::Bw>(config.bandwidth); RegModemConfig1::Cr cr = @@ -282,7 +283,8 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len) // Use continuous because it doesn't go into timeout (and you cannot // disable it...) LockMode mode_guard(*this, guard, RegOpMode::MODE_RXCONTINUOUS, - DioMapping(0, 0, 0, 0, 0, 0), false, true); + DioMapping(0, 0, 0, 0, 0, 0), + InterruptTrigger::RISING_EDGE, false, true); waitForIrq(mode_guard, RegIrqFlags::RX_DONE, 0, true); @@ -317,7 +319,8 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len) { // Now enter in mode TX to send the packet LockMode mode_guard(*this, guard, RegOpMode::MODE_TX, - DioMapping(1, 0, 0, 0, 0, 0), true, false); + DioMapping(1, 0, 0, 0, 0, 0), + InterruptTrigger::RISING_EDGE, true, false); // Wait for the transmission to end waitForIrq(mode_guard, RegIrqFlags::TX_DONE, 0); diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h index da4a1905b591741972e4adddfc204844a9498f78..c30bdf41f72962659748fca95b292272d6ca32b8 100644 --- a/src/shared/radio/SX1278/SX1278Lora.h +++ b/src/shared/radio/SX1278/SX1278Lora.h @@ -136,10 +136,12 @@ public: /** * @brief Construct a new SX1278 */ - explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, + explicit SX1278Lora(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0, + miosix::GpioPin dio1, miosix::GpioPin dio3, SPI::ClockDivider clock_divider, std::unique_ptr<SX1278::ISX1278Frontend> frontend) - : SX1278Common(bus, cs, clock_divider, std::move(frontend)), + : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider, + std::move(frontend)), crc_enabled(false) { } diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp index 4c2508ea283c97135dc1c91213eeb9a145a7830d..e6f69d0be1602ae81c2dbe397d0b4c73a2ead4cd 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-bidir.cpp @@ -139,12 +139,12 @@ int main() SX1278Fsk::Error err; SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); - sx1278 = - new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp index 0d430f6952e32e4465453827f9ac6db892706914..caffecc2ef6308573e55ebba14b739df744289de 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -96,16 +96,7 @@ void __attribute__((used)) SX1278_IRQ_DIO3() void initBoard() { - GpioPin dio0_pin = dio0::getPin(); - GpioPin dio1_pin = dio1::getPin(); - GpioPin dio3_pin = dio3::getPin(); - - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); + } Mav* channel; @@ -160,12 +151,11 @@ int main() SX1278Fsk::Error err; SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); sx1278 = - new SX1278Fsk(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), dio3::getPin(), SPI::ClockDivider::DIV_64, std::move(frontend)); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE) diff --git a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp index 0185e0167cd6e0093baf741c9e1f5c4b0ef2d580..c89191e55cf55303c9525c3dddfe1abe5581aea8 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-bidir.cpp @@ -89,17 +89,6 @@ void initBoard() rxen::low(); txen::low(); #endif - - GpioPin dio0_pin = dio0::getPin(); - GpioPin dio1_pin = dio1::getPin(); - GpioPin dio3_pin = dio3::getPin(); - - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_EDGE); } bool isByteBuf(uint8_t *buf, ssize_t len) @@ -182,7 +171,6 @@ int main() SX1278Lora::Error err; SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); #ifdef IS_EBYTE std::unique_ptr<SX1278::ISX1278Frontend> frontend( @@ -191,8 +179,9 @@ int main() std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif - sx1278 = - new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) diff --git a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp index bac40989bcbdf9c822dd2f61631024c4d54957c4..3b51df6cbdd75bcafe7f1c9148023db007e82714 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-mavlink.cpp @@ -109,17 +109,6 @@ void initBoard() rxen::low(); txen::low(); #endif - - GpioPin dio0_pin = dio0::getPin(); - GpioPin dio1_pin = dio1::getPin(); - GpioPin dio3_pin = dio3::getPin(); - - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_EDGE); } Mav* channel; @@ -193,7 +182,6 @@ int main() SX1278Lora::Error err; SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); #ifdef IS_EBYTE std::unique_ptr<SX1278::ISX1278Frontend> frontend( @@ -202,8 +190,9 @@ int main() std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif - sx1278 = - new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) diff --git a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp index 8bd407e8ef3121ab9fec97c8e860be2610dbeacb..85a2a75ea9544baea7fb6666dc621f0bbe77cbb1 100644 --- a/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp +++ b/src/tests/radio/sx1278/lora/test-sx1278-simple.cpp @@ -85,17 +85,6 @@ void initBoard() rxen::low(); txen::low(); #endif - - GpioPin dio0_pin = dio0::getPin(); - GpioPin dio1_pin = dio1::getPin(); - GpioPin dio3_pin = dio3::getPin(); - - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_EDGE); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_EDGE); } int main() @@ -112,7 +101,6 @@ int main() SX1278Lora::Error err; SPIBus bus(SX1278_SPI); - GpioPin cs = cs::getPin(); #ifdef IS_EBYTE std::unique_ptr<SX1278::ISX1278Frontend> frontend( @@ -121,8 +109,9 @@ int main() std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend()); #endif - sx1278 = - new SX1278Lora(bus, cs, SPI::ClockDivider::DIV_64, std::move(frontend)); + sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(), + dio3::getPin(), SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278...\n"); if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE) diff --git a/src/tests/radio/sx1278/sx1278-init.h b/src/tests/radio/sx1278/sx1278-init.h index 30cc3ae33d156038c7ff2713539990828fd4ada3..f5ff21857ce3a6f5226605e64a4f69c89af7fd3d 100644 --- a/src/tests/radio/sx1278/sx1278-init.h +++ b/src/tests/radio/sx1278/sx1278-init.h @@ -128,24 +128,6 @@ void initBoard() rxen::low(); txen::low(); #endif - -#ifdef SX1278_IRQ_DIO0 - miosix::GpioPin dio0_pin = dio0::getPin(); - enableExternalInterrupt(dio0_pin.getPort(), dio0_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); -#endif - -#ifdef SX1278_IRQ_DIO1 - miosix::GpioPin dio1_pin = dio1::getPin(); - enableExternalInterrupt(dio1_pin.getPort(), dio1_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); -#endif - -#ifdef SX1278_IRQ_DIO3 - miosix::GpioPin dio3_pin = dio3::getPin(); - enableExternalInterrupt(dio3_pin.getPort(), dio3_pin.getNumber(), - InterruptTrigger::RISING_FALLING_EDGE); -#endif } Boardcore::SPIBus sx1278_bus(SX1278_SPI); @@ -173,7 +155,8 @@ bool initRadio() Boardcore::SX1278Lora::Config config; Boardcore::SX1278Lora::Error err; - sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), + sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(), + dio1::getPin(), dio3::getPin(), Boardcore::SPI::ClockDivider::DIV_64, std::move(frontend)); @@ -190,9 +173,10 @@ bool initRadio() Boardcore::SX1278Fsk::Config config; Boardcore::SX1278Fsk::Error err; - sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), - Boardcore::SPI::ClockDivider::DIV_64, - std::move(frontend)); + sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(), + dio1::getPin(), dio3::getPin(), + Boardcore::SPI::ClockDivider::DIV_64, + std::move(frontend)); printf("\n[sx1278] Configuring sx1278 fsk...\n"); if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE)