diff --git a/src/boards/Groundstation/Automated/Hub.cpp b/src/boards/Groundstation/Automated/Hub.cpp index caa0dd88a2ccda4bce3278bec1ac85865aa3e223..67e6b6967645844db920068864589f1b763418fd 100644 --- a/src/boards/Groundstation/Automated/Hub.cpp +++ b/src/boards/Groundstation/Automated/Hub.cpp @@ -64,6 +64,7 @@ void Hub::dispatchOutgoingMsg(const mavlink_message_t& msg) {MAV_ARP_CMD_FORCE_NO_FEEDBACK, TMTC_ARP_FORCE_NO_FEEDBACK}, {MAV_ARP_CMD_ARM, TMTC_ARP_ARM}, {MAV_ARP_CMD_DISARM, TMTC_ARP_DISARM}, + {MAV_ARP_CMD_FOLLOW, TMTC_ARP_FOLLOW}, {MAV_ARP_CMD_CALIBRATE, TMTC_ARP_CALIBRATE}, {MAV_ARP_CMD_ENTER_TEST_MODE, TMTC_ARP_ENTER_TEST_MODE}, {MAV_ARP_CMD_EXIT_TEST_MODE, TMTC_ARP_EXIT_TEST_MODE}, diff --git a/src/boards/Groundstation/Automated/SMController/SMController.cpp b/src/boards/Groundstation/Automated/SMController/SMController.cpp index a502f2a48e67ebf8c671138e5c09f8bb49848ad3..a2e1f47415ecb0edb82192a8411300a87993b393 100644 --- a/src/boards/Groundstation/Automated/SMController/SMController.cpp +++ b/src/boards/Groundstation/Automated/SMController/SMController.cpp @@ -502,7 +502,6 @@ 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: @@ -517,7 +516,7 @@ State SMController::state_armed(const Event& event) { return HANDLED; } - case ARP_ARMED: + case TMTC_ARP_FOLLOW: { return transition(&SMController::state_fix_antennas); } @@ -733,7 +732,6 @@ 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: @@ -748,7 +746,7 @@ State SMController::state_armed_nf(const Event& event) { return HANDLED; } - case ARP_ARMED: + case TMTC_ARP_FOLLOW: { return transition(&SMController::state_fix_rocket_nf); } diff --git a/src/boards/common/Events.h b/src/boards/common/Events.h index 3d8a513a93d5b02bd3b465cd6d03e11d8800efd0..8946681a413610172df1d75d2d391d39d0c5e5b4 100644 --- a/src/boards/common/Events.h +++ b/src/boards/common/Events.h @@ -50,7 +50,6 @@ enum Events : uint8_t ADA_APOGEE_DETECTED, ARP_INIT_OK, ARP_INIT_ERROR, - ARP_ARMED, ARP_CAL_DONE, ARP_FIX_ANTENNAS, ARP_FIX_ROCKET, @@ -118,6 +117,7 @@ enum Events : uint8_t TMTC_ARP_FORCE_NO_FEEDBACK, TMTC_ARP_ARM, TMTC_ARP_DISARM, + TMTC_ARP_FOLLOW, TMTC_ARP_CALIBRATE, TMTC_ARP_ENTER_TEST_MODE, TMTC_ARP_EXIT_TEST_MODE, @@ -162,7 +162,6 @@ 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"}, @@ -231,6 +230,7 @@ inline std::string getEventString(uint8_t event) {TMTC_ARP_ARM, "TMTC_ARP_ARM"}, {TMTC_ARP_DISARM, "TMTC_ARP_DISARM"}, {TMTC_ARP_CALIBRATE, "TMTC_ARP_CALIBRATE"}, + {TMTC_ARP_FOLLOW, "TMTC_ARP_FOLLOW"}, {TMTC_ARP_ENTER_TEST_MODE, "TMTC_ARP_ENTER_TEST_MODE"}, {TMTC_ARP_EXIT_TEST_MODE, "TMTC_ARP_EXIT_TEST_MODE"}, {MOTOR_START_TARS, "MOTOR_START_TARS"},