diff --git a/src/shared/radio/SX1278/SX1278Defs.h b/src/shared/radio/SX1278/SX1278Defs.h
index b674d59d24de0bad0b9c3fada6469cc16ec931fd..ee5e4ea17ca6cb373adbb40c97a46fa07862403d 100644
--- a/src/shared/radio/SX1278/SX1278Defs.h
+++ b/src/shared/radio/SX1278/SX1278Defs.h
@@ -230,7 +230,7 @@ inline constexpr uint8_t make(bool rx_trigger_rssi_interrupt,
                               bool restart_rx_on_collision)
 {
     return (rx_trigger_rssi_interrupt ? 0b001 : 0) |
-           (rx_trigger_preable_detect ? 0b110 << 1 : 0) |
+           (rx_trigger_preable_detect ? 0b110 : 0) |
            (agc_auto_on ? 1 << 3 : 0) | (afc_auto_on ? 1 << 4 : 0) |
            (restart_rx_with_pll_lock ? 1 << 5 : 0) |
            (restart_rx_without_pll_lock ? 1 << 6 : 0) |
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index 9179b9aaca63787c47b33445f563b38708d9e77c..0677a3edef766ef4b56e53e24e345108f98e4cb8 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -74,8 +74,8 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
     setDefaultMode(RegOpMode::MODE_SLEEP, DEFAULT_MAPPING, false, false);
     miosix::Thread::sleep(1);
 
-    // Make sure the device remains in standby and not in sleep
-    setDefaultMode(RegOpMode::MODE_STDBY, DEFAULT_MAPPING, false, false);
+    // Make sure the device remains in RX and not in sleep
+    setDefaultMode(RegOpMode::MODE_RX, DEFAULT_MAPPING, false, false);
     miosix::Thread::sleep(1);
 
     // Lock the bus
@@ -142,6 +142,9 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
         spi.writeRegister(REG_SYNC_VALUE_1, 0x12);
         spi.writeRegister(REG_SYNC_VALUE_2, 0xad);
 
+        // Set preamble length
+        spi.writeRegister16(REG_PREAMBLE_MSB, 2);
+
         // Setup shaping
         spi.writeRegister(REG_PA_RAMP,
                           RegPaRamp::make(RegPaRamp::PA_RAMP_US_40, shaping));
@@ -176,7 +179,6 @@ SX1278Fsk::Error SX1278Fsk::configure(const Config &config)
         }
 
         // Setup other registers
-        spi.writeRegister16(REG_PREAMBLE_MSB, 2);
 
         spi.writeRegister(
             REG_RX_CONFIG,
diff --git a/src/tests/radio/sx1278/gui/GUI.h b/src/tests/radio/sx1278/gui/GUI.h
index d42aa0125b80a9b25da95fbcc428a2be535dc6a1..9f317e8dfa9a0f0113d3b703d90a3eec1f5a49a3 100644
--- a/src/tests/radio/sx1278/gui/GUI.h
+++ b/src/tests/radio/sx1278/gui/GUI.h
@@ -39,6 +39,16 @@ std::string format_link_speed(size_t value)
         return fmt::format("{} b/s", value);
 }
 
+std::string format_frequency(size_t value)
+{
+    if (value > 1000000)
+        return fmt::format("{:.2f} MHz", static_cast<float>(value) / 1000000);
+    else if (value > 1000)
+        return fmt::format("{:.2f} kHz", static_cast<float>(value) / 1000);
+    else
+        return fmt::format("{} Hz", value);
+}
+
 class StatsScreen
 {
 public:
@@ -91,9 +101,9 @@ public:
         root.addView(&lbl_tx_data, 0.1);
         root.addView(&tx_data, 0.4);
         root.addView(&lbl_rx_data, 0.1);
-        root.addView(&rx_data, 0.8);
+        root.addView(&rx_data, 0.6);
         root.addView(&lbl_misc_data, 0.1);
-        root.addView(&misc_data, 0.2);
+        root.addView(&misc_data, 0.6);
     }
 
     void updateReady()
@@ -112,7 +122,7 @@ public:
         corrupted_count.setText(fmt::format("{}", stats.corrupted_count));
 
         rssi.setText(fmt::format("{} dBm", stats.rssi));
-        fei.setText(fmt::format("{} Hz", stats.fei));
+        fei.setText(format_frequency(stats.fei));
         snr.setText(fmt::format("{}", stats.snr));
     }
 
diff --git a/src/tests/radio/sx1278/sx1278-init.h b/src/tests/radio/sx1278/sx1278-init.h
index 75672862a91faf564ff326b3c5da491e81e2f6b0..2ed08f3aff834c08925c045e2f893387ce95a5e1 100644
--- a/src/tests/radio/sx1278/sx1278-init.h
+++ b/src/tests/radio/sx1278/sx1278-init.h
@@ -39,7 +39,7 @@
 // Uncomment the following line to enable Ebyte module
 // #define SX1278_IS_EBYTE
 // Uncomment the following line to ebable Skyward433 module
-#define SX1278_IS_SKYWARD433
+// #define SX1278_IS_SKYWARD433
 
 using cs   = miosix::peripherals::ra01::pc13::cs;
 using dio0 = miosix::peripherals::ra01::pc13::dio0;
@@ -75,8 +75,8 @@ using sck  = miosix::radio::sck;
 using miso = miosix::radio::miso;
 using mosi = miosix::radio::mosi;
 
-using txen = miosix::radio::txEn;
-using rxen = miosix::radio::rxEn;
+using txen                         = miosix::radio::txEn;
+using rxen                         = miosix::radio::rxEn;
 
 #define SX1278_SPI SPI4
 
@@ -191,8 +191,8 @@ bool initRadio()
     Boardcore::SX1278Fsk::Error err;
 
     sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(),
-                                            Boardcore::SPI::ClockDivider::DIV_64,
-                                            std::move(frontend));
+                                      Boardcore::SPI::ClockDivider::DIV_64,
+                                      std::move(frontend));
 
     printf("\n[sx1278] Configuring sx1278 fsk...\n");
     if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE)
@@ -206,4 +206,4 @@ bool initRadio()
 #endif
 
     return true;
-}
\ No newline at end of file
+}
diff --git a/src/tests/radio/sx1278/test-sx1278-bench.cpp b/src/tests/radio/sx1278/test-sx1278-bench.cpp
index ca8a8454ed1bda520671872953aaedf1c26adee9..a68dcbff56e4863a7abbd9ddf96c29da37d1547e 100644
--- a/src/tests/radio/sx1278/test-sx1278-bench.cpp
+++ b/src/tests/radio/sx1278/test-sx1278-bench.cpp
@@ -20,14 +20,14 @@
  * THE SOFTWARE.
  */
 
-#include "sx1278-init.h"
-
 #include <drivers/timer/TimestampTimer.h>
 #include <miosix.h>
 #include <utils/MovingAverage.h>
 
 #include <thread>
 
+#include "sx1278-init.h"
+
 using namespace Boardcore;
 using namespace miosix;
 
@@ -166,4 +166,17 @@ void spawnThreads()
     std::thread send([]() { sendLoop(); });
     send.detach();
 #endif
+
+    /* For now, I'll keep it here, just in case ...
+    std::thread watchdog([]() {
+        while(1) {
+            {
+                FastInterruptDisableLock dlock;
+                sx1278->handleDioIRQ();
+            }
+            Thread::sleep(200);
+        }
+    });
+    watchdog.detach();
+    //*/
 }