diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp
index ae0e6f41ae36a2b43fec40d02a6cbc7232e1d1d5..2eaeafd5ca0b5f08e43fd22cdf8f43e2646d043a 100644
--- a/src/entrypoints/sx1278-serial.cpp
+++ b/src/entrypoints/sx1278-serial.cpp
@@ -94,7 +94,7 @@ using rxen                         = radio::rxEn;
 // #define SX1278_IS_EBYTE
 
 // Comment to use SX1278_2
-// #define SX1278_1
+#define SX1278_1
 
 #ifdef SX1278_1
 using cs   = miosix::radio1::cs;
@@ -239,11 +239,11 @@ int main()
 #elif defined SX1278_IS_SKYWARD433
     printf("[sx1278] Confuring Skyward 433 frontend...\n");
     std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
-              new Boardcore::Skyward433Frontend());
+        new Boardcore::Skyward433Frontend());
 #else
     printf("[sx1278] Confuring RA01 frontend...\n");
     std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
-         new Boardcore::RA01Frontend());
+        new Boardcore::RA01Frontend());
 #endif
 
 #ifdef SX1278_IS_LORA
@@ -266,12 +266,19 @@ int main()
     printf("\n[sx1278] Initialization complete!\n");
 #else
     // Run default configuration
-    Boardcore::SX1278Fsk::Config config;
+    Boardcore::SX1278Fsk::Config config = {
+              .freq_rf    = 434000000,
+              .freq_dev   = 50000,
+              .bitrate    = 48000,
+              .rx_bw      = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000,
+              .afc_bw     = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000,
+              .ocp        = 120,
+              .power      = 13,
+              .shaping    = Boardcore::SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0,
+              .dc_free    = Boardcore::SX1278Fsk::Config::DcFree::WHITENING,
+              .enable_crc = false};
     Boardcore::SX1278Fsk::Error err;
 
-    config.freq_rf    = 868000000;
-    config.enable_crc = false;
-
     sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(),
                                             dio1::getPin(), dio3::getPin(),
                                             Boardcore::SPI::ClockDivider::DIV_256,
@@ -280,7 +287,7 @@ int main()
     printf("\n[sx1278] Configuring sx1278 fsk...\n");
     if ((err = sx1278->init(config)) != Boardcore::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 false;
     }
diff --git a/src/shared/radio/SX1278/SX1278Common.cpp b/src/shared/radio/SX1278/SX1278Common.cpp
index a4cc12d11b023225a5504b94801a93956e9772fb..f779b37112587f8c968ac8695845337656da399b 100644
--- a/src/shared/radio/SX1278/SX1278Common.cpp
+++ b/src/shared/radio/SX1278/SX1278Common.cpp
@@ -45,6 +45,8 @@ void SX1278Common::handleDioIRQ()
     }
 }
 
+int SX1278Common::resetCount() { return reset_count; }
+
 void SX1278Common::enableIrqs()
 {
     enableExternalInterrupt(dio0, InterruptTrigger::RISING_EDGE);
@@ -59,16 +61,16 @@ void SX1278Common::disableIrqs()
     disableExternalInterrupt(dio3);
 }
 
-void SX1278Common::setDefaultMode(Mode mode, DioMapping mapping,
+void SX1278Common::setDefaultMode(Lock &guard, Mode mode, DioMapping mapping,
                                   InterruptTrigger dio1_trigger,
                                   bool tx_frontend, bool rx_frontend)
 {
-    miosix::Lock<miosix::FastMutex> lock(mutex);
-    enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
+    enterMode(guard, mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
 }
 
-ISX1278::IrqFlags SX1278Common::waitForIrq(LockMode &guard, IrqFlags set_irq,
-                                           IrqFlags reset_irq, bool unlock)
+SX1278Common::IrqFlags SX1278Common::waitForIrq(LockMode &guard,
+                                                IrqFlags set_irq,
+                                                IrqFlags reset_irq, bool unlock)
 {
     IrqFlags ret_irq = 0;
 
@@ -81,32 +83,39 @@ ISX1278::IrqFlags SX1278Common::waitForIrq(LockMode &guard, IrqFlags set_irq,
         }
 
         // Check that this hasn't already happened
-        if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
+        if ((ret_irq = checkForIrqAndReset(guard, set_irq, reset_irq)) != 0)
         {
             break;
         }
 
         if (!waitForIrqInner(guard, unlock))
         {
-            // TODO: Something bad happened, do something!
+            if (checkDeviceFailure(guard.parent()))
+            {
+                // Increment the reset count, to notify everybody
+                reset_count += 1;
+                reconfigure(guard.parent());
+            }
         }
 
-        // TODO: Check state of the device, and reset if needed!
+        // The device has failed, just quit.
+        // This also checks for invalidation after the line above
+        if (guard.wasDeviceInvalidated())
+        {
+            break;
+        }
 
         // Protect against sporadic IRQs
-    } while ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) == 0);
+    } while ((ret_irq = checkForIrqAndReset(guard, set_irq, reset_irq)) == 0);
 
     return ret_irq;
 }
 
