From c661979473f0ab7667c300f07acb2c65e1f120fb Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Nicol=C3=B2=20Caruso?= <niccolo.caruso@skywarder.eu>
Date: Wed, 2 Oct 2024 15:17:14 +0200
Subject: [PATCH] [Fix] Reboot command was not correctly executed always.

Reboot MAV_COMMAND was only used by the state_init and not in the other cases. Now moved to Hub.cpp instead of on SMA.cpp
---
 src/boards/Groundstation/Automated/Hub.cpp     | 6 +++++-
 src/boards/Groundstation/Automated/SMA/SMA.cpp | 5 -----
 2 files changed, 5 insertions(+), 6 deletions(-)

diff --git a/src/boards/Groundstation/Automated/Hub.cpp b/src/boards/Groundstation/Automated/Hub.cpp
index 6833d510b..8ba014793 100644
--- a/src/boards/Groundstation/Automated/Hub.cpp
+++ b/src/boards/Groundstation/Automated/Hub.cpp
@@ -75,7 +75,6 @@ void Hub::dispatchOutgoingMsg(const mavlink_message_t& msg)
                 static const std::map<MavCommandList, Events> commandToEvent{
                     {MAV_CMD_FORCE_INIT, TMTC_ARP_FORCE_INIT},
                     {MAV_CMD_RESET_ALGORITHM, TMTC_ARP_RESET_ALGORITHM},
-                    {MAV_CMD_FORCE_REBOOT, TMTC_ARP_RESET_BOARD},
                     {MAV_CMD_ARP_FORCE_NO_FEEDBACK, TMTC_ARP_FORCE_NO_FEEDBACK},
                     {MAV_CMD_ARM, TMTC_ARP_ARM},
                     {MAV_CMD_DISARM, TMTC_ARP_DISARM},
@@ -88,6 +87,11 @@ void Hub::dispatchOutgoingMsg(const mavlink_message_t& msg)
                 MavCommandList commandId = static_cast<MavCommandList>(
                     mavlink_msg_arp_command_tc_get_command_id(&msg));
 
+                if (commandId == MAV_CMD_FORCE_REBOOT)
+                {
+                    reboot();
+                }
+
                 auto it = commandToEvent.find(commandId);
 
                 if (it != commandToEvent.end())
diff --git a/src/boards/Groundstation/Automated/SMA/SMA.cpp b/src/boards/Groundstation/Automated/SMA/SMA.cpp
index c14fbf723..7ae4e1da9 100644
--- a/src/boards/Groundstation/Automated/SMA/SMA.cpp
+++ b/src/boards/Groundstation/Automated/SMA/SMA.cpp
@@ -360,11 +360,6 @@ State SMA::state_config(const Event& event)
         {
             return transition(&SMA::state_init);
         }
-        case TMTC_ARP_RESET_BOARD:
-        {
-            reboot();
-            return HANDLED;
-        }
         default:
         {
             return UNHANDLED;
-- 
GitLab