diff --git a/CMakeLists.txt b/CMakeLists.txt
index b4ab6e3bfbabf404dc55894632df7405dafafadd..1e16cfc5ea55b2bf8aa520ac69682362b10c5274 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -67,7 +67,7 @@ sbs_target(sx1278lora-ra01-serial stm32f429zi_skyward_groundstation_v2)
 
 add_executable(sx1278fsk-skyward433-serial src/entrypoints/sx1278-serial.cpp)
 target_compile_definitions(sx1278fsk-skyward433-serial PRIVATE SX1278_IS_FSK SX1278_IS_SKYWARD433)
-sbs_target(sx1278fsk-skyward433-serial stm32f429zi_skyward_groundstation_v2)
+sbs_target(sx1278fsk-skyward433-serial stm32f767zi_gemini_gs)
 
 add_executable(sx1278lora-skyward433-serial src/entrypoints/sx1278-serial.cpp)
 target_compile_definitions(sx1278lora-skyward433-serial PRIVATE SX1278_IS_LORA SX1278_IS_SKYWARD433)
diff --git a/src/entrypoints/sx1278-serial.cpp b/src/entrypoints/sx1278-serial.cpp
index 8b44a472a483ba6822533c5a91c1f143c6d43b28..21401681df78278d4b1f26a18e4bf70d44c51cdc 100644
--- a/src/entrypoints/sx1278-serial.cpp
+++ b/src/entrypoints/sx1278-serial.cpp
@@ -30,7 +30,6 @@
 
 #include <thread>
 
-using namespace Boardcore;
 using namespace miosix;
 
 // Uncomment the following line to enable Lora mode
@@ -88,21 +87,79 @@ using rxen                         = radio::rxEn;
 #define SX1278_IRQ_DIO1 EXTI12_IRQHandlerImpl
 #define SX1278_IRQ_DIO3 EXTI13_IRQHandlerImpl
 
+#elif defined _BOARD_STM32F767ZI_GEMINI_GS
+#include "interfaces-impl/hwmapping.h"
+
+// #define SX1278_IS_SKYWARD433
+// #define SX1278_IS_EBYTE
+
+// Comment to use SX1278_2
+#define SX1278_1
+
+#ifdef SX1278_1
+using cs   = miosix::radio1::cs;
+using dio0 = miosix::radio1::dio0;
+using dio1 = miosix::radio1::dio1;
+using dio3 = miosix::radio1::dio3;
+
+using sck  = miosix::radio1::spi::sck;
+using miso = miosix::radio1::spi::miso;
+using mosi = miosix::radio1::spi::mosi;
+
+using txen = miosix::radio1::txen;
+using rxen = miosix::radio1::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio1::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO1_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO1_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO1_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO1_DIO3_IRQ
+#else
+using cs   = miosix::radio2::cs;
+using dio0 = miosix::radio2::dio0;
+using dio1 = miosix::radio2::dio1;
+using dio3 = miosix::radio2::dio3;
+
+using sck  = miosix::radio2::spi::sck;
+using miso = miosix::radio2::spi::miso;
+using mosi = miosix::radio2::spi::mosi;
+
+using txen = miosix::radio2::txen;
+using rxen = miosix::radio2::rxen;
+
+#define SX1278_NRST
+using rst  = miosix::radio2::nrst;
+
+#define SX1278_SPI MIOSIX_RADIO2_SPI
+
+#define SX1278_IRQ_DIO0 MIOSIX_RADIO2_DIO0_IRQ
+#define SX1278_IRQ_DIO1 MIOSIX_RADIO2_DIO1_IRQ
+#define SX1278_IRQ_DIO3 MIOSIX_RADIO2_DIO3_IRQ
+#endif
+
 #else
 #error "Target not supported"
 #endif
 
 #ifdef SX1278_IS_LORA
-static constexpr size_t SX1278_MTU = SX1278Lora::MTU;
-SX1278Lora *sx1278                 = nullptr;
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Lora::MTU;
+Boardcore::SX1278Lora *sx1278      = nullptr;
 #else
-static constexpr size_t SX1278_MTU = SX1278Fsk::MTU;
-SX1278Fsk *sx1278                  = nullptr;
+static constexpr size_t SX1278_MTU = Boardcore::SX1278Fsk::MTU;
+Boardcore::SX1278Fsk *sx1278       = nullptr;
 #endif
 
+volatile int dio0_cnt = 0;
+volatile int dio1_cnt = 0;
+volatile int dio3_cnt = 0;
+
 #ifdef SX1278_IRQ_DIO0
 void __attribute__((used)) SX1278_IRQ_DIO0()
 {
+    dio0_cnt++;
     if (sx1278)
         sx1278->handleDioIRQ();
 }
@@ -111,6 +168,7 @@ void __attribute__((used)) SX1278_IRQ_DIO0()
 #ifdef SX1278_IRQ_DIO1
 void __attribute__((used)) SX1278_IRQ_DIO1()
 {
+    dio1_cnt++;
     if (sx1278)
         sx1278->handleDioIRQ();
 }
@@ -119,6 +177,7 @@ void __attribute__((used)) SX1278_IRQ_DIO1()
 #ifdef SX1278_IRQ_DIO3
 void __attribute__((used)) SX1278_IRQ_DIO3()
 {
+    dio3_cnt++;
     if (sx1278)
         sx1278->handleDioIRQ();
 }