-ISX1278::IrqFlags SX1278Common::waitForIrqBusy(LockMode &_guard,
-                                               IrqFlags set_irq,
-                                               IrqFlags reset_irq, int timeout)
+SX1278Common::IrqFlags SX1278Common::waitForIrqBusy(LockMode &guard,
+                                                    IrqFlags set_irq,
+                                                    IrqFlags reset_irq,
+                                                    int timeout)
 {
-    // Take a reference to a _guard to MAKE SURE that the mutex is locked, but
-    // otherwise don't do anything with it
-    (void)_guard;
-
     long long start  = miosix::getTick();
     IrqFlags ret_irq = 0;
 
@@ -119,7 +128,7 @@ ISX1278::IrqFlags SX1278Common::waitForIrqBusy(LockMode &_guard,
         for (unsigned int i = 0; i < 1000 / DELAY; i++)
         {
             // Check if some of the interrupts triggered
-            if ((ret_irq = checkForIrqAndReset(set_irq, reset_irq)) != 0)
+            if ((ret_irq = checkForIrqAndReset(guard, set_irq, reset_irq)) != 0)
             {
                 return ret_irq;
             }
@@ -166,14 +175,15 @@ bool SX1278Common::waitForIrqInner(LockMode &_guard, bool unlock)
     return result == miosix::TimedWaitResult::NoTimeout;
 }
 
-ISX1278::IrqFlags SX1278Common::checkForIrqAndReset(IrqFlags set_irq,
-                                                    IrqFlags reset_irq)
+SX1278Common::IrqFlags SX1278Common::checkForIrqAndReset(LockMode &guard,
+                                                         IrqFlags set_irq,
+                                                         IrqFlags reset_irq)
 {
-    IrqFlags cur_irq = getIrqFlags();
+    IrqFlags cur_irq = getIrqFlags(guard.parent());
     if (cur_irq & set_irq)
     {
         // Reset all of the interrupts we have detected
-        resetIrqFlags(cur_irq & set_irq);
+        resetIrqFlags(guard.parent(), cur_irq & set_irq);
     }
 
     return (cur_irq & set_irq) | (~cur_irq & reset_irq);
@@ -181,9 +191,15 @@ ISX1278::IrqFlags SX1278Common::checkForIrqAndReset(IrqFlags set_irq,
 
 ISX1278Frontend &SX1278Common::getFrontend() { return *frontend; }
 
-SPISlave &SX1278Common::getSpiSlave() { return slave; }
+SPISlave &SX1278Common::getSpiSlave(Lock &_guard)
+{
+    // This parameter is unused, and taken only for API purposes
+    (void)_guard;
+    return slave;
+}
 
-SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping,
+SX1278Common::DeviceState SX1278Common::lockMode(Lock &guard, Mode mode,
+                                                 DioMapping mapping,
                                                  InterruptTrigger dio1_trigger,
                                                  bool tx_frontend,
                                                  bool rx_frontend)
@@ -191,17 +207,17 @@ SX1278Common::DeviceState SX1278Common::lockMode(Mode mode, DioMapping mapping,
     // Store previous state
     DeviceState old_state = state;
 
-    enterMode(mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
+    enterMode(guard, mode, mapping, dio1_trigger, tx_frontend, rx_frontend);
     state.irq_wait_thread = nullptr;
 
     return old_state;
 }
 
-void SX1278Common::unlockMode(DeviceState old_state)
+void SX1278Common::unlockMode(Lock &guard, 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.dio1_trigger,
+    enterMode(guard, old_state.mode, old_state.mapping, old_state.dio1_trigger,
               old_state.is_tx_frontend_on, old_state.is_rx_frontend_on);
 }
 
@@ -209,7 +225,7 @@ void SX1278Common::lock() { mutex.lock(); }
 
 void SX1278Common::unlock() { mutex.unlock(); }
 
-void SX1278Common::enterMode(Mode mode, DioMapping mapping,
+void SX1278Common::enterMode(Lock &guard, Mode mode, DioMapping mapping,
                              InterruptTrigger dio1_trigger,
                              bool set_tx_frontend_on, bool set_rx_frontend_on)
 {
@@ -243,7 +259,7 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping,
 
     if (mode != state.mode)
     {
-        setMode(mode);
+        setMode(guard, mode);
         state.mode = mode;
     }
 
@@ -257,7 +273,7 @@ void SX1278Common::enterMode(Mode mode, DioMapping mapping,
     // Finally setup DIO mapping
     if (mapping != state.mapping)
     {
-        setMapping(mapping);
+        setMapping(guard, mapping);
         state.mapping = mapping;
     }
 }
diff --git a/src/shared/radio/SX1278/SX1278Common.h b/src/shared/radio/SX1278/SX1278Common.h
index 30122331fc437aecd57faf5f37de482862e9c2c8..9cbc92b6aac7513f8571032d239d6e1bb10361a1 100644
--- a/src/shared/radio/SX1278/SX1278Common.h
+++ b/src/shared/radio/SX1278/SX1278Common.h
@@ -40,44 +40,6 @@ namespace SX1278
 
 using DioMapping = RegDioMapping::Mapping;
 
-/**
- * @brief Shared interface between all SX1278 drivers
- */
-class ISX1278 : public Transceiver
-{
-public:
-    /**
-     * @brief Get the RSSI in dBm, during last packet receive.
-     */
-    virtual float getLastRxRssi() = 0;
-
-    /**
-     * @brief Get the frequency error index in Hz, during last packet receive
-     * (NaN if not available).
-     */
-    virtual float getLastRxFei() { return std::nanf(""); }
-
-    /**
-     * @brief Get the signal to noise ratio, during last packet receive (NaN if
-     * not available).
-     */
-    virtual float getLastRxSnr() { return std::nanf(""); }
-
-protected:
-    /*
-     * Stuff used internally by SX1278Common
-     */
-
-    using IrqFlags = int;
-    using Mode     = int;
-
-    virtual void setMode(Mode mode)             = 0;
-    virtual void setMapping(DioMapping mapping) = 0;
-
-    virtual IrqFlags getIrqFlags()             = 0;
-    virtual void resetIrqFlags(IrqFlags flags) = 0;
-};
-
 /**
  * @brief Shared interface between all SX1278 frontends
  */
@@ -100,8 +62,12 @@ public:
     virtual void disableTx() = 0;
 };
 
-class SX1278Common : public ISX1278
+class SX1278Common : public Transceiver
 {
+protected:
+    using IrqFlags = int;
+    using Mode     = int;
+
 private:
     struct DeviceState
     {
@@ -128,6 +94,28 @@ public:
      */
     void handleDioIRQ();
 
+    /**
+     * @brief Get the number of times this device has been reset.
+     */
+    int resetCount();
+
+    /**
+     * @brief Get the RSSI in dBm, during last packet receive.
+     */
+    virtual float getLastRxRssi() = 0;
+
+    /**
+     * @brief Get the frequency error index in Hz, during last packet receive
+     * (NaN if not available).
+     */
+    virtual float getLastRxFei() { return std::nanf(""); }
+
+    /**
+     * @brief Get the signal to noise ratio, during last packet receive (NaN if
+     * not available).
+     */
+    virtual float getLastRxSnr() { return std::nanf(""); }
+
 protected:
     explicit SX1278Common(SPIBus &bus, miosix::GpioPin cs, miosix::GpioPin dio0,
                           miosix::GpioPin dio1, miosix::GpioPin dio3,
@@ -161,22 +149,44 @@ protected:
     class LockMode
     {
     public:
-        LockMode(SX1278Common &driver, Lock &lock, Mode mode,
+        LockMode(SX1278Common &driver, Lock &guard, Mode mode,
                  DioMapping mapping, InterruptTrigger dio1_trigger,
                  bool set_tx_frontend_on = false,
                  bool set_rx_frontend_on = false)
-            : driver(driver), lock(lock)
+            : driver(driver), guard(guard), reset_count(driver.reset_count)
         {
             // cppcheck-suppress useInitializationList
-            old_state = driver.lockMode(mode, mapping, dio1_trigger,
+            old_state = driver.lockMode(guard, mode, mapping, dio1_trigger,
                                         set_tx_frontend_on, set_rx_frontend_on);
         }
 
-        ~LockMode() { driver.unlockMode(old_state); }
+        ~LockMode()
+        {
+            // Restore device mode ONLY if the lock is valid!
+            if (!wasDeviceInvalidated())
+            {
+                driver.unlockMode(guard, old_state);
+            }
+        }
+
+        /**
+         * @brief Returns the parent simple lock.
+         */
+        Lock &parent() { return guard; }
+
+        /**
+         * @brief Returns true if this LockMode is still valid, and the device
+         * hasn't failed while holding the lock.
+         */
+        bool wasDeviceInvalidated()
+        {
+            return driver.reset_count != reset_count;
+        }
 
     private:
         SX1278Common &driver;
-        Lock &lock;
+        Lock &guard;
+        int reset_count;
         DeviceState old_state;
     };
 
@@ -185,7 +195,7 @@ protected:
      *
      * WARNING: This will lock the mutex.
      */
-    void setDefaultMode(Mode mode, DioMapping mapping,
+    void setDefaultMode(Lock &guard, Mode mode, DioMapping mapping,
                         InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
                         bool set_rx_frontend_on);
 
@@ -214,11 +224,22 @@ protected:
      * @return Mask containing all triggered interrupts (both rising and
      * falling)
      */
-    IrqFlags checkForIrqAndReset(IrqFlags set_irq, IrqFlags reset_irq);
+    IrqFlags checkForIrqAndReset(LockMode &guard, IrqFlags set_irq,
+                                 IrqFlags reset_irq);
 
     ISX1278Frontend &getFrontend();
 
-    SPISlave &getSpiSlave();
+    SPISlave &getSpiSlave(Lock &guard);
+
+protected:
+    virtual bool checkDeviceFailure(Lock &guard) = 0;
+    virtual void reconfigure(Lock &guard)        = 0;
+
+    virtual void setMode(Lock &guard, Mode mode)             = 0;
+    virtual void setMapping(Lock &guard, DioMapping mapping) = 0;
+
+    virtual IrqFlags getIrqFlags(Lock &guard)               = 0;
+    virtual void resetIrqFlags(Lock &guard, IrqFlags flags) = 0;
 
 private:
     void enableIrqs();
@@ -226,16 +247,17 @@ private:
 
     bool waitForIrqInner(LockMode &guard, bool unlock);
 
-    DeviceState lockMode(Mode mode, DioMapping mapping,
+    DeviceState lockMode(Lock &guard, Mode mode, DioMapping mapping,
                          InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
                          bool set_rx_frontend_on);
-    void unlockMode(DeviceState old_state);
+    void unlockMode(Lock &guard, DeviceState old_state);
 
     void lock();
     void unlock();
 
-    void enterMode(Mode mode, DioMapping mapping, InterruptTrigger dio1_trigger,
-                   bool set_tx_frontend_on, bool set_rx_frontend_on);
+    void enterMode(Lock &guard, Mode mode, DioMapping mapping,
+                   InterruptTrigger dio1_trigger, bool set_tx_frontend_on,
+                   bool set_rx_frontend_on);
 
     miosix::FastMutex mutex;
     DeviceState state;
@@ -244,6 +266,7 @@ private:
     miosix::GpioPin dio1;
     miosix::GpioPin dio3;
     std::unique_ptr<ISX1278Frontend> frontend;
+    int reset_count = 0;
 };
 
 }  // namespace SX1278
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index ddd8668755e944e4baf892189052e9d0d2d21183..317d779c125ce2649aafed75006381518e009aee 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -50,9 +50,28 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
         return Error::BAD_VALUE;
     }
 
-    Error err;
-    if ((err = configure(config)) != Error::NONE)
-        return err;
+    // Check that the configuration is actually valid
+    bool pa_boost = getFrontend().isOnPaBoost();
+    int min_power = pa_boost ? 2 : 0;
+    int max_power = getFrontend().maxInPower();
+
+    (void)pa_boost;
+    (void)min_power;
+    (void)max_power;
+
+    assert(config.power >= min_power && config.power <= max_power &&
+           "[sx1278] Configured power invalid for given frontend!");
+    assert(((config.ocp >= 0 && config.ocp <= 120) ||
+            (config.ocp >= 130 && config.ocp <= 240)) &&
+           "[sx1278] Invalid ocp!");
+    assert(config.freq_dev >= MIN_FREQ_DEV && config.freq_dev <= MAX_FREQ_DEV &&
+           "[sx1278] Invalid freq_dev!");
+    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
+           "[sx1278] Invalid freq_rf");
+
+    Lock guard(*this);
+    this->config = config;
+    reconfigure(guard);
 
     return Error::NONE;
 }
@@ -60,7 +79,7 @@ SX1278Fsk::Error SX1278Fsk::init(const Config &config)
 bool SX1278Fsk::checkVersion()
 {
     Lock guard(*this);
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     uint8_t version = spi.readRegister(REG_VERSION);
     TRACE("[sx1278] Chip id: %d\n", version);
@@ -68,37 +87,22 @@ bool SX1278Fsk::checkVersion()
     return version == 0x12;
 }
 
-SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
+void SX1278Fsk::reconfigure(Lock &guard)
 {
-    // Check that the configuration is actually valid
     bool pa_boost = getFrontend().isOnPaBoost();
     int min_power = pa_boost ? 2 : 0;
     int max_power = getFrontend().maxInPower();
 
-    assert(config.power >= min_power && config.power <= max_power &&
-           "[sx1278] Configured power invalid for given frontend!");
-    assert(((config.ocp >= 0 && config.ocp <= 120) ||
-            (config.ocp >= 130 && config.ocp <= 240)) &&
-           "[sx1278] Invalid ocp!");
-    assert(config.freq_dev >= MIN_FREQ_DEV && config.freq_dev <= MAX_FREQ_DEV &&
-           "[sx1278] Invalid freq_dev!");
-    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
-           "[sx1278] Invalid freq_rf");
-
     // First make sure the device is in fsk and in standby
-    enterFskMode();
+    enterFskMode(guard);
+    // After this the device will already be in STANDBY
 
     // Set default mode to standby, that way we reset the fifo every time we
     // enter receive
-    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+    setDefaultMode(guard, 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,
-                        InterruptTrigger::RISING_EDGE);
-
     // This code is unreliable so it got commented out, the datasheet states
     // that this triggers during a successful state transition, but for some
     // reason, this isn't always the case, and can lead to random failures of
@@ -121,10 +125,10 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
     RegPacketConfig1::DcFree dc_free =
         static_cast<RegPacketConfig1::DcFree>(config.dc_free);
 
-    crc_enabled = config.enable_crc;
+    bool crc_enabled = config.enable_crc;
 
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard));
 
         // Setup bitrate
         uint16_t bitrate_raw = FXOSC / bitrate;
@@ -245,8 +249,6 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
         spi.writeRegister(REG_NODE_ADRS, 0x00);
         spi.writeRegister(REG_BROADCAST_ADRS, 0x00);
     }
-
-    return Error::NONE;
 }
 
 ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
@@ -273,17 +275,26 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
         flags = waitForIrq(guard_mode,
                            RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY,
                            0, true);
-        if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
+
+        if (guard_mode.wasDeviceInvalidated())
+        {
+            // The device was invalidated, just do a quick return, nothing else
+            // matters
+            return -1;
+        }
+
+        if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && config.enable_crc)
         {
-            crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
+            crc_ok =
+                checkForIrqAndReset(guard_mode, RegIrqFlags::CRC_OK, 0) != 0;
         }
 
         // Record RSSI here, it's where it is the most accurate
-        last_rx_rssi = getRssi();
+        last_rx_rssi = getRssi(guard_mode.parent());
 
         // Now first packet bit
         {
-            SPITransaction spi(getSpiSlave());
+            SPITransaction spi(getSpiSlave(guard_mode.parent()));
             len = spi.readRegister(REG_FIFO);
 
             int read_size = std::min((int)len, FIFO_LEN / 2);
@@ -300,12 +311,21 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
             flags = waitForIrq(
                 guard_mode,
                 RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0);
-            if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
+
+            if (guard_mode.wasDeviceInvalidated())
+            {
+                // The device was invalidated, just do a quick return, nothing
+                // else matters
+                return -1;
+            }
+
+            if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && config.enable_crc)
             {
-                crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
+                crc_ok = checkForIrqAndReset(guard_mode, RegIrqFlags::CRC_OK,
+                                             0) != 0;
             }
 
-            SPITransaction spi(getSpiSlave());
+            SPITransaction spi(getSpiSlave(guard_mode.parent()));
 
             int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
             spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
@@ -316,7 +336,7 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
         // For some reason this sometimes happen?
     } while (len == 0);
 
-    if (len > max_len || (!crc_ok && crc_enabled))
+    if (len > max_len || (!crc_ok && config.enable_crc))
     {
         return -1;
     }
@@ -341,9 +361,16 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
 
     waitForIrq(guard_mode, RegIrqFlags::TX_READY, 0);
 
+    if (guard_mode.wasDeviceInvalidated())
+    {
+        // The device was invalidated, just do a quick return, nothing else
+        // matters
+        return -1;
+    }
+
     // Send first segment
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard_mode.parent()));
 
         spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len));
 
