diff --git a/libs/backward-cpp b/libs/backward-cpp
index 2395cfa2422edb71929c9d166a6a614571331db3..3bb9240cb15459768adb3e7d963a20e1523a6294 160000
--- a/libs/backward-cpp
+++ b/libs/backward-cpp
@@ -1 +1 @@
-Subproject commit 2395cfa2422edb71929c9d166a6a614571331db3
+Subproject commit 3bb9240cb15459768adb3e7d963a20e1523a6294
diff --git a/libs/mavlink-skyward-lib b/libs/mavlink-skyward-lib
index b4c2b98d38a0d15049b7fc9afcfb615aea2403a1..ce83ce010ef39c922e040442f34c07fe5b484045 160000
--- a/libs/mavlink-skyward-lib
+++ b/libs/mavlink-skyward-lib
@@ -1 +1 @@
-Subproject commit b4c2b98d38a0d15049b7fc9afcfb615aea2403a1
+Subproject commit ce83ce010ef39c922e040442f34c07fe5b484045
diff --git a/src/shared/Modules/CommandPad/MessagesList.h b/src/shared/Modules/CommandPad/MessagesList.h
index 8ef3d2bbfd534d55328876a59fb58526635c8194..7880c5c981627d5f0d4889c00a5f64c179a59454 100644
--- a/src/shared/Modules/CommandPad/MessagesList.h
+++ b/src/shared/Modules/CommandPad/MessagesList.h
@@ -38,6 +38,7 @@ static const QStringList messagesList{"PING_TC",
                                       "SET_REFERENCE_ALTITUDE_TC",
                                       "SET_REFERENCE_TEMPERATURE_TC",
                                       "SET_ORIENTATION_TC",
+                                      "SET_ORIENTATION_QUAT_TC",
                                       "SET_COORDINATES_TC",
                                       "RAW_EVENT_TC",
                                       "SET_DEPLOYMENT_ALTITUDE_TC",
@@ -46,18 +47,20 @@ static const QStringList messagesList{"PING_TC",
                                       "SET_ATOMIC_VALVE_TIMING_TC",
                                       "SET_VALVE_MAXIMUM_APERTURE_TC",
                                       "SET_IGNITION_TIME_TC",
+                                      "SET_NITROGEN_TIME_TC",
+                                      "SET_COOLING_TIME_TC",
                                       "CONRIG_STATE_TC"};
 
 static const QMap<QString, int> systemTmList{
     {"MAV_SYS_ID", MAV_SYS_ID},
-    {"MAV_FSM_ID", MAV_FSM_ID},
     {"MAV_PIN_OBS_ID", MAV_PIN_OBS_ID},
     {"MAV_LOGGER_ID", MAV_LOGGER_ID},
-    {"MAV_MAVLINK_STATS", MAV_MAVLINK_STATS},
+    {"MAV_MAVLINK_STATS_ID", MAV_MAVLINK_STATS_ID},
     {"MAV_TASK_STATS_ID", MAV_TASK_STATS_ID},
     {"MAV_ADA_ID", MAV_ADA_ID},
     {"MAV_NAS_ID", MAV_NAS_ID},
-    {"MAV_CAN_ID", MAV_CAN_ID},
+    {"MAV_MEA_ID", MAV_MEA_ID},
+    {"MAV_CAN_STATS_ID", MAV_CAN_STATS_ID},
     {"MAV_FLIGHT_ID", MAV_FLIGHT_ID},
     {"MAV_STATS_ID", MAV_STATS_ID},
     {"MAV_SENSORS_STATE_ID", MAV_SENSORS_STATE_ID},
@@ -66,33 +69,37 @@ static const QMap<QString, int> systemTmList{
     {"MAV_REGISTRY_ID", MAV_REGISTRY_ID}};
 
 static const QMap<QString, int> sensorsList{
-    {"MAV_GPS_ID", MAV_GPS_ID},
     {"MAV_BMX160_ID", MAV_BMX160_ID},
     {"MAV_VN100_ID", MAV_VN100_ID},
     {"MAV_MPU9250_ID", MAV_MPU9250_ID},
-    {"MAV_ADS_ID", MAV_ADS_ID},
+    {"MAV_ADS131M08_ID", MAV_ADS131M08_ID},
     {"MAV_MS5803_ID", MAV_MS5803_ID},
     {"MAV_BME280_ID", MAV_BME280_ID},
-    {"MAV_CURRENT_SENSE_ID", MAV_CURRENT_SENSE_ID},
     {"MAV_LIS3MDL_ID", MAV_LIS3MDL_ID},
+    {"MAV_LIS2MDL_ID", MAV_LIS2MDL_ID},
+    {"MAV_LPS28DFW_ID", MAV_LPS28DFW_ID},
+    {"MAV_LSM6DSRX_ID", MAV_LSM6DSRX_ID},
+    {"MAV_H3LIS331DL_ID", MAV_H3LIS331DL_ID},
+    {"MAV_LPS22DF_ID", MAV_LPS22DF_ID},
+    {"MAV_GPS_ID", MAV_GPS_ID},
+    {"MAV_CURRENT_SENSE_ID", MAV_CURRENT_SENSE_ID},
+    {"MAV_BATTERY_VOLTAGE_ID", MAV_BATTERY_VOLTAGE_ID},
+    {"MAV_ROTATED_IMU_ID", MAV_ROTATED_IMU_ID},
     {"MAV_DPL_PRESS_ID", MAV_DPL_PRESS_ID},
     {"MAV_STATIC_PRESS_ID", MAV_STATIC_PRESS_ID},
-    {"MAV_PITOT_PRESS_ID", MAV_PITOT_PRESS_ID},
-    {"MAV_BATTERY_VOLTAGE_ID", MAV_BATTERY_VOLTAGE_ID},
+    {"MAV_BACKUP_STATIC_PRESS_ID", MAV_BACKUP_STATIC_PRESS_ID},
+    {"MAV_STATIC_PITOT_PRESS_ID", MAV_STATIC_PITOT_PRESS_ID},
+    {"MAV_TOTAL_PITOT_PRESS_ID", MAV_TOTAL_PITOT_PRESS_ID},
+    {"MAV_DYNAMIC_PITOT_PRESS_ID", MAV_DYNAMIC_PITOT_PRESS_ID},
     {"MAV_LOAD_CELL_ID", MAV_LOAD_CELL_ID},
-    {"MAV_FILLING_PRESS_ID", MAV_FILLING_PRESS_ID},
-    {"MAV_VESSEL_PRESS_ID", MAV_VESSEL_PRESS_ID},
     {"MAV_TANK_TOP_PRESS_ID", MAV_TANK_TOP_PRESS_ID},
     {"MAV_TANK_BOTTOM_PRESS_ID", MAV_TANK_BOTTOM_PRESS_ID},
     {"MAV_TANK_TEMP_ID", MAV_TANK_TEMP_ID},
     {"MAV_COMBUSTION_PRESS_ID", MAV_COMBUSTION_PRESS_ID},
+    {"MAV_FILLING_PRESS_ID", MAV_FILLING_PRESS_ID},
+    {"MAV_VESSEL_PRESS_ID", MAV_VESSEL_PRESS_ID},
     {"MAV_LOAD_CELL_VESSEL_ID", MAV_LOAD_CELL_VESSEL_ID},
-    {"MAV_LOAD_CELL_TANK_ID", MAV_LOAD_CELL_TANK_ID},
-    {"MAV_LIS2MDL_ID", MAV_LIS2MDL_ID},
-    {"MAV_LPS28DFW_ID", MAV_LPS28DFW_ID},
-    {"MAV_LSM6DSRX_ID", MAV_LSM6DSRX_ID},
-    {"MAV_H3LIS331DL_ID", MAV_H3LIS331DL_ID},
-    {"MAV_LPS22DF_ID", MAV_LPS22DF_ID}};
+    {"MAV_LOAD_CELL_TANK_ID", MAV_LOAD_CELL_TANK_ID}};
 
 static const QMap<QString, int> commandsList{
     {"MAV_CMD_ARM", MAV_CMD_ARM},
@@ -101,10 +108,10 @@ static const QMap<QString, int> commandsList{
     {"MAV_CMD_SAVE_CALIBRATION", MAV_CMD_SAVE_CALIBRATION},
     {"MAV_CMD_FORCE_INIT", MAV_CMD_FORCE_INIT},
     {"MAV_CMD_FORCE_LAUNCH", MAV_CMD_FORCE_LAUNCH},
-    {"MAV_CMD_FORCE_LANDING", MAV_CMD_FORCE_LANDING},
-    {"MAV_CMD_FORCE_APOGEE", MAV_CMD_FORCE_APOGEE},
+    {"MAV_CMD_FORCE_ENGINE_SHUTDOWN", MAV_CMD_FORCE_ENGINE_SHUTDOWN},
     {"MAV_CMD_FORCE_EXPULSION", MAV_CMD_FORCE_EXPULSION},
-    {"MAV_CMD_FORCE_MAIN", MAV_CMD_FORCE_DEPLOYMENT},
+    {"MAV_CMD_FORCE_DEPLOYMENT", MAV_CMD_FORCE_DEPLOYMENT},
+    {"MAV_CMD_FORCE_LANDING", MAV_CMD_FORCE_LANDING},
     {"MAV_CMD_START_LOGGING", MAV_CMD_START_LOGGING},
     {"MAV_CMD_STOP_LOGGING", MAV_CMD_STOP_LOGGING},
     {"MAV_CMD_FORCE_REBOOT", MAV_CMD_FORCE_REBOOT},
@@ -115,7 +122,8 @@ static const QMap<QString, int> commandsList{
     {"MAV_CMD_OPEN_NITROGEN", MAV_CMD_OPEN_NITROGEN},
     {"MAV_CMD_REGISTRY_LOAD", MAV_CMD_REGISTRY_LOAD},
     {"MAV_CMD_REGISTRY_SAVE", MAV_CMD_REGISTRY_SAVE},
-    {"MAV_CMD_REGISTRY_CLEAR", MAV_CMD_REGISTRY_CLEAR}};
+    {"MAV_CMD_REGISTRY_CLEAR", MAV_CMD_REGISTRY_CLEAR},
+    {"MAV_CMD_ENTER_HIL", MAV_CMD_ENTER_HIL}};
 
 const QMap<QString, int> servosList{
     {"AIR_BRAKES_SERVO", AIR_BRAKES_SERVO},
@@ -178,6 +186,13 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements)
     element->addFloat("roll", "Roll:", -180, 180, 2);
     formElements["SET_ORIENTATION_TC"] = element;
 
+    element = new MessageFormElement();
+    element->addFloat("quat_x", "Quat X:", 0, 1, 2);
+    element->addFloat("quat_y", "Quat Y:", 0, 1, 2);
+    element->addFloat("quat_z", "Quat Z:", 0, 1, 2);
+    element->addFloat("quat_w", "Quat W:", 0, 1, 2);
+    formElements["SET_ORIENTATION_QUAT_TC"] = element;
+
     element = new MessageFormElement();
     element->addFloat("latitude", "Latitude:", -90, 90, 6);
     element->addFloat("longitude", "Longitude:", -90, 90, 6);
@@ -215,6 +230,14 @@ inline void fillMessagesMap(QMap<QString, MessageFormElement *> &formElements)
     element->addInteger("timing", "Timing [ms]:", 0, 3600000);
     formElements["SET_IGNITION_TIME_TC"] = element;
 
+    element = new MessageFormElement();
+    element->addInteger("timing", "Timing [ms]:", 0, 3600000);
+    formElements["SET_NITROGEN_TIME_TC"] = element;
+
+    element = new MessageFormElement();
+    element->addInteger("timing", "Timing [ms]:", 0, 3600000);
+    formElements["SET_COOLING_TIME_TC"] = element;
+
     element = new MessageFormElement();
     element->addInteger("ignition_btn", "Ignition:", 0, 1);
     element->addInteger("filling_valve_btn", "Filling:", 0, 1);
diff --git a/src/shared/Modules/Mavlink/MavlinkCodec.cpp b/src/shared/Modules/Mavlink/MavlinkCodec.cpp
index 37daea184d8ac5a115df1962a0184fc27276f967..ae6b181bb6fba4200dabe8e1bd7588e91b6468db 100644
--- a/src/shared/Modules/Mavlink/MavlinkCodec.cpp
+++ b/src/shared/Modules/Mavlink/MavlinkCodec.cpp
@@ -318,12 +318,6 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
             sysId, compId, &output, msg.getField("ref_temp").getDouble());
         return true;
     }
