diff --git a/src/boards/Main/CanHandler/CanHandler.cpp b/src/boards/Main/CanHandler/CanHandler.cpp
index 080c43b782c2cc886fbcac32bede9acf502f313e..5784904a53b757d41e508d2a748da7f9a6c62f52 100644
--- a/src/boards/Main/CanHandler/CanHandler.cpp
+++ b/src/boards/Main/CanHandler/CanHandler.cpp
@@ -44,23 +44,41 @@ bool CanHandler::isStarted() { return protocol->isStarted(); }
 
 void CanHandler::sendArmEvent()
 {
-    protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
+    protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
                            static_cast<uint8_t>(Board::MAIN),
-                           static_cast<uint8_t>(Board::BROADCAST),
+                           static_cast<uint8_t>(Board::AUXILIARY),
                            static_cast<uint8_t>(EventId::ARM));
 }
 
 void CanHandler::sendDisarmEvent()
+{
+    protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
+                           static_cast<uint8_t>(PrimaryType::EVENTS),
+                           static_cast<uint8_t>(Board::MAIN),
+                           static_cast<uint8_t>(Board::AUXILIARY),
+                           static_cast<uint8_t>(EventId::DISARM));
+}
+
+void CanHandler::sendArmCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
                            static_cast<uint8_t>(Board::MAIN),
-                           static_cast<uint8_t>(Board::BROADCAST),
+                           static_cast<uint8_t>(Board::PAYLOAD),
+                           static_cast<uint8_t>(EventId::ARM));
+}
+
+void CanHandler::sendDisarmCommand()
+{
+    protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
+                           static_cast<uint8_t>(PrimaryType::EVENTS),
+                           static_cast<uint8_t>(Board::MAIN),
+                           static_cast<uint8_t>(Board::PAYLOAD),
                            static_cast<uint8_t>(EventId::DISARM));
 }
 
-void CanHandler::sendCalibrateEvent()
+void CanHandler::sendCalibrateCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -69,7 +87,7 @@ void CanHandler::sendCalibrateEvent()
                            static_cast<uint8_t>(EventId::CALIBRATE));
 }
 
-void CanHandler::sendCamOnEvent()
+void CanHandler::sendCamOnCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -78,7 +96,7 @@ void CanHandler::sendCamOnEvent()
                            static_cast<uint8_t>(EventId::CAM_ON));
 }
 
-void CanHandler::sendCamOffEvent()
+void CanHandler::sendCamOffCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
diff --git a/src/boards/Main/CanHandler/CanHandler.h b/src/boards/Main/CanHandler/CanHandler.h
index 8169f1e458a850957d3b6ecacdffa726e2e1c3b8..9b711ca844e74d9b3ec6dc26615985d8e0c41ac7 100644
--- a/src/boards/Main/CanHandler/CanHandler.h
+++ b/src/boards/Main/CanHandler/CanHandler.h
@@ -43,9 +43,11 @@ public:
 
     void sendArmEvent();
     void sendDisarmEvent();
-    void sendCalibrateEvent();
-    void sendCamOnEvent();
-    void sendCamOffEvent();
+    void sendArmCommand();
+    void sendDisarmCommand();
+    void sendCalibrateCommand();
+    void sendCamOnCommand();
+    void sendCamOffCommand();
     void sendErrorEvent();
     void sendLiftoffEvent();
     void sendApogeeEvent();
diff --git a/src/boards/Main/Configs/CanHandlerConfig.h b/src/boards/Main/Configs/CanHandlerConfig.h
index 63d13fa9419b9fa62b41e35d7848117ffd8d9de2..f8bddd7afcddaa57ebc0b53b8d84e031b7a3e7cf 100644
--- a/src/boards/Main/Configs/CanHandlerConfig.h
+++ b/src/boards/Main/Configs/CanHandlerConfig.h
@@ -47,9 +47,11 @@ static const std::map<Common::Events, std::function<void(CanHandler *)>>
     eventToFunction{
         {Common::FLIGHT_ARMED, &CanHandler::sendArmEvent},
         {Common::FLIGHT_DISARMED, &CanHandler::sendDisarmEvent},
-        {Common::TMTC_CALIBRATE, &CanHandler::sendCalibrateEvent},
-        {Common::TMTC_START_RECORDING, &CanHandler::sendCamOnEvent},
-        {Common::TMTC_STOP_RECORDING, &CanHandler::sendCamOffEvent},
+        {Common::TMTC_ARM, &CanHandler::sendArmCommand},
+        {Common::TMTC_DISARM, &CanHandler::sendDisarmCommand},
+        {Common::TMTC_CALIBRATE, &CanHandler::sendCalibrateCommand},
+        {Common::TMTC_START_RECORDING, &CanHandler::sendCamOnCommand},
+        {Common::TMTC_STOP_RECORDING, &CanHandler::sendCamOffCommand},
         {Common::FLIGHT_ERROR_DETECTED, &CanHandler::sendErrorEvent},
         {Common::FLIGHT_LIFTOFF, &CanHandler::sendLiftoffEvent},
         {Common::FLIGHT_APOGEE_DETECTED, &CanHandler::sendApogeeEvent},
diff --git a/src/boards/Payload/CanHandler/CanHandler.cpp b/src/boards/Payload/CanHandler/CanHandler.cpp
index feac32eb5a99c30a74a3b785865b55789421f23e..a7cf5e2046b144db3e64ce384575351cd2ec20d3 100644
--- a/src/boards/Payload/CanHandler/CanHandler.cpp
+++ b/src/boards/Payload/CanHandler/CanHandler.cpp
@@ -49,7 +49,7 @@ bool CanHandler::start() { return EventHandler::start() && protocol->start(); }
 
 bool CanHandler::isStarted() { return protocol->isStarted(); }
 
-void CanHandler::sendArmEvent()
+void CanHandler::sendArmCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -58,7 +58,7 @@ void CanHandler::sendArmEvent()
                            static_cast<uint8_t>(EventId::ARM));
 }
 