@@ -360,7 +387,14 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
         // Wait for FIFO_LEVEL to go down
         waitForIrq(guard_mode, 0, RegIrqFlags::FIFO_LEVEL);
 
-        SPITransaction spi(getSpiSlave());
+        if (guard_mode.wasDeviceInvalidated())
+        {
+            // The device was invalidated, just do a quick return, nothing else
+            // matters
+            return -1;
+        }
+
+        SPITransaction spi(getSpiSlave(guard_mode.parent()));
 
         int write_size = std::min((int)len, FIFO_LEN / 2);
         spi.writeRegisters(REG_FIFO, pkt, write_size);
@@ -373,6 +407,13 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
     // Wait for packet sent
     waitForIrq(guard_mode, RegIrqFlags::PACKET_SENT, 0);
 
+    if (guard_mode.wasDeviceInvalidated())
+    {
+        // The device was invalidated, just do a quick return, nothing else
+        // matters
+        return -1;
+    }
+
     last_tx = now();
     return true;
 }
@@ -380,7 +421,7 @@ bool SX1278Fsk::send(uint8_t *pkt, size_t len)
 float SX1278Fsk::getLastRxFei()
 {
     Lock guard(*this);
-    return getFei();
+    return getFei(guard);
 }
 
 float SX1278Fsk::getLastRxRssi() { return last_rx_rssi; }
