diff --git a/src/boards/Groundstation/Automated/SMController/SMController.cpp b/src/boards/Groundstation/Automated/SMController/SMController.cpp
index b4c07f141b9d0db2d3fcdaa995fea74c908328dc..63ae6934f79410c4ef2603cc37739a7ed463d5f6 100644
--- a/src/boards/Groundstation/Automated/SMController/SMController.cpp
+++ b/src/boards/Groundstation/Automated/SMController/SMController.cpp
@@ -500,6 +500,7 @@ State SMController::state_armed(const Event& event)
         {
             logStatus(SMControllerState::ARMED);
             ModuleManager::getInstance().get<Actuators>()->arm();
+            EventBroker::getInstance().post(ARP_ARMED, TOPIC_ARP);
             return HANDLED;
         }
         case EV_EXIT:
@@ -514,13 +515,13 @@ State SMController::state_armed(const Event& event)
         {
             return HANDLED;
         }
-        case TMTC_ARP_ENTER_TEST_MODE:
+        case ARP_ARMED:
         {
-            return transition(&SMController::state_test);
+            return transition(&SMController::state_fix_antennas);
         }
-        case TMTC_ARP_CALIBRATE:
+        case TMTC_ARP_ENTER_TEST_MODE:
         {
-            return transition(&SMController::state_calibrate);
+            return transition(&SMController::state_test);
         }
         default:
         {
@@ -550,6 +551,10 @@ State SMController::state_test(const Event& event)
         {
             return HANDLED;
         }
+        case TMTC_ARP_CALIBRATE:
+        {
+            return transition(&SMController::state_calibrate);
+        }
         case TMTC_ARP_EXIT_TEST_MODE:
         {
             return transition(&SMController::state_armed);
@@ -584,11 +589,7 @@ State SMController::state_calibrate(const Event& event)
         }
         case ARP_CAL_DONE:
         {
-            return transition(&SMController::state_fix_antennas);
-        }
-        case TMTC_ARP_RESET_ALGORITHM:
-        {
-            return transition(&SMController::state_armed);
+            return transition(&SMController::state_test);
         }
         default:
         {
@@ -730,6 +731,7 @@ State SMController::state_armed_nf(const Event& event)
         {
             logStatus(SMControllerState::ARMED_NF);
             ModuleManager::getInstance().get<Actuators>()->arm();
+            EventBroker::getInstance().post(ARP_ARMED, TOPIC_ARP);
             return HANDLED;
         }
         case EV_EXIT:
@@ -744,13 +746,13 @@ State SMController::state_armed_nf(const Event& event)
         {
             return HANDLED;
         }
-        case TMTC_ARP_ENTER_TEST_MODE:
+        case ARP_ARMED:
         {
-            return transition(&SMController::state_test_nf);
+            return transition(&SMController::state_fix_rocket_nf);
         }
-        case TMTC_ARP_CALIBRATE:
+        case TMTC_ARP_ENTER_TEST_MODE:
         {
-            return transition(&SMController::state_fix_rocket_nf);
+            return transition(&SMController::state_test_nf);
         }
         default:
         {
diff --git a/src/boards/common/Events.h b/src/boards/common/Events.h
index 48b5138a9ebe65ccb85a683b8cf31019ea7424b8..3d8a513a93d5b02bd3b465cd6d03e11d8800efd0 100644
--- a/src/boards/common/Events.h
+++ b/src/boards/common/Events.h
@@ -50,6 +50,7 @@ enum Events : uint8_t
     ADA_APOGEE_DETECTED,
     ARP_INIT_OK,
     ARP_INIT_ERROR,
+    ARP_ARMED,
     ARP_CAL_DONE,
     ARP_FIX_ANTENNAS,
     ARP_FIX_ROCKET,
@@ -161,6 +162,7 @@ inline std::string getEventString(uint8_t event)
         {ADA_APOGEE_DETECTED, "ADA_APOGEE_DETECTED"},
         {ARP_INIT_OK, "ARP_INIT_OK"},
         {ARP_INIT_ERROR, "ARP_INIT_ERROR"},
+        {ARP_ARMED, "ARP_ARMED"},
         {ARP_CAL_DONE, "ARP_CAL_DONE"},
         {ARP_FIX_ANTENNAS, "ARP_FIX_ANTENNAS"},
         {ARP_FIX_ROCKET, "ARP_FIX_ROCKET"},