-void CanHandler::sendDisarmEvent()
+void CanHandler::sendDisarmCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -67,7 +67,7 @@ void CanHandler::sendDisarmEvent()
                            static_cast<uint8_t>(EventId::DISARM));
 }
 
-void CanHandler::sendCalibrateEvent()
+void CanHandler::sendCalibrateCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -76,7 +76,7 @@ void CanHandler::sendCalibrateEvent()
                            static_cast<uint8_t>(EventId::CALIBRATE));
 }
 
-void CanHandler::sendCamOnEvent()
+void CanHandler::sendCamOnCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
@@ -85,7 +85,7 @@ void CanHandler::sendCamOnEvent()
                            static_cast<uint8_t>(EventId::CAM_ON));
 }
 
-void CanHandler::sendCamOffEvent()
+void CanHandler::sendCamOffCommand()
 {
     protocol->enqueueEvent(static_cast<uint8_t>(Priority::MEDIUM),
                            static_cast<uint8_t>(PrimaryType::EVENTS),
diff --git a/src/boards/Payload/CanHandler/CanHandler.h b/src/boards/Payload/CanHandler/CanHandler.h
index 8a9224d9f959b9d5179cecbac1f9c4f9d4017945..6177467813c983291c04820290cd1253c9052ab6 100644
--- a/src/boards/Payload/CanHandler/CanHandler.h
+++ b/src/boards/Payload/CanHandler/CanHandler.h
@@ -38,19 +38,15 @@ public:
 
     bool isStarted();
 
-    // Boardcore::Canbus::CanRXStatus getCanStatus();
+    void sendArmCommand();
 
-    // void logStatus();
+    void sendDisarmCommand();
 
-    void sendArmEvent();
+    void sendCalibrateCommand();
 
-    void sendDisarmEvent();
+    void sendCamOnCommand();
 
-    void sendCalibrateEvent();
-
-    void sendCamOnEvent();
-
-    void sendCamOffEvent();
+    void sendCamOffCommand();
 
 private:
     CanHandler();
diff --git a/src/boards/Payload/Configs/CanHandlerConfig.h b/src/boards/Payload/Configs/CanHandlerConfig.h
index b3829aabd674d8252e291a33895958714cddff98..9d8d55b444170b871143e06e43e83aa3aca7d0d4 100644
--- a/src/boards/Payload/Configs/CanHandlerConfig.h
+++ b/src/boards/Payload/Configs/CanHandlerConfig.h
@@ -48,11 +48,11 @@ static const std::map<Common::CanConfig::EventId, Common::Events> eventToEvent{
 
 static const std::map<Common::Events, std::function<void(CanHandler *)>>
     eventToFunction{
-        {Common::FLIGHT_ARMED, &CanHandler::sendArmEvent},
-        {Common::FLIGHT_DISARMED, &CanHandler::sendDisarmEvent},
-        {Common::TMTC_CALIBRATE, &CanHandler::sendCalibrateEvent},
-        {Common::TMTC_START_RECORDING, &CanHandler::sendCamOnEvent},
-        {Common::TMTC_STOP_RECORDING, &CanHandler::sendCamOffEvent},
+        {Common::TMTC_ARM, &CanHandler::sendArmCommand},
+        {Common::TMTC_DISARM, &CanHandler::sendDisarmCommand},
+        {Common::TMTC_CALIBRATE, &CanHandler::sendCalibrateCommand},
+        {Common::TMTC_START_RECORDING, &CanHandler::sendCamOnCommand},
+        {Common::TMTC_STOP_RECORDING, &CanHandler::sendCamOffCommand},
     };
 
 }  // namespace CanHandlerConfig
diff --git a/src/tests/Main/test-can-handler.cpp b/src/tests/Main/test-can-handler.cpp
index c575f3db8207f80d67f4e7135918af45605c0f64..836ddf5df2d8c036237d5ef7e2ffca51bd0fa8ef 100644
--- a/src/tests/Main/test-can-handler.cpp
+++ b/src/tests/Main/test-can-handler.cpp
@@ -35,20 +35,20 @@ int main()
 
     while (true)
     {
-        CanHandler::getInstance().sendArmEvent();
+        CanHandler::getInstance().sendArmCommand();
         printf("sendArmEvent\n");
         Thread::sleep(PERIOD);
 
-        CanHandler::getInstance().sendDisarmEvent();
-        printf("sendDisarmEvent\n");
+        CanHandler::getInstance().sendDisarmCommand();
+        printf("sendDisarmCommand\n");
         Thread::sleep(PERIOD);
 
-        CanHandler::getInstance().sendCamOnEvent();
-        printf("sendCamOnEvent\n");
+        CanHandler::getInstance().sendCamOnCommand();
+        printf("sendCamOnCommand\n");
         Thread::sleep(PERIOD);
 
-        CanHandler::getInstance().sendCamOffEvent();
-        printf("sendCamOffEvent\n");
+        CanHandler::getInstance().sendCamOffCommand();
+        printf("sendCamOffCommand\n");
         Thread::sleep(PERIOD);
 
         CanHandler::getInstance().sendLiftoffEvent();