@@ -388,13 +429,12 @@ float SX1278Fsk::getLastRxRssi() { return last_rx_rssi; }
 float SX1278Fsk::getCurRssi()
 {
     Lock guard(*this);
-    return getRssi();
+    return getRssi(guard);
 }
 
-void SX1278Fsk::enterFskMode()
+void SX1278Fsk::enterFskMode(Lock &guard)
 {
-    Lock guard(*this);
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     // First enter Fsk sleep
     spi.writeRegister(REG_OP_MODE,
@@ -420,13 +460,26 @@ void SX1278Fsk::rateLimitTx()
     }
 }
 
-ISX1278::IrqFlags SX1278Fsk::getIrqFlags()
+bool SX1278Fsk::checkDeviceFailure(Lock &guard)
+{
+    // This check will be performed sometimes when hte IRQ timeout ends
+    // In such cases the device will NEVER be in standby, even if we keep it at
+    // standby between operations. So, if the device IS in standby in that case,
+    // then something must have gone wrong
+
+    SPITransaction spi(getSpiSlave(guard));
+    uint8_t mode = spi.readRegister(REG_OP_MODE);
+
+    return (mode & 0b111) == RegOpMode::Mode::MODE_STDBY;
+}
+
+SX1278Fsk::IrqFlags SX1278Fsk::getIrqFlags(Lock &guard)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     return spi.readRegister16(REG_IRQ_FLAGS_1);
 }
 