-    else if (messageName == "SET_DEPLOYMENT_ALTITUDE_TC")
-    {
-        mavlink_msg_set_deployment_altitude_tc_pack(
-            sysId, compId, &output, msg.getField("dpl_altitude").getDouble());
-        return true;
-    }
     else if (messageName == "SET_ORIENTATION_TC")
     {
         mavlink_msg_set_orientation_tc_pack(sysId, compId, &output,
@@ -332,6 +326,15 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
                                             msg.getField("roll").getDouble());
         return true;
     }
+    else if (messageName == "SET_ORIENTATION_QUAT_TC")
+    {
+        mavlink_msg_set_orientation_quat_tc_pack(
+            sysId, compId, &output, msg.getField("quat_x").getDouble(),
+            msg.getField("quat_y").getDouble(),
+            msg.getField("quat_z").getDouble(),
+            msg.getField("quat_w").getDouble());
+        return true;
+    }
     else if (messageName == "SET_COORDINATES_TC")
     {
         mavlink_msg_set_coordinates_tc_pack(
@@ -347,6 +350,12 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
             msg.getField("event_id").getUnsignedInteger());
         return true;
     }
+    else if (messageName == "SET_DEPLOYMENT_ALTITUDE_TC")
+    {
+        mavlink_msg_set_deployment_altitude_tc_pack(
+            sysId, compId, &output, msg.getField("dpl_altitude").getDouble());
+        return true;
+    }
     else if (messageName == "SET_TARGET_COORDINATES_TC")
     {
         mavlink_msg_set_target_coordinates_tc_pack(
@@ -384,6 +393,20 @@ bool MavlinkCodec::encodeMessage(const Message& msg, SysId sysId, CompId compId,
             msg.getField("timing").getUnsignedInteger());
         return true;
     }
+    else if (messageName == "SET_NITROGEN_TIME_TC")
+    {
+        mavlink_msg_set_nitrogen_time_tc_pack(
+            sysId, compId, &output,
+            msg.getField("timing").getUnsignedInteger());
+        return true;
+    }
+    else if (messageName == "SET_COOLING_TIME_TC")
+    {
+        mavlink_msg_set_cooling_time_tc_pack(
+            sysId, compId, &output,
+            msg.getField("timing").getUnsignedInteger());
+        return true;
+    }
     else if (messageName == "CONRIG_STATE_TC")
     {
         mavlink_msg_conrig_state_tc_pack(
diff --git a/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.cpp b/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.cpp
index 28a67fd84846ddd10fbe095f4cd375354ea45ead..7be4f30fbfee0ab866173d302f8f741b90eb17ff 100644
--- a/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.cpp
+++ b/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.cpp
@@ -46,6 +46,11 @@ OutgoingMessagesViewerModule::OutgoingMessagesViewerModule()
         this,
         [this](const Message& message, const Filter& filter)
         { handleNack(message); });
+    MessageBroker::getInstance().subscribe(
+        Filter::fromString(SkywardHubStrings::mavlink_received_msg_WACK_topic),
+        this,
+        [this](const Message& message, const Filter& filter)
+        { handleWack(message); });
 }
 
 OutgoingMessagesViewerModule::~OutgoingMessagesViewerModule() { delete ui; }
@@ -74,7 +79,7 @@ void OutgoingMessagesViewerModule::handleAck(const Message& ack)
     {
         Message msg = messages[i].getMsg();
 
-        // Color the message the ack is for by checking the message is and
+        // Color the message the ack is for by checking the message id and
         // sequence number
         if (msg.getField("message_id") == ack.getField("recv_msgid"))
             if (msg.getField("sequence_number") == ack.getField("seq_ack"))
@@ -88,7 +93,7 @@ void OutgoingMessagesViewerModule::handleNack(const Message& nack)
     {
         Message msg = messages[i].getMsg();
 
-        // Color the message the nack is for by checking the message is and
+        // Color the message the nack is for by checking the message id and
         // sequence number
         if (msg.getField("message_id") == nack.getField("recv_msgid"))
             if (msg.getField("sequence_number") == nack.getField("seq_ack"))
@@ -96,6 +101,21 @@ void OutgoingMessagesViewerModule::handleNack(const Message& nack)
     }
 }
 
+void OutgoingMessagesViewerModule::handleWack(const Message& wack)
+{
+    for (int i = 0; i < messages.count(); i++)
+    {
+        Message msg = messages[i].getMsg();
+
+        // Color the message the wack is for by checking the message id and
+        // sequence number
+        if (msg.getField("message_id") == wack.getField("recv_msgid"))
+            if (msg.getField("sequence_number") == wack.getField("seq_ack"))
+                messages[i].getItem()->setBackground(
+                    QBrush(QColor(255, 255, 255)));
+    }
+}
+
 int OutgoingMessagesViewerModule::updateVerticalHeaders(const Message& msg)
 {
     int row = 0;  // Insert on top
diff --git a/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.h b/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.h
index c51592123f215b75a086135d729e33e2ced3b6c1..4fccc266820f00568f7f791a4b3989c3b96799c5 100644
--- a/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.h
+++ b/src/shared/Modules/OutgoingMessagesViewer/OutgoingMessagesViewerModule.h
@@ -58,6 +58,7 @@ public:
     void addMsgSent(const Message& msg);
     void handleAck(const Message& ack);
     void handleNack(const Message& nack);
+    void handleWack(const Message& wack);
 
 protected:
     int updateVerticalHeaders(const Message& msg);
diff --git a/src/shared/Modules/SkywardHubStrings.h b/src/shared/Modules/SkywardHubStrings.h
index 3fe3e14c9ae661b3dea8b87ec0c3b055a4f149c6..1742e9079cf505d1c4a8e73712d6f6e7b0cc8ff3 100644
--- a/src/shared/Modules/SkywardHubStrings.h
+++ b/src/shared/Modules/SkywardHubStrings.h
@@ -74,6 +74,8 @@ static const QString mavlink_received_msg_ACK_topic =
     mavlink_received_msg_topic + "/ACK_TM";
 static const QString mavlink_received_msg_NACK_topic =
     mavlink_received_msg_topic + "/NACK_TM";
+static const QString mavlink_received_msg_WACK_topic =
+    mavlink_received_msg_topic + "/WACK_TM";
 
 static const QString mavlink_system_id_name    = "system_id";
 static const QString mavlink_component_id_name = "component_id";