@@ -132,6 +191,11 @@ void initBoard()
     rxen::low();
     txen::low();
 #endif
+
+#ifdef SX1278_NRST
+    rst::mode(miosix::Mode::OUTPUT);
+    rst::high();
+#endif
 }
 
 void recvLoop()
@@ -162,22 +226,24 @@ void sendLoop()
     }
 }
 
+Boardcore::SPIBus sx1278_bus(SX1278_SPI);
+
 int main()
 {
     initBoard();
 
-    SPIBus bus(SX1278_SPI);
-
 #if defined SX1278_IS_EBYTE
     printf("[sx1278] Confuring Ebyte frontend...\n");
-    std::unique_ptr<SX1278::ISX1278Frontend> frontend(
-        new EbyteFrontend(txen::getPin(), rxen::getPin()));
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+        new Boardcore::EbyteFrontend(txen::getPin(), rxen::getPin()));
 #elif defined SX1278_IS_SKYWARD433
     printf("[sx1278] Confuring Skyward 433 frontend...\n");
-    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new Skyward433Frontend());
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+        new Boardcore::Skyward433Frontend());
 #else
     printf("[sx1278] Confuring RA01 frontend...\n");
-    std::unique_ptr<SX1278::ISX1278Frontend> frontend(new RA01Frontend());
+    std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend(
+        new Boardcore::RA01Frontend());
 #endif
 
 #ifdef SX1278_IS_LORA
@@ -185,9 +251,9 @@ int main()
     SX1278Lora::Config config;
     SX1278Lora::Error err;
 
-    sx1278 = new SX1278Lora(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
-                            dio3::getPin(), SPI::ClockDivider::DIV_64,
-                            std::move(frontend));
+    sx1278 = new SX1278Lora(sx1278_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)
@@ -199,19 +265,23 @@ int main()
     printf("\n[sx1278] Initialization complete!\n");
 #else
     // Run default configuration
-    SX1278Fsk::Config config;
-    SX1278Fsk::Error err;
+    Boardcore::SX1278Fsk::Config config;
+    Boardcore::SX1278Fsk::Error err;
+
+    config.freq_rf    = 868000000;
+    config.enable_crc = false;
 
-    sx1278 = new SX1278Fsk(bus, cs::getPin(), dio0::getPin(), dio1::getPin(),
-                                            dio3::getPin(), SPI::ClockDivider::DIV_64,
+    sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(),
+                                            dio1::getPin(), dio3::getPin(),
+                                            Boardcore::SPI::ClockDivider::DIV_256,
                                             std::move(frontend));
 
     printf("\n[sx1278] Configuring sx1278 fsk...\n");
-    if ((err = sx1278->init(config)) != SX1278Fsk::Error::NONE)
+    if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE)
     {
         // FIXME: Why does clang-format put this line up here?
         printf("[sx1278] sx1278->init error\n");
-        return -1;
+        return false;
     }
 
     printf("\n[sx1278] Initialization complete!\n");
diff --git a/src/shared/radio/SX1278/SX1278Fsk.cpp b/src/shared/radio/SX1278/SX1278Fsk.cpp
index 75701ded057e6d67f32406cb6e67d08d7e10032f..cd07309083f9177bb07d52dd1a4943f6de7cad58 100644
--- a/src/shared/radio/SX1278/SX1278Fsk.cpp
+++ b/src/shared/radio/SX1278/SX1278Fsk.cpp
@@ -257,12 +257,10 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
     // TODO: Maybe flush stuff?
 
     uint8_t len = 0;
-    bool length_ok;
     bool crc_ok;
 
     do
     {
-        length_ok = false;
         crc_ok    = false;
 
         // Current FIFO read progress
@@ -307,23 +305,6 @@ ssize_t SX1278Fsk::receive(uint8_t *pkt, size_t max_len)
             // Advance the read pointer
             cur_len += read_size;
 
-            // If the payload went from high to low, this means we have read the
-            // whole packet
-            if (payload_ready &&
-                checkForIrqAndReset(0, RegIrqFlags::PAYLOAD_READY) != 0)
-            {
-                // Check if we have read the correct amount of data
-                length_ok = cur_len == len;
-                break;
-            }
-            else if (cur_len == len)
-            {
-                // We have read the whole packet, but PAYLOAD_READY did not
-                // trigger, something went wrong!
-                length_ok = false;
-                break;
-            }
-
             // Ok there is still more data, wait for it
             if ((waitForIrq(
                      guard_mode,
@@ -339,7 +320,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) || !length_ok)
+    if (len > max_len || (!crc_ok && crc_enabled))
         return -1;
 
     // Finally copy the packet to the destination
diff --git a/src/tests/radio/sx1278/sx1278-init.h b/src/tests/radio/sx1278/sx1278-init.h
index 9a7bd5943f1f0b7a45e47ea7d318111545250749..6de9eed7ed61dcbd7675b7d0f5cef3526ac87648 100644
--- a/src/tests/radio/sx1278/sx1278-init.h
+++ b/src/tests/radio/sx1278/sx1278-init.h
@@ -241,7 +241,8 @@ bool initRadio()
     Boardcore::SX1278Fsk::Config config;
     Boardcore::SX1278Fsk::Error err;
 
-    config.freq_rf = 434000000;
+    config.freq_rf = 868000000;
+    config.enable_crc = false;
 
     sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(),
                                             dio1::getPin(), dio3::getPin(),