-void SX1278Fsk::resetIrqFlags(IrqFlags flags)
+void SX1278Fsk::resetIrqFlags(Lock &guard, IrqFlags flags)
 {
     // Mask only resettable flags
     flags &= RegIrqFlags::RSSI | RegIrqFlags::PREAMBLE_DETECT |
@@ -435,38 +488,38 @@ void SX1278Fsk::resetIrqFlags(IrqFlags flags)
 
     if (flags != 0)
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard));
         spi.writeRegister16(REG_IRQ_FLAGS_1, flags);
     }
 }
 
-float SX1278Fsk::getRssi()
+float SX1278Fsk::getRssi(Lock &guard)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE);
     return static_cast<float>(rssi_raw) * -0.5f;
 }
 
-float SX1278Fsk::getFei()
+float SX1278Fsk::getFei(Lock &guard)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB);
     return static_cast<float>(fei_raw) * FSTEP;
 }
 
-void SX1278Fsk::setMode(Mode mode)
+void SX1278Fsk::setMode(Lock &guard, Mode mode)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     spi.writeRegister(REG_OP_MODE,
                       RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true,
                                       RegOpMode::MODULATION_TYPE_FSK));
 }
 
-void SX1278Fsk::setMapping(SX1278::DioMapping mapping)
+void SX1278Fsk::setMapping(Lock &guard, SX1278::DioMapping mapping)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
 }
 
