diff --git a/CMakeLists.txt b/CMakeLists.txt
index 1e16cfc5ea55b2bf8aa520ac69682362b10c5274..0bbf59d28c919842c2d528e021ec45b440b58ea9 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -317,7 +317,7 @@ target_compile_definitions(test-sx1278fsk-gui-rx PRIVATE DISABLE_TX)
 sbs_target(test-sx1278fsk-gui-rx stm32f429zi_skyward_groundstation_v2)
 
 add_executable(test-sx1278fsk-mavlink src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp)
-sbs_target(test-sx1278fsk-mavlink stm32f429zi_skyward_groundstation_v2)
+sbs_target(test-sx1278fsk-mavlink stm32f767zi_gemini_gs)
 
 # add_executable(test-mavlinkdriver src/tests/radio/test-mavlinkdriver.cpp)
 # sbs_target(test-mavlinkdriver stm32f407vg_stm32f4discovery)
diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp
index 21401681df78278d4b1f26a18e4bf70d44c51cdc..ccda46ee6b3b5238714d096c8101d6ea19524c78 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;
@@ -248,15 +248,16 @@ int main()
 
 #ifdef SX1278_IS_LORA
     // Run default configuration
-    SX1278Lora::Config config;
-    SX1278Lora::Error err;
+    Boardcore::SX1278Lora::Config config;
+    Boardcore::SX1278Lora::Error err;
 
-    sx1278 = new SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(),
-                            dio1::getPin(), dio3::getPin(),
-                            SPI::ClockDivider::DIV_64, std::move(frontend));
+    sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                       dio1::getPin(), dio3::getPin(),
+                                       Boardcore::SPI::ClockDivider::DIV_64,
+                                       std::move(frontend));
 
     printf("\n[sx1278] Configuring sx1278 lora...\n");
-    if ((err = sx1278->init(config)) != SX1278Lora::Error::NONE)
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Lora::Error::NONE)
     {
         printf("[sx1278] sx1278->init error\n");
         return -1;
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index cd07309083f9177bb07d52dd1a4943f6de7cad58..455b99327084c58dcee3ab12eab06ab354ce8759 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -254,74 +254,67 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
     // Save the packet locally, we always want to read it all
     uint8_t tmp_pkt[MTU];
 
-    // TODO: Maybe flush stuff?
-
     uint8_t len = 0;
     bool crc_ok;
+    IrqFlags flags = 0;
 
     do
     {
-        crc_ok    = false;
+        crc_ok = false;
 
-        // Current FIFO read progress
         uint8_t cur_len = 0;
-        // Have we received payload ready yet? (aka the whole packet is in the
-        // FIFO)
-        bool payload_ready = false;
 
         // Special wait for fifo level/payload ready, release the lock at this
         // stage
-        if ((waitForIrq(guard_mode,
-                        RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0,
-                        true) &
-             RegIrqFlags::PAYLOAD_READY) != 0 &&
-            crc_enabled)
+        flags = waitForIrq(guard_mode,
+                           RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY,
+                           0, true);
+        if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
         {
-            payload_ready = true;
-            crc_ok        = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
+            crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
         }
 
         // Record RSSI here, it's where it is the most accurate
         last_rx_rssi = getRssi();
 
-        // Now read packet length
+        // Now first packet bit
         {
             SPITransaction spi(getSpiSlave());
             len = spi.readRegister(REG_FIFO);
-        }
 
-        while (cur_len < len)
-        {
-            // Calculate next read_size, remember, the FIFO will be at least
-            // FIFO_LEN / 2 filled at this point!
-            int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
-
-            // Read the packet chunk
-            {
-                SPITransaction spi(getSpiSlave());
+            int read_size = std::min((int)len, FIFO_LEN / 2);
+            // Skip 0 sized read
+            if (read_size != 0)
                 spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
-            }
 
-            // Advance the read pointer
             cur_len += read_size;
+        }
 
-            // Ok there is still more data, wait for it
-            if ((waitForIrq(
-                     guard_mode,
-                     RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0) &
-                 RegIrqFlags::PAYLOAD_READY) != 0 &&
-                crc_enabled)
+        // Then read the other chunks
+        while (cur_len < len)
+        {
+            flags = waitForIrq(
+                guard_mode,
+                RegIrqFlags::FIFO_LEVEL | RegIrqFlags::PAYLOAD_READY, 0);
+            if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
             {
-                payload_ready = true;
                 crc_ok = checkForIrqAndReset(RegIrqFlags::CRC_OK, 0) != 0;
             }
+
+            SPITransaction spi(getSpiSlave());
+
+            int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
+            spi.readRegisters(REG_FIFO, &tmp_pkt[cur_len], read_size);
+
+            cur_len += read_size;
         }
 
         // For some reason this sometimes happen?
     } while (len == 0);
 
-    if (len > max_len || (!crc_ok && crc_enabled))
+    if (len > max_len || (!crc_ok && crc_enabled)) {
         return -1;
+    }
 
     // Finally copy the packet to the destination
     memcpy(pkt, tmp_pkt, len);
diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
index f62f534ab934bef0821cd2f49a559ebb1fb45c11..237ecebaf33a9ac62d0579641fbacf34fc7ebea9 100644
--- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
+++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp
@@ -214,7 +214,7 @@ int main()
     initBoard();
 
     SX1278Fsk::Config config = {
-        .freq_rf    = 434000000,
+        .freq_rf    = 868000000,
         .freq_dev   = 50000,
         .bitrate    = 48000,
         .rx_bw      = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000,
@@ -223,7 +223,7 @@ int main()
         .power      = 13,
         .shaping    = Boardcore::SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0,
         .dc_free    = Boardcore::SX1278Fsk::Config::DcFree::WHITENING,
-        .enable_crc = true};
+        .enable_crc = false};
 
     SX1278Fsk::Error err;