diff --git a/src/shared/radio/SX1278/SX1278Fsk.h b/src/shared/radio/SX1278/SX1278Fsk.h
index b67f6c202eb45fa1a5425d4cf2b4424d011b1b53..4c5754de9f46dad3c60ca747fb486cf1ecfe5424 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.h
+++ b/src/shared/radio/SX1278/SX1278Fsk.h
@@ -140,8 +140,7 @@ public:
                        SPI::ClockDivider clock_divider,
                        std::unique_ptr<SX1278::ISX1278Frontend> frontend)
         : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
-                       std::move(frontend)),
-          crc_enabled(false)
+                       std::move(frontend))
     {
     }
 
@@ -155,11 +154,6 @@ public:
      */
     bool checkVersion();
 
-    /**
-     * @brief Configure this device on the fly.
-     */
-    [[nodiscard]] virtual Error configure(const Config &config);
-
     /**
      * @brief Wait until a new packet is received.
      *
@@ -196,22 +190,26 @@ public:
     float getLastRxFei() override;
 
 private:
-    void enterFskMode();
+    void enterFskMode(Lock &guard);
 
     void rateLimitTx();
 
-    IrqFlags getIrqFlags() override;
-    void resetIrqFlags(IrqFlags flags) override;
+    bool checkDeviceFailure(Lock &lock) override;
+    void reconfigure(Lock &lock) override;
 
-    float getRssi();
-    float getFei();
+    IrqFlags getIrqFlags(Lock &lock) override;
+    void resetIrqFlags(Lock &lock, IrqFlags flags) override;
 
-    void setMode(Mode mode) override;
-    void setMapping(SX1278::DioMapping mapping) override;
+    float getRssi(Lock &lock);
+    float getFei(Lock &lock);
+
+    void setMode(Lock &lock, Mode mode) override;
+    void setMapping(Lock &lock, SX1278::DioMapping mapping) override;
 
-    bool crc_enabled;
     long long last_tx  = 0;
     float last_rx_rssi = 0.0f;
+
+    Config config;
     PrintLogger logger = Logging::getLogger("sx1278");
 };
 
diff --git a/src/shared/radio/SX1278/SX1278Lora.cpp b/src/shared/radio/SX1278/SX1278Lora.cpp
index 6062b50b231dbd2437207dbedd5a04c19fb04db4..11ef83f232d3dca0cab612bf549a16204a2b6a33 100644
--- a/src/shared/radio/SX1278/SX1278Lora.cpp
+++ b/src/shared/radio/SX1278/SX1278Lora.cpp
@@ -139,9 +139,26 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
         return Error::BAD_VALUE;
     }
 
-    Error err;
-    if ((err = configure(config)) != Error::NONE)
-        return err;
+    // Check that the configuration is actually valid
+    bool pa_boost = getFrontend().isOnPaBoost();
+    int min_power = pa_boost ? 2 : 0;
+    int max_power = getFrontend().maxInPower();
+
+    (void)pa_boost;
+    (void)min_power;
+    (void)max_power;
+
+    assert(config.power >= min_power && config.power <= max_power &&
+           "[sx1278] Configured power invalid for given frontend!");
+    assert(((config.ocp >= 0 && config.ocp <= 120) ||
+            (config.ocp >= 130 && config.ocp <= 240)) &&
+           "[sx1278] Invalid ocp!");
+    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
+           "[sx1278] Invalid freq_rf");
+
+    Lock guard(*this);
+    this->config = config;
+    reconfigure(guard);
 
     return Error::NONE;
 }
@@ -149,7 +166,7 @@ SX1278Lora::Error SX1278Lora::init(const Config &config)
 bool SX1278Lora::checkVersion()
 {
     Lock guard(*this);
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     uint8_t version = spi.readRegister(REG_VERSION);
     TRACE("[sx1278] Chip id: %d\n", version);
@@ -157,33 +174,20 @@ bool SX1278Lora::checkVersion()
     return version == 0x12;
 }
 
-SX1278Lora::Error SX1278Lora::configure(const Config &config)
+void SX1278Lora::reconfigure(Lock &guard)
 {
     // Check that the configuration is actually valid
     bool pa_boost = getFrontend().isOnPaBoost();
     int min_power = pa_boost ? 2 : 0;
     int max_power = getFrontend().maxInPower();
 
-    assert(config.power >= min_power && config.power <= max_power &&
-           "[sx1278] Configured power invalid for given frontend!");
-    assert(((config.ocp >= 0 && config.ocp <= 120) ||
-            (config.ocp >= 130 && config.ocp <= 240)) &&
-           "[sx1278] Invalid ocp!");
-    assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
-           "[sx1278] Invalid freq_rf");
-
     // First make sure the device is in lora mode and in standby
-    enterLoraMode();
+    enterLoraMode(guard);
 
     // Then make sure the device remains in standby and not in sleep
-    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING,
+    setDefaultMode(guard, 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,
-                        InterruptTrigger::RISING_EDGE);
-
     RegModemConfig1::Bw bw = static_cast<RegModemConfig1::Bw>(config.bandwidth);
     RegModemConfig1::Cr cr =
         static_cast<RegModemConfig1::Cr>(config.coding_rate);
@@ -205,10 +209,10 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
     ErrataRegistersValues errata_values =
         ErrataRegistersValues::calculate(bw, freq_rf);
 
-    crc_enabled = config.enable_crc;
+    bool crc_enabled = config.enable_crc;
 
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard));
 
         // Setup FIFO sections
         spi.writeRegister(REG_FIFO_TX_BASE_ADDR, FIFO_TX_BASE_ADDR);
@@ -286,8 +290,6 @@ SX1278Lora::Error SX1278Lora::configure(const Config &config)
         if (errata_values.reg_if_freq_2 != -1)
             spi.writeRegister(REG_IF_FREQ_2, errata_values.reg_if_freq_2);
     }
-
-    return Error::NONE;
 }
 
 ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len)
@@ -302,19 +304,27 @@ ssize_t SX1278Lora::receive(uint8_t *pkt, size_t max_len)
 
     waitForIrq(mode_guard, RegIrqFlags::RX_DONE, 0, true);
 
+    if (mode_guard.wasDeviceInvalidated())
+    {
+        // The device was invalidated, just do a quick return, nothing else
+        // matters
+        return -1;
+    }
+
     uint8_t len;
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(mode_guard.parent()));
         len = spi.readRegister(REG_RX_NB_BYTES);
     }
 
     if (len > max_len ||
-        (crc_enabled &&
-         checkForIrqAndReset(RegIrqFlags::PAYLOAD_CRC_ERROR, 0) != 0))
+        (config.enable_crc &&
+         checkForIrqAndReset(mode_guard, RegIrqFlags::PAYLOAD_CRC_ERROR, 0) !=
+             0))
         return -1;
 
     // Finally read the contents of the fifo
-    readFifo(FIFO_RX_BASE_ADDR, pkt, len);
+    readFifo(mode_guard.parent(), FIFO_RX_BASE_ADDR, pkt, len);
     return len;
 }
 
@@ -326,12 +336,13 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len)
     Lock guard(*this);
 
     {
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard));
 
         spi.writeRegister(REG_PAYLOAD_LENGTH, len);
-        writeFifo(FIFO_TX_BASE_ADDR, pkt, len);
     }
 
+    writeFifo(guard, FIFO_TX_BASE_ADDR, pkt, len);
+
     {
         // Now enter in mode TX to send the packet
         LockMode mode_guard(*this, guard, RegOpMode::MODE_TX,
@@ -340,6 +351,13 @@ bool SX1278Lora::send(uint8_t *pkt, size_t len)
 
         // Wait for the transmission to end
         waitForIrq(mode_guard, RegIrqFlags::TX_DONE, 0);
+
+        if (mode_guard.wasDeviceInvalidated())
+        {
+            // The device was invalidated, just do a quick return, nothing else
+            // matters
+            return -1;
+        }
     }
 
     return true;
@@ -350,7 +368,7 @@ float SX1278Lora::getLastRxRssi()
     float rssi;
     {
         Lock guard(*this);
-        SPITransaction spi(getSpiSlave());
+        SPITransaction spi(getSpiSlave(guard));
         rssi =
             static_cast<float>(spi.readRegister(REG_PKT_RSSI_VALUE)) - 164.0f;
     }
@@ -366,16 +384,15 @@ float SX1278Lora::getLastRxRssi()
 float SX1278Lora::getLastRxSnr()
 {
     Lock guard(*this);
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     return static_cast<float>(
                static_cast<int8_t>(spi.readRegister(REG_PKT_SNR_VALUE))) /
            4.0f;
 }
 
-void SX1278Lora::enterLoraMode()
+void SX1278Lora::enterLoraMode(Lock &guard)
 {
-    Lock guard(*this);
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     // First enter LoRa sleep
     spi.writeRegister(REG_OP_MODE,
@@ -388,45 +405,48 @@ void SX1278Lora::enterLoraMode()
     miosix::Thread::sleep(1);
 }
 
-void SX1278Lora::readFifo(uint8_t addr, uint8_t *dst, uint8_t size)
+void SX1278Lora::readFifo(Lock &guard, uint8_t addr, uint8_t *dst, uint8_t size)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
     spi.readRegisters(REG_FIFO, dst, size);
 }
 
-void SX1278Lora::writeFifo(uint8_t addr, uint8_t *src, uint8_t size)
+void SX1278Lora::writeFifo(Lock &guard, uint8_t addr, uint8_t *src,
+                           uint8_t size)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     spi.writeRegister(REG_FIFO_ADDR_PTR, addr);
     spi.writeRegisters(REG_FIFO, src, size);
 }
 
-ISX1278::IrqFlags SX1278Lora::getIrqFlags()
+bool SX1278Lora::checkDeviceFailure(Lock &guard) { return false; }
+
+SX1278Common::IrqFlags SX1278Lora::getIrqFlags(Lock &guard)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     return spi.readRegister(REG_IRQ_FLAGS);
 }
 
-void SX1278Lora::resetIrqFlags(IrqFlags flags)
+void SX1278Lora::resetIrqFlags(Lock &guard, IrqFlags flags)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     // Register is write clear
     spi.writeRegister(REG_IRQ_FLAGS, flags);
 }
 
-void SX1278Lora::setMode(ISX1278::Mode mode)
+void SX1278Lora::setMode(Lock &guard, SX1278Common::Mode mode)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
 
     spi.writeRegister(
         REG_OP_MODE,
         RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true, false));
 }
 
-void SX1278Lora::setMapping(SX1278::DioMapping mapping)
+void SX1278Lora::setMapping(Lock &guard, SX1278::DioMapping mapping)
 {
-    SPITransaction spi(getSpiSlave());
+    SPITransaction spi(getSpiSlave(guard));
     spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
 }
 
diff --git a/src/shared/radio/SX1278/SX1278Lora.h b/src/shared/radio/SX1278/SX1278Lora.h
index c30bdf41f72962659748fca95b292272d6ca32b8..9cf025218ad3911b4815ee9d03aeaaa47d7fbf36 100644
--- a/src/shared/radio/SX1278/SX1278Lora.h
+++ b/src/shared/radio/SX1278/SX1278Lora.h
@@ -141,8 +141,7 @@ public:
                         SPI::ClockDivider clock_divider,
                         std::unique_ptr<SX1278::ISX1278Frontend> frontend)
         : SX1278Common(bus, cs, dio0, dio1, dio3, clock_divider,
-                       std::move(frontend)),
-          crc_enabled(false)
+                       std::move(frontend))
     {
     }
 
@@ -192,20 +191,21 @@ public:
     float getLastRxSnr() override;
 
 private:
-    void enterLoraMode();
+    void enterLoraMode(Lock &lock);
 
-    void readFifo(uint8_t addr, uint8_t *dst, uint8_t size);
-    void writeFifo(uint8_t addr, uint8_t *src, uint8_t size);
+    void readFifo(Lock &guard, uint8_t addr, uint8_t *dst, uint8_t size);
+    void writeFifo(Lock &guard, uint8_t addr, uint8_t *src, uint8_t size);
 
-    IrqFlags getIrqFlags() override;
-    void resetIrqFlags(IrqFlags flags) override;
+    bool checkDeviceFailure(Lock &guard) override;
+    void reconfigure(Lock &guard) override;
 
-    void setMode(Mode mode) override;
-    void setMapping(SX1278::DioMapping mapping) override;
+    IrqFlags getIrqFlags(Lock &guard) override;
+    void resetIrqFlags(Lock &guard, IrqFlags flags) override;
 
-    void setFreqRF(int freq_rf);
+    void setMode(Lock &guard, Mode mode) override;
+    void setMapping(Lock &guard, SX1278::DioMapping mapping) override;
 
-    bool crc_enabled;
+    Config config;
 };
 
 }  // namespace Boardcore