diff --git a/mavlink_lib.py b/mavlink_lib.py
index 28d1b9d394ea5095a33b3833535f97bb74c6e390..bdf1af08e7db5d096affe3f09b88e50a5ae045d3 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -491,6 +491,17 @@ enums['ServosList'][15] = EnumEntry('NITROGEN_VALVE', '''Valve enabling N2 to re
 ServosList_ENUM_END = 16 # 
 enums['ServosList'][16] = EnumEntry('ServosList_ENUM_END', '''''')
 
+# TARSList
+enums['TARSList'] = {}
+TARS_OFF = 0 # 
+enums['TARSList'][0] = EnumEntry('TARS_OFF', '''''')
+TARS_1 = 1 # 
+enums['TARSList'][1] = EnumEntry('TARS_1', '''''')
+TARS_3 = 2 # 
+enums['TARSList'][2] = EnumEntry('TARS_3', '''''')
+TARSList_ENUM_END = 3 # 
+enums['TARSList'][3] = EnumEntry('TARSList_ENUM_END', '''''')
+
 # StepperList
 enums['StepperList'] = {}
 STEPPER_X = 1 # 
@@ -561,6 +572,8 @@ MAVLINK_MSG_ID_CONRIG_STATE_TC = 32
 MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 33
 MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC = 34
 MAVLINK_MSG_ID_SET_COOLING_TIME_TC = 35
+MAVLINK_MSG_ID_GET_VALVE_INFO_TC = 36
+MAVLINK_MSG_ID_VALVE_INFO_TM = 37
 MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 60
 MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 61
 MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC = 62
@@ -1300,23 +1313,23 @@ class MAVLink_conrig_state_tc_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_CONRIG_STATE_TC
         name = 'CONRIG_STATE_TC'
-        fieldnames = ['ox_filling_btn', 'ox_release_btn', 'ox_detach_btn', 'ox_venting_btn', 'n2_filling_btn', 'n2_release_btn', 'n2_detach_btn', 'n2_quenching_btn', 'n2_3way_btn', 'tars3_btn', 'tars3m_btn', 'nitrogen_btn', 'ignition_btn', 'arm_switch']
-        ordered_fieldnames = ['ox_filling_btn', 'ox_release_btn', 'ox_detach_btn', 'ox_venting_btn', 'n2_filling_btn', 'n2_release_btn', 'n2_detach_btn', 'n2_quenching_btn', 'n2_3way_btn', 'tars3_btn', 'tars3m_btn', 'nitrogen_btn', 'ignition_btn', 'arm_switch']
-        fieldtypes = ['uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
+        fieldnames = ['ox_filling_btn', 'ox_release_btn', 'ox_detach_btn', 'ox_venting_btn', 'n2_filling_btn', 'n2_release_btn', 'n2_detach_btn', 'n2_quenching_btn', 'n2_3way_switch', 'tars_switch', 'nitrogen_btn', 'ignition_btn', 'arm_switch']
+        ordered_fieldnames = ['ox_filling_btn', 'ox_release_btn', 'ox_detach_btn', 'ox_venting_btn', 'n2_filling_btn', 'n2_release_btn', 'n2_detach_btn', 'n2_quenching_btn', 'n2_3way_switch', 'tars_switch', 'nitrogen_btn', 'ignition_btn', 'arm_switch']
+        fieldtypes = ['uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
-        fieldenums_by_name = {}
+        fieldenums_by_name = {"tars_switch": "TARSList"}
         fieldunits_by_name = {}
-        format = '<BBBBBBBBBBBBBB'
-        native_format = bytearray('<BBBBBBBBBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 238
-        unpacker = struct.Struct('<BBBBBBBBBBBBBB')
+        format = '<BBBBBBBBBBBBB'
+        native_format = bytearray('<BBBBBBBBBBBBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 183
+        unpacker = struct.Struct('<BBBBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_btn, tars3_btn, tars3m_btn, nitrogen_btn, ignition_btn, arm_switch):
+        def __init__(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_switch, tars_switch, nitrogen_btn, ignition_btn, arm_switch):
                 MAVLink_message.__init__(self, MAVLink_conrig_state_tc_message.id, MAVLink_conrig_state_tc_message.name)
                 self._fieldnames = MAVLink_conrig_state_tc_message.fieldnames
                 self._instance_field = MAVLink_conrig_state_tc_message.instance_field
@@ -1329,15 +1342,14 @@ class MAVLink_conrig_state_tc_message(MAVLink_message):
                 self.n2_release_btn = n2_release_btn
                 self.n2_detach_btn = n2_detach_btn
                 self.n2_quenching_btn = n2_quenching_btn
-                self.n2_3way_btn = n2_3way_btn
-                self.tars3_btn = tars3_btn
-                self.tars3m_btn = tars3m_btn
+                self.n2_3way_switch = n2_3way_switch
+                self.tars_switch = tars_switch
                 self.nitrogen_btn = nitrogen_btn
                 self.ignition_btn = ignition_btn
                 self.arm_switch = arm_switch
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 238, struct.pack('<BBBBBBBBBBBBBB', self.ox_filling_btn, self.ox_release_btn, self.ox_detach_btn, self.ox_venting_btn, self.n2_filling_btn, self.n2_release_btn, self.n2_detach_btn, self.n2_quenching_btn, self.n2_3way_btn, self.tars3_btn, self.tars3m_btn, self.nitrogen_btn, self.ignition_btn, self.arm_switch), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 183, struct.pack('<BBBBBBBBBBBBB', self.ox_filling_btn, self.ox_release_btn, self.ox_detach_btn, self.ox_venting_btn, self.n2_filling_btn, self.n2_release_btn, self.n2_detach_btn, self.n2_quenching_btn, self.n2_3way_switch, self.tars_switch, self.nitrogen_btn, self.ignition_btn, self.arm_switch), force_mavlink1=force_mavlink1)
 
 class MAVLink_set_ignition_time_tc_message(MAVLink_message):
         '''
@@ -1437,6 +1449,74 @@ class MAVLink_set_cooling_time_tc_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 84, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
 
+class MAVLink_get_valve_info_tc_message(MAVLink_message):
+        '''
+        Request valve information
+        '''
+        id = MAVLINK_MSG_ID_GET_VALVE_INFO_TC
+        name = 'GET_VALVE_INFO_TC'
+        fieldnames = ['servo_id']
+        ordered_fieldnames = ['servo_id']
+        fieldtypes = ['uint8_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {"servo_id": "ServosList"}
+        fieldunits_by_name = {}
+        format = '<B'
+        native_format = bytearray('<B', 'ascii')
+        orders = [0]
+        lengths = [1]
+        array_lengths = [0]
+        crc_extra = 86
+        unpacker = struct.Struct('<B')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, servo_id):
+                MAVLink_message.__init__(self, MAVLink_get_valve_info_tc_message.id, MAVLink_get_valve_info_tc_message.name)
+                self._fieldnames = MAVLink_get_valve_info_tc_message.fieldnames
+                self._instance_field = MAVLink_get_valve_info_tc_message.instance_field
+                self._instance_offset = MAVLink_get_valve_info_tc_message.instance_offset
+                self.servo_id = servo_id
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 86, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+
+class MAVLink_valve_info_tm_message(MAVLink_message):
+        '''
+        TM containing the valve information
+        '''
+        id = MAVLINK_MSG_ID_VALVE_INFO_TM
+        name = 'VALVE_INFO_TM'
+        fieldnames = ['timestamp', 'servo_id', 'state', 'close_timestamp', 'aperture']
+        ordered_fieldnames = ['timestamp', 'close_timestamp', 'aperture', 'servo_id', 'state']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint64_t', 'float']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {"servo_id": "ServosList"}
+        fieldunits_by_name = {"timestamp": "us", "close_timestamp": "ms"}
+        format = '<QQfBB'
+        native_format = bytearray('<QQfBB', 'ascii')
+        orders = [0, 3, 4, 1, 2]
+        lengths = [1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0]
+        crc_extra = 227
+        unpacker = struct.Struct('<QQfBB')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timestamp, servo_id, state, close_timestamp, aperture):
+                MAVLink_message.__init__(self, MAVLink_valve_info_tm_message.id, MAVLink_valve_info_tm_message.name)
+                self._fieldnames = MAVLink_valve_info_tm_message.fieldnames
+                self._instance_field = MAVLink_valve_info_tm_message.instance_field
+                self._instance_offset = MAVLink_valve_info_tm_message.instance_offset
+                self.timestamp = timestamp
+                self.servo_id = servo_id
+                self.state = state
+                self.close_timestamp = close_timestamp
+                self.aperture = aperture
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 227, struct.pack('<QQfBB', self.timestamp, self.close_timestamp, self.aperture, self.servo_id, self.state), force_mavlink1=force_mavlink1)
+
 class MAVLink_set_stepper_angle_tc_message(MAVLink_message):
         '''
         Move the stepper of a certain angle
@@ -3013,8 +3093,8 @@ class MAVLink_gse_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_GSE_TM
         name = 'GSE_TM'
-        fieldnames = ['timestamp', 'rocket_mass', 'ox_tank_mass', 'ox_vessel_mass', 'ox_filling_pressure', 'ox_vessel_pressure', 'n2_filling_pressure', 'n2_vessel_1_pressure', 'n2_vessel_2_pressure', 'ox_filling_valve_state', 'ox_release_valve_state', 'ox_detach_state', 'ox_venting_valve_state', 'n2_filling_valve_state', 'n2_release_valve_state', 'n2_detach_state', 'n2_quenching_valve_state', 'n2_3way_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'chamber_valve_state', 'gmm_state', 'tars3_state', 'tars3m_state', 'arming_state', 'cpu_load', 'free_heap', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status', 'log_number', 'log_good']
-        ordered_fieldnames = ['timestamp', 'rocket_mass', 'ox_tank_mass', 'ox_vessel_mass', 'ox_filling_pressure', 'ox_vessel_pressure', 'n2_filling_pressure', 'n2_vessel_1_pressure', 'n2_vessel_2_pressure', 'cpu_load', 'free_heap', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'log_good', 'log_number', 'ox_filling_valve_state', 'ox_release_valve_state', 'ox_detach_state', 'ox_venting_valve_state', 'n2_filling_valve_state', 'n2_release_valve_state', 'n2_detach_state', 'n2_quenching_valve_state', 'n2_3way_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'chamber_valve_state', 'gmm_state', 'tars3_state', 'tars3m_state', 'arming_state', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status']
+        fieldnames = ['timestamp', 'rocket_mass', 'ox_tank_mass', 'ox_vessel_mass', 'ox_filling_pressure', 'ox_vessel_pressure', 'n2_filling_pressure', 'n2_vessel_1_pressure', 'n2_vessel_2_pressure', 'ox_filling_valve_state', 'ox_release_valve_state', 'ox_detach_state', 'ox_venting_valve_state', 'n2_filling_valve_state', 'n2_release_valve_state', 'n2_detach_state', 'n2_quenching_valve_state', 'n2_3way_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'chamber_valve_state', 'gmm_state', 'tars1_state', 'tars3_state', 'arming_state', 'cpu_load', 'free_heap', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status', 'log_number', 'log_good']
+        ordered_fieldnames = ['timestamp', 'rocket_mass', 'ox_tank_mass', 'ox_vessel_mass', 'ox_filling_pressure', 'ox_vessel_pressure', 'n2_filling_pressure', 'n2_vessel_1_pressure', 'n2_vessel_2_pressure', 'cpu_load', 'free_heap', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'log_good', 'log_number', 'ox_filling_valve_state', 'ox_release_valve_state', 'ox_detach_state', 'ox_venting_valve_state', 'n2_filling_valve_state', 'n2_release_valve_state', 'n2_detach_state', 'n2_quenching_valve_state', 'n2_3way_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'chamber_valve_state', 'gmm_state', 'tars1_state', 'tars3_state', 'arming_state', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status']
         fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'uint32_t', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
@@ -3024,12 +3104,12 @@ class MAVLink_gse_tm_message(MAVLink_message):
         orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 9, 10, 11, 12, 13, 32, 33, 34, 35, 36, 37, 15, 14]
         lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
         array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 84
+        crc_extra = 220
         unpacker = struct.Struct('<QfffffffffIfffihBBBBBBBBBBBBBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars3_state, tars3m_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
+        def __init__(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars1_state, tars3_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
                 MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.name)
                 self._fieldnames = MAVLink_gse_tm_message.fieldnames
                 self._instance_field = MAVLink_gse_tm_message.instance_field
@@ -3056,8 +3136,8 @@ class MAVLink_gse_tm_message(MAVLink_message):
                 self.nitrogen_valve_state = nitrogen_valve_state
                 self.chamber_valve_state = chamber_valve_state
                 self.gmm_state = gmm_state
+                self.tars1_state = tars1_state
                 self.tars3_state = tars3_state
-                self.tars3m_state = tars3m_state
                 self.arming_state = arming_state
                 self.cpu_load = cpu_load
                 self.free_heap = free_heap
@@ -3074,7 +3154,7 @@ class MAVLink_gse_tm_message(MAVLink_message):
                 self.log_good = log_good
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 84, struct.pack('<QfffffffffIfffihBBBBBBBBBBBBBBBBBBBBBB', self.timestamp, self.rocket_mass, self.ox_tank_mass, self.ox_vessel_mass, self.ox_filling_pressure, self.ox_vessel_pressure, self.n2_filling_pressure, self.n2_vessel_1_pressure, self.n2_vessel_2_pressure, self.cpu_load, self.free_heap, self.battery_voltage, self.current_consumption, self.umbilical_current_consumption, self.log_good, self.log_number, self.ox_filling_valve_state, self.ox_release_valve_state, self.ox_detach_state, self.ox_venting_valve_state, self.n2_filling_valve_state, self.n2_release_valve_state, self.n2_detach_state, self.n2_quenching_valve_state, self.n2_3way_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.chamber_valve_state, self.gmm_state, self.tars3_state, self.tars3m_state, self.arming_state, self.main_board_state, self.payload_board_state, self.motor_board_state, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 220, struct.pack('<QfffffffffIfffihBBBBBBBBBBBBBBBBBBBBBB', self.timestamp, self.rocket_mass, self.ox_tank_mass, self.ox_vessel_mass, self.ox_filling_pressure, self.ox_vessel_pressure, self.n2_filling_pressure, self.n2_vessel_1_pressure, self.n2_vessel_2_pressure, self.cpu_load, self.free_heap, self.battery_voltage, self.current_consumption, self.umbilical_current_consumption, self.log_good, self.log_number, self.ox_filling_valve_state, self.ox_release_valve_state, self.ox_detach_state, self.ox_venting_valve_state, self.n2_filling_valve_state, self.n2_release_valve_state, self.n2_detach_state, self.n2_quenching_valve_state, self.n2_3way_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.chamber_valve_state, self.gmm_state, self.tars1_state, self.tars3_state, self.arming_state, self.main_board_state, self.payload_board_state, self.motor_board_state, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1)
 
 class MAVLink_motor_tm_message(MAVLink_message):
         '''
@@ -3352,6 +3432,8 @@ mavlink_map = {
         MAVLINK_MSG_ID_SET_IGNITION_TIME_TC : MAVLink_set_ignition_time_tc_message,
         MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC : MAVLink_set_nitrogen_time_tc_message,
         MAVLINK_MSG_ID_SET_COOLING_TIME_TC : MAVLink_set_cooling_time_tc_message,
+        MAVLINK_MSG_ID_GET_VALVE_INFO_TC : MAVLink_get_valve_info_tc_message,
+        MAVLINK_MSG_ID_VALVE_INFO_TM : MAVLink_valve_info_tm_message,
         MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC : MAVLink_set_stepper_angle_tc_message,
         MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC : MAVLink_set_stepper_steps_tc_message,
         MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC : MAVLink_set_stepper_multiplier_tc_message,
@@ -4222,7 +4304,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.set_valve_maximum_aperture_tc_encode(servo_id, maximum_aperture), force_mavlink1=force_mavlink1)
 
-        def conrig_state_tc_encode(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_btn, tars3_btn, tars3m_btn, nitrogen_btn, ignition_btn, arm_switch):
+        def conrig_state_tc_encode(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_switch, tars_switch, nitrogen_btn, ignition_btn, arm_switch):
                 '''
                 The state of the ConRIG control panel
 
@@ -4234,17 +4316,16 @@ class MAVLink(object):
                 n2_release_btn            : N2 release line pressure valve button state (type:uint8_t)
                 n2_detach_btn             : N2 quick connector detach button state (type:uint8_t)
                 n2_quenching_btn          : N2 quenching valve button state (type:uint8_t)
-                n2_3way_btn               : N2 3-way valve button state (type:uint8_t)
-                tars3_btn                 : TARS 3 algorithm button state (type:uint8_t)
-                tars3m_btn                : TARS 3M algorithm button state (type:uint8_t)
+                n2_3way_switch            : N2 3-way valve switch state (type:uint8_t)
+                tars_switch               : TARS switch state (type:uint8_t, values:TARSList)
                 nitrogen_btn              : Nitrogen valve button state (type:uint8_t)
                 ignition_btn              : Ignition button state (type:uint8_t)
                 arm_switch                : Arming switch state (type:uint8_t)
 
                 '''
-                return MAVLink_conrig_state_tc_message(ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_btn, tars3_btn, tars3m_btn, nitrogen_btn, ignition_btn, arm_switch)
+                return MAVLink_conrig_state_tc_message(ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_switch, tars_switch, nitrogen_btn, ignition_btn, arm_switch)
 
-        def conrig_state_tc_send(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_btn, tars3_btn, tars3m_btn, nitrogen_btn, ignition_btn, arm_switch, force_mavlink1=False):
+        def conrig_state_tc_send(self, ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_switch, tars_switch, nitrogen_btn, ignition_btn, arm_switch, force_mavlink1=False):
                 '''
                 The state of the ConRIG control panel
 
@@ -4256,15 +4337,14 @@ class MAVLink(object):
                 n2_release_btn            : N2 release line pressure valve button state (type:uint8_t)
                 n2_detach_btn             : N2 quick connector detach button state (type:uint8_t)
                 n2_quenching_btn          : N2 quenching valve button state (type:uint8_t)
-                n2_3way_btn               : N2 3-way valve button state (type:uint8_t)
-                tars3_btn                 : TARS 3 algorithm button state (type:uint8_t)
-                tars3m_btn                : TARS 3M algorithm button state (type:uint8_t)
+                n2_3way_switch            : N2 3-way valve switch state (type:uint8_t)
+                tars_switch               : TARS switch state (type:uint8_t, values:TARSList)
                 nitrogen_btn              : Nitrogen valve button state (type:uint8_t)
                 ignition_btn              : Ignition button state (type:uint8_t)
                 arm_switch                : Arming switch state (type:uint8_t)
 
                 '''
-                return self.send(self.conrig_state_tc_encode(ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_btn, tars3_btn, tars3m_btn, nitrogen_btn, ignition_btn, arm_switch), force_mavlink1=force_mavlink1)
+                return self.send(self.conrig_state_tc_encode(ox_filling_btn, ox_release_btn, ox_detach_btn, ox_venting_btn, n2_filling_btn, n2_release_btn, n2_detach_btn, n2_quenching_btn, n2_3way_switch, tars_switch, nitrogen_btn, ignition_btn, arm_switch), force_mavlink1=force_mavlink1)
 
         def set_ignition_time_tc_encode(self, timing):
                 '''
@@ -4324,6 +4404,50 @@ class MAVLink(object):
                 '''
                 return self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1)
 
+        def get_valve_info_tc_encode(self, servo_id):
+                '''
+                Request valve information
+
+                servo_id                  : The ID of the valve (type:uint8_t, values:ServosList)
+
+                '''
+                return MAVLink_get_valve_info_tc_message(servo_id)
+
+        def get_valve_info_tc_send(self, servo_id, force_mavlink1=False):
+                '''
+                Request valve information
+
+                servo_id                  : The ID of the valve (type:uint8_t, values:ServosList)
+
+                '''
+                return self.send(self.get_valve_info_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+
+        def valve_info_tm_encode(self, timestamp, servo_id, state, close_timestamp, aperture):
+                '''
+                TM containing the valve information
+
+                timestamp                 : Timestamp [us] (type:uint64_t)
+                servo_id                  : The ID of the valve (type:uint8_t, values:ServosList)
+                state                     : State of the valve (1 = open, 0 = closed) (type:uint8_t)
+                close_timestamp           : Time when the valve is scheduled to close (undefined if the valve is closed) [ms] (type:uint64_t)
+                aperture                  : Maximum valve aperture (open position) [0-1] (type:float)
+
+                '''
+                return MAVLink_valve_info_tm_message(timestamp, servo_id, state, close_timestamp, aperture)
+
+        def valve_info_tm_send(self, timestamp, servo_id, state, close_timestamp, aperture, force_mavlink1=False):
+                '''
+                TM containing the valve information
+
+                timestamp                 : Timestamp [us] (type:uint64_t)
+                servo_id                  : The ID of the valve (type:uint8_t, values:ServosList)
+                state                     : State of the valve (1 = open, 0 = closed) (type:uint8_t)
+                close_timestamp           : Time when the valve is scheduled to close (undefined if the valve is closed) [ms] (type:uint64_t)
+                aperture                  : Maximum valve aperture (open position) [0-1] (type:float)
+
+                '''
+                return self.send(self.valve_info_tm_encode(timestamp, servo_id, state, close_timestamp, aperture), force_mavlink1=force_mavlink1)
+
         def set_stepper_angle_tc_encode(self, stepper_id, angle):
                 '''
                 Move the stepper of a certain angle
@@ -5714,7 +5838,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.payload_stats_tm_encode(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
 
-        def gse_tm_encode(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars3_state, tars3m_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
+        def gse_tm_encode(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars1_state, tars3_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
                 '''
                 Ground Segment Equipment telemetry
 
@@ -5740,8 +5864,8 @@ class MAVLink(object):
                 nitrogen_valve_state        : Rocket main N2 valve state (1: open, 0: close) (type:uint8_t)
                 chamber_valve_state        : Chamber pressurization valve state (1: enabled, 0: disabled) (type:uint8_t)
                 gmm_state                 : State of the GroundModeManager (type:uint8_t)
+                tars1_state               : State of TARS 1 (type:uint8_t)
                 tars3_state               : State of TARS 3 (type:uint8_t)
-                tars3m_state              : State of TARS 3 Maintenance (type:uint8_t)
                 arming_state              : Arming state (1: armed, 0: otherwise) (type:uint8_t)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap memory (type:uint32_t)
@@ -5758,9 +5882,9 @@ class MAVLink(object):
                 log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
 
                 '''
-                return MAVLink_gse_tm_message(timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars3_state, tars3m_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good)
+                return MAVLink_gse_tm_message(timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars1_state, tars3_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good)
 
-        def gse_tm_send(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars3_state, tars3m_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good, force_mavlink1=False):
+        def gse_tm_send(self, timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars1_state, tars3_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good, force_mavlink1=False):
                 '''
                 Ground Segment Equipment telemetry
 
@@ -5786,8 +5910,8 @@ class MAVLink(object):
                 nitrogen_valve_state        : Rocket main N2 valve state (1: open, 0: close) (type:uint8_t)
                 chamber_valve_state        : Chamber pressurization valve state (1: enabled, 0: disabled) (type:uint8_t)
                 gmm_state                 : State of the GroundModeManager (type:uint8_t)
+                tars1_state               : State of TARS 1 (type:uint8_t)
                 tars3_state               : State of TARS 3 (type:uint8_t)
-                tars3m_state              : State of TARS 3 Maintenance (type:uint8_t)
                 arming_state              : Arming state (1: armed, 0: otherwise) (type:uint8_t)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap memory (type:uint32_t)
@@ -5804,7 +5928,7 @@ class MAVLink(object):
                 log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
 
                 '''
-                return self.send(self.gse_tm_encode(timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars3_state, tars3m_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good), force_mavlink1=force_mavlink1)
+                return self.send(self.gse_tm_encode(timestamp, rocket_mass, ox_tank_mass, ox_vessel_mass, ox_filling_pressure, ox_vessel_pressure, n2_filling_pressure, n2_vessel_1_pressure, n2_vessel_2_pressure, ox_filling_valve_state, ox_release_valve_state, ox_detach_state, ox_venting_valve_state, n2_filling_valve_state, n2_release_valve_state, n2_detach_state, n2_quenching_valve_state, n2_3way_valve_state, main_valve_state, nitrogen_valve_state, chamber_valve_state, gmm_state, tars1_state, tars3_state, arming_state, cpu_load, free_heap, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good), force_mavlink1=force_mavlink1)
 
         def motor_tm_encode(self, timestamp, ox_tank_top_pressure, ox_tank_bot_pressure, n2_tank_pressure, combustion_chamber_pressure, ox_tank_temperature, n2_quenching_valve_state, ox_venting_valve_state, nitrogen_valve_state, main_valve_state, battery_voltage, log_number, log_good, hil_state):
                 '''
diff --git a/mavlink_lib/orion/mavlink.h b/mavlink_lib/orion/mavlink.h
index 9b0bb07a6b4de436470c08e4248458faacb5e2e8..34aeb3fcb032be75a9f11e2e46e6138dab23f697 100644
--- a/mavlink_lib/orion/mavlink.h
+++ b/mavlink_lib/orion/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 9073854407394636743
+#define MAVLINK_PRIMARY_XML_HASH -5011644279445830804
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/orion/mavlink_msg_conrig_state_tc.h b/mavlink_lib/orion/mavlink_msg_conrig_state_tc.h
index 16c32335dc7f995319589aee40c0540106bd4ac2..6dce3376a547e34059e8a0cf1288443d6ec841f2 100644
--- a/mavlink_lib/orion/mavlink_msg_conrig_state_tc.h
+++ b/mavlink_lib/orion/mavlink_msg_conrig_state_tc.h
@@ -13,21 +13,20 @@ typedef struct __mavlink_conrig_state_tc_t {
  uint8_t n2_release_btn; /*<  N2 release line pressure valve button state*/
  uint8_t n2_detach_btn; /*<  N2 quick connector detach button state*/
  uint8_t n2_quenching_btn; /*<  N2 quenching valve button state*/
- uint8_t n2_3way_btn; /*<  N2 3-way valve button state*/
- uint8_t tars3_btn; /*<  TARS 3 algorithm button state*/
- uint8_t tars3m_btn; /*<  TARS 3M algorithm button state*/
+ uint8_t n2_3way_switch; /*<  N2 3-way valve switch state*/
+ uint8_t tars_switch; /*<  TARS switch state*/
  uint8_t nitrogen_btn; /*<  Nitrogen valve button state*/
  uint8_t ignition_btn; /*<  Ignition button state*/
  uint8_t arm_switch; /*<  Arming switch state*/
 } mavlink_conrig_state_tc_t;
 
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN 14
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN 14
-#define MAVLINK_MSG_ID_32_LEN 14
-#define MAVLINK_MSG_ID_32_MIN_LEN 14
+#define MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN 13
+#define MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN 13
+#define MAVLINK_MSG_ID_32_LEN 13
+#define MAVLINK_MSG_ID_32_MIN_LEN 13
 
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC 238
-#define MAVLINK_MSG_ID_32_CRC 238
+#define MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC 183
+#define MAVLINK_MSG_ID_32_CRC 183
 
 
 
@@ -35,7 +34,7 @@ typedef struct __mavlink_conrig_state_tc_t {
 #define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
     32, \
     "CONRIG_STATE_TC", \
-    14, \
+    13, \
     {  { "ox_filling_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ox_filling_btn) }, \
          { "ox_release_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, ox_release_btn) }, \
          { "ox_detach_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, ox_detach_btn) }, \
@@ -44,18 +43,17 @@ typedef struct __mavlink_conrig_state_tc_t {
          { "n2_release_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, n2_release_btn) }, \
          { "n2_detach_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, n2_detach_btn) }, \
          { "n2_quenching_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_conrig_state_tc_t, n2_quenching_btn) }, \
-         { "n2_3way_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_conrig_state_tc_t, n2_3way_btn) }, \
-         { "tars3_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_conrig_state_tc_t, tars3_btn) }, \
-         { "tars3m_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_conrig_state_tc_t, tars3m_btn) }, \
-         { "nitrogen_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_conrig_state_tc_t, nitrogen_btn) }, \
-         { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
-         { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
+         { "n2_3way_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_conrig_state_tc_t, n2_3way_switch) }, \
+         { "tars_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_conrig_state_tc_t, tars_switch) }, \
+         { "nitrogen_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_conrig_state_tc_t, nitrogen_btn) }, \
+         { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
+         { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
     "CONRIG_STATE_TC", \
-    14, \
+    13, \
     {  { "ox_filling_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ox_filling_btn) }, \
          { "ox_release_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, ox_release_btn) }, \
          { "ox_detach_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, ox_detach_btn) }, \
@@ -64,12 +62,11 @@ typedef struct __mavlink_conrig_state_tc_t {
          { "n2_release_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, n2_release_btn) }, \
          { "n2_detach_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, n2_detach_btn) }, \
          { "n2_quenching_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_conrig_state_tc_t, n2_quenching_btn) }, \
-         { "n2_3way_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_conrig_state_tc_t, n2_3way_btn) }, \
-         { "tars3_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_conrig_state_tc_t, tars3_btn) }, \
-         { "tars3m_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_conrig_state_tc_t, tars3m_btn) }, \
-         { "nitrogen_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_conrig_state_tc_t, nitrogen_btn) }, \
-         { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
-         { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
+         { "n2_3way_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_conrig_state_tc_t, n2_3way_switch) }, \
+         { "tars_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_conrig_state_tc_t, tars_switch) }, \
+         { "nitrogen_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_conrig_state_tc_t, nitrogen_btn) }, \
+         { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
+         { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
          } \
 }
 #endif
@@ -88,16 +85,15 @@ typedef struct __mavlink_conrig_state_tc_t {
  * @param n2_release_btn  N2 release line pressure valve button state
  * @param n2_detach_btn  N2 quick connector detach button state
  * @param n2_quenching_btn  N2 quenching valve button state
- * @param n2_3way_btn  N2 3-way valve button state
- * @param tars3_btn  TARS 3 algorithm button state
- * @param tars3m_btn  TARS 3M algorithm button state
+ * @param n2_3way_switch  N2 3-way valve switch state
+ * @param tars_switch  TARS switch state
  * @param nitrogen_btn  Nitrogen valve button state
  * @param ignition_btn  Ignition button state
  * @param arm_switch  Arming switch state
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_btn, uint8_t tars3_btn, uint8_t tars3m_btn, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
+                               uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_switch, uint8_t tars_switch, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
@@ -109,12 +105,11 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8
     _mav_put_uint8_t(buf, 5, n2_release_btn);
     _mav_put_uint8_t(buf, 6, n2_detach_btn);
     _mav_put_uint8_t(buf, 7, n2_quenching_btn);
-    _mav_put_uint8_t(buf, 8, n2_3way_btn);
-    _mav_put_uint8_t(buf, 9, tars3_btn);
-    _mav_put_uint8_t(buf, 10, tars3m_btn);
-    _mav_put_uint8_t(buf, 11, nitrogen_btn);
-    _mav_put_uint8_t(buf, 12, ignition_btn);
-    _mav_put_uint8_t(buf, 13, arm_switch);
+    _mav_put_uint8_t(buf, 8, n2_3way_switch);
+    _mav_put_uint8_t(buf, 9, tars_switch);
+    _mav_put_uint8_t(buf, 10, nitrogen_btn);
+    _mav_put_uint8_t(buf, 11, ignition_btn);
+    _mav_put_uint8_t(buf, 12, arm_switch);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
 #else
@@ -127,9 +122,8 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8
     packet.n2_release_btn = n2_release_btn;
     packet.n2_detach_btn = n2_detach_btn;
     packet.n2_quenching_btn = n2_quenching_btn;
-    packet.n2_3way_btn = n2_3way_btn;
-    packet.tars3_btn = tars3_btn;
-    packet.tars3m_btn = tars3m_btn;
+    packet.n2_3way_switch = n2_3way_switch;
+    packet.tars_switch = tars_switch;
     packet.nitrogen_btn = nitrogen_btn;
     packet.ignition_btn = ignition_btn;
     packet.arm_switch = arm_switch;
@@ -155,9 +149,8 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8
  * @param n2_release_btn  N2 release line pressure valve button state
  * @param n2_detach_btn  N2 quick connector detach button state
  * @param n2_quenching_btn  N2 quenching valve button state
- * @param n2_3way_btn  N2 3-way valve button state
- * @param tars3_btn  TARS 3 algorithm button state
- * @param tars3m_btn  TARS 3M algorithm button state
+ * @param n2_3way_switch  N2 3-way valve switch state
+ * @param tars_switch  TARS switch state
  * @param nitrogen_btn  Nitrogen valve button state
  * @param ignition_btn  Ignition button state
  * @param arm_switch  Arming switch state
@@ -165,7 +158,7 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8
  */
 static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint8_t ox_filling_btn,uint8_t ox_release_btn,uint8_t ox_detach_btn,uint8_t ox_venting_btn,uint8_t n2_filling_btn,uint8_t n2_release_btn,uint8_t n2_detach_btn,uint8_t n2_quenching_btn,uint8_t n2_3way_btn,uint8_t tars3_btn,uint8_t tars3m_btn,uint8_t nitrogen_btn,uint8_t ignition_btn,uint8_t arm_switch)
+                                   uint8_t ox_filling_btn,uint8_t ox_release_btn,uint8_t ox_detach_btn,uint8_t ox_venting_btn,uint8_t n2_filling_btn,uint8_t n2_release_btn,uint8_t n2_detach_btn,uint8_t n2_quenching_btn,uint8_t n2_3way_switch,uint8_t tars_switch,uint8_t nitrogen_btn,uint8_t ignition_btn,uint8_t arm_switch)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
@@ -177,12 +170,11 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id,
     _mav_put_uint8_t(buf, 5, n2_release_btn);
     _mav_put_uint8_t(buf, 6, n2_detach_btn);
     _mav_put_uint8_t(buf, 7, n2_quenching_btn);
-    _mav_put_uint8_t(buf, 8, n2_3way_btn);
-    _mav_put_uint8_t(buf, 9, tars3_btn);
-    _mav_put_uint8_t(buf, 10, tars3m_btn);
-    _mav_put_uint8_t(buf, 11, nitrogen_btn);
-    _mav_put_uint8_t(buf, 12, ignition_btn);
-    _mav_put_uint8_t(buf, 13, arm_switch);
+    _mav_put_uint8_t(buf, 8, n2_3way_switch);
+    _mav_put_uint8_t(buf, 9, tars_switch);
+    _mav_put_uint8_t(buf, 10, nitrogen_btn);
+    _mav_put_uint8_t(buf, 11, ignition_btn);
+    _mav_put_uint8_t(buf, 12, arm_switch);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
 #else
@@ -195,9 +187,8 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id,
     packet.n2_release_btn = n2_release_btn;
     packet.n2_detach_btn = n2_detach_btn;
     packet.n2_quenching_btn = n2_quenching_btn;
-    packet.n2_3way_btn = n2_3way_btn;
-    packet.tars3_btn = tars3_btn;
-    packet.tars3m_btn = tars3m_btn;
+    packet.n2_3way_switch = n2_3way_switch;
+    packet.tars_switch = tars_switch;
     packet.nitrogen_btn = nitrogen_btn;
     packet.ignition_btn = ignition_btn;
     packet.arm_switch = arm_switch;
@@ -219,7 +210,7 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_conrig_state_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
 {
-    return mavlink_msg_conrig_state_tc_pack(system_id, component_id, msg, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_btn, conrig_state_tc->tars3_btn, conrig_state_tc->tars3m_btn, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
+    return mavlink_msg_conrig_state_tc_pack(system_id, component_id, msg, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_switch, conrig_state_tc->tars_switch, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
 }
 
 /**
@@ -233,7 +224,7 @@ static inline uint16_t mavlink_msg_conrig_state_tc_encode(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_conrig_state_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
 {
-    return mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_btn, conrig_state_tc->tars3_btn, conrig_state_tc->tars3m_btn, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
+    return mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_switch, conrig_state_tc->tars_switch, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
 }
 
 /**
@@ -248,16 +239,15 @@ static inline uint16_t mavlink_msg_conrig_state_tc_encode_chan(uint8_t system_id
  * @param n2_release_btn  N2 release line pressure valve button state
  * @param n2_detach_btn  N2 quick connector detach button state
  * @param n2_quenching_btn  N2 quenching valve button state
- * @param n2_3way_btn  N2 3-way valve button state
- * @param tars3_btn  TARS 3 algorithm button state
- * @param tars3m_btn  TARS 3M algorithm button state
+ * @param n2_3way_switch  N2 3-way valve switch state
+ * @param tars_switch  TARS switch state
  * @param nitrogen_btn  Nitrogen valve button state
  * @param ignition_btn  Ignition button state
  * @param arm_switch  Arming switch state
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_btn, uint8_t tars3_btn, uint8_t tars3m_btn, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
+static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_switch, uint8_t tars_switch, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
@@ -269,12 +259,11 @@ static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint
     _mav_put_uint8_t(buf, 5, n2_release_btn);
     _mav_put_uint8_t(buf, 6, n2_detach_btn);
     _mav_put_uint8_t(buf, 7, n2_quenching_btn);
-    _mav_put_uint8_t(buf, 8, n2_3way_btn);
-    _mav_put_uint8_t(buf, 9, tars3_btn);
-    _mav_put_uint8_t(buf, 10, tars3m_btn);
-    _mav_put_uint8_t(buf, 11, nitrogen_btn);
-    _mav_put_uint8_t(buf, 12, ignition_btn);
-    _mav_put_uint8_t(buf, 13, arm_switch);
+    _mav_put_uint8_t(buf, 8, n2_3way_switch);
+    _mav_put_uint8_t(buf, 9, tars_switch);
+    _mav_put_uint8_t(buf, 10, nitrogen_btn);
+    _mav_put_uint8_t(buf, 11, ignition_btn);
+    _mav_put_uint8_t(buf, 12, arm_switch);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
 #else
@@ -287,9 +276,8 @@ static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint
     packet.n2_release_btn = n2_release_btn;
     packet.n2_detach_btn = n2_detach_btn;
     packet.n2_quenching_btn = n2_quenching_btn;
-    packet.n2_3way_btn = n2_3way_btn;
-    packet.tars3_btn = tars3_btn;
-    packet.tars3m_btn = tars3m_btn;
+    packet.n2_3way_switch = n2_3way_switch;
+    packet.tars_switch = tars_switch;
     packet.nitrogen_btn = nitrogen_btn;
     packet.ignition_btn = ignition_btn;
     packet.arm_switch = arm_switch;
@@ -306,7 +294,7 @@ static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint
 static inline void mavlink_msg_conrig_state_tc_send_struct(mavlink_channel_t chan, const mavlink_conrig_state_tc_t* conrig_state_tc)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_conrig_state_tc_send(chan, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_btn, conrig_state_tc->tars3_btn, conrig_state_tc->tars3m_btn, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
+    mavlink_msg_conrig_state_tc_send(chan, conrig_state_tc->ox_filling_btn, conrig_state_tc->ox_release_btn, conrig_state_tc->ox_detach_btn, conrig_state_tc->ox_venting_btn, conrig_state_tc->n2_filling_btn, conrig_state_tc->n2_release_btn, conrig_state_tc->n2_detach_btn, conrig_state_tc->n2_quenching_btn, conrig_state_tc->n2_3way_switch, conrig_state_tc->tars_switch, conrig_state_tc->nitrogen_btn, conrig_state_tc->ignition_btn, conrig_state_tc->arm_switch);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)conrig_state_tc, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
 #endif
@@ -320,7 +308,7 @@ static inline void mavlink_msg_conrig_state_tc_send_struct(mavlink_channel_t cha
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_conrig_state_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_btn, uint8_t tars3_btn, uint8_t tars3m_btn, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
+static inline void mavlink_msg_conrig_state_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t ox_filling_btn, uint8_t ox_release_btn, uint8_t ox_detach_btn, uint8_t ox_venting_btn, uint8_t n2_filling_btn, uint8_t n2_release_btn, uint8_t n2_detach_btn, uint8_t n2_quenching_btn, uint8_t n2_3way_switch, uint8_t tars_switch, uint8_t nitrogen_btn, uint8_t ignition_btn, uint8_t arm_switch)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -332,12 +320,11 @@ static inline void mavlink_msg_conrig_state_tc_send_buf(mavlink_message_t *msgbu
     _mav_put_uint8_t(buf, 5, n2_release_btn);
     _mav_put_uint8_t(buf, 6, n2_detach_btn);
     _mav_put_uint8_t(buf, 7, n2_quenching_btn);
-    _mav_put_uint8_t(buf, 8, n2_3way_btn);
-    _mav_put_uint8_t(buf, 9, tars3_btn);
-    _mav_put_uint8_t(buf, 10, tars3m_btn);
-    _mav_put_uint8_t(buf, 11, nitrogen_btn);
-    _mav_put_uint8_t(buf, 12, ignition_btn);
-    _mav_put_uint8_t(buf, 13, arm_switch);
+    _mav_put_uint8_t(buf, 8, n2_3way_switch);
+    _mav_put_uint8_t(buf, 9, tars_switch);
+    _mav_put_uint8_t(buf, 10, nitrogen_btn);
+    _mav_put_uint8_t(buf, 11, ignition_btn);
+    _mav_put_uint8_t(buf, 12, arm_switch);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
 #else
@@ -350,9 +337,8 @@ static inline void mavlink_msg_conrig_state_tc_send_buf(mavlink_message_t *msgbu
     packet->n2_release_btn = n2_release_btn;
     packet->n2_detach_btn = n2_detach_btn;
     packet->n2_quenching_btn = n2_quenching_btn;
-    packet->n2_3way_btn = n2_3way_btn;
-    packet->tars3_btn = tars3_btn;
-    packet->tars3m_btn = tars3m_btn;
+    packet->n2_3way_switch = n2_3way_switch;
+    packet->tars_switch = tars_switch;
     packet->nitrogen_btn = nitrogen_btn;
     packet->ignition_btn = ignition_btn;
     packet->arm_switch = arm_switch;
@@ -448,35 +434,25 @@ static inline uint8_t mavlink_msg_conrig_state_tc_get_n2_quenching_btn(const mav
 }
 
 /**
- * @brief Get field n2_3way_btn from conrig_state_tc message
+ * @brief Get field n2_3way_switch from conrig_state_tc message
  *
- * @return  N2 3-way valve button state
+ * @return  N2 3-way valve switch state
  */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_n2_3way_btn(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_conrig_state_tc_get_n2_3way_switch(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  8);
 }
 
 /**
- * @brief Get field tars3_btn from conrig_state_tc message
+ * @brief Get field tars_switch from conrig_state_tc message
  *
- * @return  TARS 3 algorithm button state
+ * @return  TARS switch state
  */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_tars3_btn(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_conrig_state_tc_get_tars_switch(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  9);
 }
 
-/**
- * @brief Get field tars3m_btn from conrig_state_tc message
- *
- * @return  TARS 3M algorithm button state
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_tars3m_btn(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  10);
-}
-
 /**
  * @brief Get field nitrogen_btn from conrig_state_tc message
  *
@@ -484,7 +460,7 @@ static inline uint8_t mavlink_msg_conrig_state_tc_get_tars3m_btn(const mavlink_m
  */
 static inline uint8_t mavlink_msg_conrig_state_tc_get_nitrogen_btn(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  11);
+    return _MAV_RETURN_uint8_t(msg,  10);
 }
 
 /**
@@ -494,7 +470,7 @@ static inline uint8_t mavlink_msg_conrig_state_tc_get_nitrogen_btn(const mavlink
  */
 static inline uint8_t mavlink_msg_conrig_state_tc_get_ignition_btn(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  12);
+    return _MAV_RETURN_uint8_t(msg,  11);
 }
 
 /**
@@ -504,7 +480,7 @@ static inline uint8_t mavlink_msg_conrig_state_tc_get_ignition_btn(const mavlink
  */
 static inline uint8_t mavlink_msg_conrig_state_tc_get_arm_switch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  13);
+    return _MAV_RETURN_uint8_t(msg,  12);
 }
 
 /**
@@ -524,9 +500,8 @@ static inline void mavlink_msg_conrig_state_tc_decode(const mavlink_message_t* m
     conrig_state_tc->n2_release_btn = mavlink_msg_conrig_state_tc_get_n2_release_btn(msg);
     conrig_state_tc->n2_detach_btn = mavlink_msg_conrig_state_tc_get_n2_detach_btn(msg);
     conrig_state_tc->n2_quenching_btn = mavlink_msg_conrig_state_tc_get_n2_quenching_btn(msg);
-    conrig_state_tc->n2_3way_btn = mavlink_msg_conrig_state_tc_get_n2_3way_btn(msg);
-    conrig_state_tc->tars3_btn = mavlink_msg_conrig_state_tc_get_tars3_btn(msg);
-    conrig_state_tc->tars3m_btn = mavlink_msg_conrig_state_tc_get_tars3m_btn(msg);
+    conrig_state_tc->n2_3way_switch = mavlink_msg_conrig_state_tc_get_n2_3way_switch(msg);
+    conrig_state_tc->tars_switch = mavlink_msg_conrig_state_tc_get_tars_switch(msg);
     conrig_state_tc->nitrogen_btn = mavlink_msg_conrig_state_tc_get_nitrogen_btn(msg);
     conrig_state_tc->ignition_btn = mavlink_msg_conrig_state_tc_get_ignition_btn(msg);
     conrig_state_tc->arm_switch = mavlink_msg_conrig_state_tc_get_arm_switch(msg);
diff --git a/mavlink_lib/orion/mavlink_msg_get_valve_info_tc.h b/mavlink_lib/orion/mavlink_msg_get_valve_info_tc.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce06632b9bd91cb097fbfc6f0f91cf1f6faa8305
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_get_valve_info_tc.h
@@ -0,0 +1,213 @@
+#pragma once
+// MESSAGE GET_VALVE_INFO_TC PACKING
+
+#define MAVLINK_MSG_ID_GET_VALVE_INFO_TC 36
+
+
+typedef struct __mavlink_get_valve_info_tc_t {
+ uint8_t servo_id; /*<  The ID of the valve*/
+} mavlink_get_valve_info_tc_t;
+
+#define MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN 1
+#define MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN 1
+#define MAVLINK_MSG_ID_36_LEN 1
+#define MAVLINK_MSG_ID_36_MIN_LEN 1
+
+#define MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC 86
+#define MAVLINK_MSG_ID_36_CRC 86
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GET_VALVE_INFO_TC { \
+    36, \
+    "GET_VALVE_INFO_TC", \
+    1, \
+    {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_get_valve_info_tc_t, servo_id) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GET_VALVE_INFO_TC { \
+    "GET_VALVE_INFO_TC", \
+    1, \
+    {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_get_valve_info_tc_t, servo_id) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a get_valve_info_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  The ID of the valve
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_get_valve_info_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN);
+#else
+    mavlink_get_valve_info_tc_t packet;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GET_VALVE_INFO_TC;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+}
+
+/**
+ * @brief Pack a get_valve_info_tc message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param servo_id  The ID of the valve
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_get_valve_info_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN);
+#else
+    mavlink_get_valve_info_tc_t packet;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GET_VALVE_INFO_TC;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+}
+
+/**
+ * @brief Encode a get_valve_info_tc struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param get_valve_info_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_get_valve_info_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_get_valve_info_tc_t* get_valve_info_tc)
+{
+    return mavlink_msg_get_valve_info_tc_pack(system_id, component_id, msg, get_valve_info_tc->servo_id);
+}
+
+/**
+ * @brief Encode a get_valve_info_tc struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param get_valve_info_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_get_valve_info_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_get_valve_info_tc_t* get_valve_info_tc)
+{
+    return mavlink_msg_get_valve_info_tc_pack_chan(system_id, component_id, chan, msg, get_valve_info_tc->servo_id);
+}
+
+/**
+ * @brief Send a get_valve_info_tc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param servo_id  The ID of the valve
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_get_valve_info_tc_send(mavlink_channel_t chan, uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC, buf, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+#else
+    mavlink_get_valve_info_tc_t packet;
+    packet.servo_id = servo_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC, (const char *)&packet, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a get_valve_info_tc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_get_valve_info_tc_send_struct(mavlink_channel_t chan, const mavlink_get_valve_info_tc_t* get_valve_info_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_get_valve_info_tc_send(chan, get_valve_info_tc->servo_id);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC, (const char *)get_valve_info_tc, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_get_valve_info_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC, buf, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+#else
+    mavlink_get_valve_info_tc_t *packet = (mavlink_get_valve_info_tc_t *)msgbuf;
+    packet->servo_id = servo_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GET_VALVE_INFO_TC, (const char *)packet, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GET_VALVE_INFO_TC UNPACKING
+
+
+/**
+ * @brief Get field servo_id from get_valve_info_tc message
+ *
+ * @return  The ID of the valve
+ */
+static inline uint8_t mavlink_msg_get_valve_info_tc_get_servo_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  0);
+}
+
+/**
+ * @brief Decode a get_valve_info_tc message into a struct
+ *
+ * @param msg The message to decode
+ * @param get_valve_info_tc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_get_valve_info_tc_decode(const mavlink_message_t* msg, mavlink_get_valve_info_tc_t* get_valve_info_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    get_valve_info_tc->servo_id = mavlink_msg_get_valve_info_tc_get_servo_id(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN? msg->len : MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN;
+        memset(get_valve_info_tc, 0, MAVLINK_MSG_ID_GET_VALVE_INFO_TC_LEN);
+    memcpy(get_valve_info_tc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/mavlink_msg_gse_tm.h b/mavlink_lib/orion/mavlink_msg_gse_tm.h
index d4a993e35f6b0d1751b815b414ead8554c73cbd8..3198560a0cf58cb3bf94606253e71e15157b3bec 100644
--- a/mavlink_lib/orion/mavlink_msg_gse_tm.h
+++ b/mavlink_lib/orion/mavlink_msg_gse_tm.h
@@ -34,8 +34,8 @@ typedef struct __mavlink_gse_tm_t {
  uint8_t nitrogen_valve_state; /*<  Rocket main N2 valve state (1: open, 0: close)*/
  uint8_t chamber_valve_state; /*<  Chamber pressurization valve state (1: enabled, 0: disabled)*/
  uint8_t gmm_state; /*<  State of the GroundModeManager*/
+ uint8_t tars1_state; /*<  State of TARS 1*/
  uint8_t tars3_state; /*<  State of TARS 3*/
- uint8_t tars3m_state; /*<  State of TARS 3 Maintenance*/
  uint8_t arming_state; /*<  Arming state (1: armed, 0: otherwise)*/
  uint8_t main_board_state; /*<  Main board FMM state*/
  uint8_t payload_board_state; /*<  Payload board FMM state*/
@@ -50,8 +50,8 @@ typedef struct __mavlink_gse_tm_t {
 #define MAVLINK_MSG_ID_212_LEN 88
 #define MAVLINK_MSG_ID_212_MIN_LEN 88
 
-#define MAVLINK_MSG_ID_GSE_TM_CRC 84
-#define MAVLINK_MSG_ID_212_CRC 84
+#define MAVLINK_MSG_ID_GSE_TM_CRC 220
+#define MAVLINK_MSG_ID_212_CRC 220
 
 
 
@@ -82,8 +82,8 @@ typedef struct __mavlink_gse_tm_t {
          { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
          { "chamber_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 77, offsetof(mavlink_gse_tm_t, chamber_valve_state) }, \
          { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 78, offsetof(mavlink_gse_tm_t, gmm_state) }, \
-         { "tars3_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_gse_tm_t, tars3_state) }, \
-         { "tars3m_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_gse_tm_t, tars3m_state) }, \
+         { "tars1_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_gse_tm_t, tars1_state) }, \
+         { "tars3_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_gse_tm_t, tars3_state) }, \
          { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_gse_tm_t, arming_state) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gse_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 44, offsetof(mavlink_gse_tm_t, free_heap) }, \
@@ -126,8 +126,8 @@ typedef struct __mavlink_gse_tm_t {
          { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
          { "chamber_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 77, offsetof(mavlink_gse_tm_t, chamber_valve_state) }, \
          { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 78, offsetof(mavlink_gse_tm_t, gmm_state) }, \
-         { "tars3_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_gse_tm_t, tars3_state) }, \
-         { "tars3m_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_gse_tm_t, tars3m_state) }, \
+         { "tars1_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_gse_tm_t, tars1_state) }, \
+         { "tars3_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_gse_tm_t, tars3_state) }, \
          { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_gse_tm_t, arming_state) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gse_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 44, offsetof(mavlink_gse_tm_t, free_heap) }, \
@@ -174,8 +174,8 @@ typedef struct __mavlink_gse_tm_t {
  * @param nitrogen_valve_state  Rocket main N2 valve state (1: open, 0: close)
  * @param chamber_valve_state  Chamber pressurization valve state (1: enabled, 0: disabled)
  * @param gmm_state  State of the GroundModeManager
+ * @param tars1_state  State of TARS 1
  * @param tars3_state  State of TARS 3
- * @param tars3m_state  State of TARS 3 Maintenance
  * @param arming_state  Arming state (1: armed, 0: otherwise)
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap memory
@@ -193,7 +193,7 @@ typedef struct __mavlink_gse_tm_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars3_state, uint8_t tars3m_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
+                               uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars1_state, uint8_t tars3_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -226,8 +226,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_uint8_t(buf, 76, nitrogen_valve_state);
     _mav_put_uint8_t(buf, 77, chamber_valve_state);
     _mav_put_uint8_t(buf, 78, gmm_state);
-    _mav_put_uint8_t(buf, 79, tars3_state);
-    _mav_put_uint8_t(buf, 80, tars3m_state);
+    _mav_put_uint8_t(buf, 79, tars1_state);
+    _mav_put_uint8_t(buf, 80, tars3_state);
     _mav_put_uint8_t(buf, 81, arming_state);
     _mav_put_uint8_t(buf, 82, main_board_state);
     _mav_put_uint8_t(buf, 83, payload_board_state);
@@ -268,8 +268,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.chamber_valve_state = chamber_valve_state;
     packet.gmm_state = gmm_state;
+    packet.tars1_state = tars1_state;
     packet.tars3_state = tars3_state;
-    packet.tars3m_state = tars3m_state;
     packet.arming_state = arming_state;
     packet.main_board_state = main_board_state;
     packet.payload_board_state = payload_board_state;
@@ -313,8 +313,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
  * @param nitrogen_valve_state  Rocket main N2 valve state (1: open, 0: close)
  * @param chamber_valve_state  Chamber pressurization valve state (1: enabled, 0: disabled)
  * @param gmm_state  State of the GroundModeManager
+ * @param tars1_state  State of TARS 1
  * @param tars3_state  State of TARS 3
- * @param tars3m_state  State of TARS 3 Maintenance
  * @param arming_state  Arming state (1: armed, 0: otherwise)
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap memory
@@ -333,7 +333,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
  */
 static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float rocket_mass,float ox_tank_mass,float ox_vessel_mass,float ox_filling_pressure,float ox_vessel_pressure,float n2_filling_pressure,float n2_vessel_1_pressure,float n2_vessel_2_pressure,uint8_t ox_filling_valve_state,uint8_t ox_release_valve_state,uint8_t ox_detach_state,uint8_t ox_venting_valve_state,uint8_t n2_filling_valve_state,uint8_t n2_release_valve_state,uint8_t n2_detach_state,uint8_t n2_quenching_valve_state,uint8_t n2_3way_valve_state,uint8_t main_valve_state,uint8_t nitrogen_valve_state,uint8_t chamber_valve_state,uint8_t gmm_state,uint8_t tars3_state,uint8_t tars3m_state,uint8_t arming_state,float cpu_load,uint32_t free_heap,float battery_voltage,float current_consumption,float umbilical_current_consumption,uint8_t main_board_state,uint8_t payload_board_state,uint8_t motor_board_state,uint8_t main_can_status,uint8_t payload_can_status,uint8_t motor_can_status,int16_t log_number,int32_t log_good)
+                                   uint64_t timestamp,float rocket_mass,float ox_tank_mass,float ox_vessel_mass,float ox_filling_pressure,float ox_vessel_pressure,float n2_filling_pressure,float n2_vessel_1_pressure,float n2_vessel_2_pressure,uint8_t ox_filling_valve_state,uint8_t ox_release_valve_state,uint8_t ox_detach_state,uint8_t ox_venting_valve_state,uint8_t n2_filling_valve_state,uint8_t n2_release_valve_state,uint8_t n2_detach_state,uint8_t n2_quenching_valve_state,uint8_t n2_3way_valve_state,uint8_t main_valve_state,uint8_t nitrogen_valve_state,uint8_t chamber_valve_state,uint8_t gmm_state,uint8_t tars1_state,uint8_t tars3_state,uint8_t arming_state,float cpu_load,uint32_t free_heap,float battery_voltage,float current_consumption,float umbilical_current_consumption,uint8_t main_board_state,uint8_t payload_board_state,uint8_t motor_board_state,uint8_t main_can_status,uint8_t payload_can_status,uint8_t motor_can_status,int16_t log_number,int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -366,8 +366,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_uint8_t(buf, 76, nitrogen_valve_state);
     _mav_put_uint8_t(buf, 77, chamber_valve_state);
     _mav_put_uint8_t(buf, 78, gmm_state);
-    _mav_put_uint8_t(buf, 79, tars3_state);
-    _mav_put_uint8_t(buf, 80, tars3m_state);
+    _mav_put_uint8_t(buf, 79, tars1_state);
+    _mav_put_uint8_t(buf, 80, tars3_state);
     _mav_put_uint8_t(buf, 81, arming_state);
     _mav_put_uint8_t(buf, 82, main_board_state);
     _mav_put_uint8_t(buf, 83, payload_board_state);
@@ -408,8 +408,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.chamber_valve_state = chamber_valve_state;
     packet.gmm_state = gmm_state;
+    packet.tars1_state = tars1_state;
     packet.tars3_state = tars3_state;
-    packet.tars3m_state = tars3m_state;
     packet.arming_state = arming_state;
     packet.main_board_state = main_board_state;
     packet.payload_board_state = payload_board_state;
@@ -435,7 +435,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
 {
-    return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars3_state, gse_tm->tars3m_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
+    return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars1_state, gse_tm->tars3_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 }
 
 /**
@@ -449,7 +449,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
 {
-    return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars3_state, gse_tm->tars3m_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
+    return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars1_state, gse_tm->tars3_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 }
 
 /**
@@ -478,8 +478,8 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t
  * @param nitrogen_valve_state  Rocket main N2 valve state (1: open, 0: close)
  * @param chamber_valve_state  Chamber pressurization valve state (1: enabled, 0: disabled)
  * @param gmm_state  State of the GroundModeManager
+ * @param tars1_state  State of TARS 1
  * @param tars3_state  State of TARS 3
- * @param tars3m_state  State of TARS 3 Maintenance
  * @param arming_state  Arming state (1: armed, 0: otherwise)
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap memory
@@ -497,7 +497,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars3_state, uint8_t tars3m_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
+static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars1_state, uint8_t tars3_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -530,8 +530,8 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_uint8_t(buf, 76, nitrogen_valve_state);
     _mav_put_uint8_t(buf, 77, chamber_valve_state);
     _mav_put_uint8_t(buf, 78, gmm_state);
-    _mav_put_uint8_t(buf, 79, tars3_state);
-    _mav_put_uint8_t(buf, 80, tars3m_state);
+    _mav_put_uint8_t(buf, 79, tars1_state);
+    _mav_put_uint8_t(buf, 80, tars3_state);
     _mav_put_uint8_t(buf, 81, arming_state);
     _mav_put_uint8_t(buf, 82, main_board_state);
     _mav_put_uint8_t(buf, 83, payload_board_state);
@@ -572,8 +572,8 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.chamber_valve_state = chamber_valve_state;
     packet.gmm_state = gmm_state;
+    packet.tars1_state = tars1_state;
     packet.tars3_state = tars3_state;
-    packet.tars3m_state = tars3m_state;
     packet.arming_state = arming_state;
     packet.main_board_state = main_board_state;
     packet.payload_board_state = payload_board_state;
@@ -594,7 +594,7 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_tm_t* gse_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars3_state, gse_tm->tars3m_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
+    mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->rocket_mass, gse_tm->ox_tank_mass, gse_tm->ox_vessel_mass, gse_tm->ox_filling_pressure, gse_tm->ox_vessel_pressure, gse_tm->n2_filling_pressure, gse_tm->n2_vessel_1_pressure, gse_tm->n2_vessel_2_pressure, gse_tm->ox_filling_valve_state, gse_tm->ox_release_valve_state, gse_tm->ox_detach_state, gse_tm->ox_venting_valve_state, gse_tm->n2_filling_valve_state, gse_tm->n2_release_valve_state, gse_tm->n2_detach_state, gse_tm->n2_quenching_valve_state, gse_tm->n2_3way_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->chamber_valve_state, gse_tm->gmm_state, gse_tm->tars1_state, gse_tm->tars3_state, gse_tm->arming_state, gse_tm->cpu_load, gse_tm->free_heap, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)gse_tm, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #endif
@@ -608,7 +608,7 @@ static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars3_state, uint8_t tars3m_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
+static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float rocket_mass, float ox_tank_mass, float ox_vessel_mass, float ox_filling_pressure, float ox_vessel_pressure, float n2_filling_pressure, float n2_vessel_1_pressure, float n2_vessel_2_pressure, uint8_t ox_filling_valve_state, uint8_t ox_release_valve_state, uint8_t ox_detach_state, uint8_t ox_venting_valve_state, uint8_t n2_filling_valve_state, uint8_t n2_release_valve_state, uint8_t n2_detach_state, uint8_t n2_quenching_valve_state, uint8_t n2_3way_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t chamber_valve_state, uint8_t gmm_state, uint8_t tars1_state, uint8_t tars3_state, uint8_t arming_state, float cpu_load, uint32_t free_heap, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -641,8 +641,8 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_uint8_t(buf, 76, nitrogen_valve_state);
     _mav_put_uint8_t(buf, 77, chamber_valve_state);
     _mav_put_uint8_t(buf, 78, gmm_state);
-    _mav_put_uint8_t(buf, 79, tars3_state);
-    _mav_put_uint8_t(buf, 80, tars3m_state);
+    _mav_put_uint8_t(buf, 79, tars1_state);
+    _mav_put_uint8_t(buf, 80, tars3_state);
     _mav_put_uint8_t(buf, 81, arming_state);
     _mav_put_uint8_t(buf, 82, main_board_state);
     _mav_put_uint8_t(buf, 83, payload_board_state);
@@ -683,8 +683,8 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->nitrogen_valve_state = nitrogen_valve_state;
     packet->chamber_valve_state = chamber_valve_state;
     packet->gmm_state = gmm_state;
+    packet->tars1_state = tars1_state;
     packet->tars3_state = tars3_state;
-    packet->tars3m_state = tars3m_state;
     packet->arming_state = arming_state;
     packet->main_board_state = main_board_state;
     packet->payload_board_state = payload_board_state;
@@ -924,21 +924,21 @@ static inline uint8_t mavlink_msg_gse_tm_get_gmm_state(const mavlink_message_t*
 }
 
 /**
- * @brief Get field tars3_state from gse_tm message
+ * @brief Get field tars1_state from gse_tm message
  *
- * @return  State of TARS 3
+ * @return  State of TARS 1
  */
-static inline uint8_t mavlink_msg_gse_tm_get_tars3_state(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_gse_tm_get_tars1_state(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  79);
 }
 
 /**
- * @brief Get field tars3m_state from gse_tm message
+ * @brief Get field tars3_state from gse_tm message
  *
- * @return  State of TARS 3 Maintenance
+ * @return  State of TARS 3
  */
-static inline uint8_t mavlink_msg_gse_tm_get_tars3m_state(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_gse_tm_get_tars3_state(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  80);
 }
@@ -1121,8 +1121,8 @@ static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavli
     gse_tm->nitrogen_valve_state = mavlink_msg_gse_tm_get_nitrogen_valve_state(msg);
     gse_tm->chamber_valve_state = mavlink_msg_gse_tm_get_chamber_valve_state(msg);
     gse_tm->gmm_state = mavlink_msg_gse_tm_get_gmm_state(msg);
+    gse_tm->tars1_state = mavlink_msg_gse_tm_get_tars1_state(msg);
     gse_tm->tars3_state = mavlink_msg_gse_tm_get_tars3_state(msg);
-    gse_tm->tars3m_state = mavlink_msg_gse_tm_get_tars3m_state(msg);
     gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg);
     gse_tm->main_board_state = mavlink_msg_gse_tm_get_main_board_state(msg);
     gse_tm->payload_board_state = mavlink_msg_gse_tm_get_payload_board_state(msg);
diff --git a/mavlink_lib/orion/mavlink_msg_valve_info_tm.h b/mavlink_lib/orion/mavlink_msg_valve_info_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..f7f806398b72422908fb7cb3679365e576c701f9
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_valve_info_tm.h
@@ -0,0 +1,313 @@
+#pragma once
+// MESSAGE VALVE_INFO_TM PACKING
+
+#define MAVLINK_MSG_ID_VALVE_INFO_TM 37
+
+
+typedef struct __mavlink_valve_info_tm_t {
+ uint64_t timestamp; /*< [us] Timestamp*/
+ uint64_t close_timestamp; /*< [ms] Time when the valve is scheduled to close (undefined if the valve is closed)*/
+ float aperture; /*<  Maximum valve aperture (open position) [0-1]*/
+ uint8_t servo_id; /*<  The ID of the valve*/
+ uint8_t state; /*<  State of the valve (1 = open, 0 = closed)*/
+} mavlink_valve_info_tm_t;
+
+#define MAVLINK_MSG_ID_VALVE_INFO_TM_LEN 22
+#define MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN 22
+#define MAVLINK_MSG_ID_37_LEN 22
+#define MAVLINK_MSG_ID_37_MIN_LEN 22
+
+#define MAVLINK_MSG_ID_VALVE_INFO_TM_CRC 227
+#define MAVLINK_MSG_ID_37_CRC 227
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VALVE_INFO_TM { \
+    37, \
+    "VALVE_INFO_TM", \
+    5, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_valve_info_tm_t, timestamp) }, \
+         { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_valve_info_tm_t, servo_id) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_valve_info_tm_t, state) }, \
+         { "close_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_valve_info_tm_t, close_timestamp) }, \
+         { "aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_valve_info_tm_t, aperture) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VALVE_INFO_TM { \
+    "VALVE_INFO_TM", \
+    5, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_valve_info_tm_t, timestamp) }, \
+         { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_valve_info_tm_t, servo_id) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_valve_info_tm_t, state) }, \
+         { "close_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_valve_info_tm_t, close_timestamp) }, \
+         { "aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_valve_info_tm_t, aperture) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a valve_info_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param servo_id  The ID of the valve
+ * @param state  State of the valve (1 = open, 0 = closed)
+ * @param close_timestamp [ms] Time when the valve is scheduled to close (undefined if the valve is closed)
+ * @param aperture  Maximum valve aperture (open position) [0-1]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_valve_info_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t servo_id, uint8_t state, uint64_t close_timestamp, float aperture)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VALVE_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, close_timestamp);
+    _mav_put_float(buf, 16, aperture);
+    _mav_put_uint8_t(buf, 20, servo_id);
+    _mav_put_uint8_t(buf, 21, state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN);
+#else
+    mavlink_valve_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.close_timestamp = close_timestamp;
+    packet.aperture = aperture;
+    packet.servo_id = servo_id;
+    packet.state = state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VALVE_INFO_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+}
+
+/**
+ * @brief Pack a valve_info_tm message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param timestamp [us] Timestamp
+ * @param servo_id  The ID of the valve
+ * @param state  State of the valve (1 = open, 0 = closed)
+ * @param close_timestamp [ms] Time when the valve is scheduled to close (undefined if the valve is closed)
+ * @param aperture  Maximum valve aperture (open position) [0-1]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_valve_info_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t timestamp,uint8_t servo_id,uint8_t state,uint64_t close_timestamp,float aperture)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VALVE_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, close_timestamp);
+    _mav_put_float(buf, 16, aperture);
+    _mav_put_uint8_t(buf, 20, servo_id);
+    _mav_put_uint8_t(buf, 21, state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN);
+#else
+    mavlink_valve_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.close_timestamp = close_timestamp;
+    packet.aperture = aperture;
+    packet.servo_id = servo_id;
+    packet.state = state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VALVE_INFO_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+}
+
+/**
+ * @brief Encode a valve_info_tm struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param valve_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_valve_info_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_valve_info_tm_t* valve_info_tm)
+{
+    return mavlink_msg_valve_info_tm_pack(system_id, component_id, msg, valve_info_tm->timestamp, valve_info_tm->servo_id, valve_info_tm->state, valve_info_tm->close_timestamp, valve_info_tm->aperture);
+}
+
+/**
+ * @brief Encode a valve_info_tm struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param valve_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_valve_info_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_valve_info_tm_t* valve_info_tm)
+{
+    return mavlink_msg_valve_info_tm_pack_chan(system_id, component_id, chan, msg, valve_info_tm->timestamp, valve_info_tm->servo_id, valve_info_tm->state, valve_info_tm->close_timestamp, valve_info_tm->aperture);
+}
+
+/**
+ * @brief Send a valve_info_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [us] Timestamp
+ * @param servo_id  The ID of the valve
+ * @param state  State of the valve (1 = open, 0 = closed)
+ * @param close_timestamp [ms] Time when the valve is scheduled to close (undefined if the valve is closed)
+ * @param aperture  Maximum valve aperture (open position) [0-1]
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_valve_info_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t servo_id, uint8_t state, uint64_t close_timestamp, float aperture)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VALVE_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, close_timestamp);
+    _mav_put_float(buf, 16, aperture);
+    _mav_put_uint8_t(buf, 20, servo_id);
+    _mav_put_uint8_t(buf, 21, state);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VALVE_INFO_TM, buf, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+#else
+    mavlink_valve_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.close_timestamp = close_timestamp;
+    packet.aperture = aperture;
+    packet.servo_id = servo_id;
+    packet.state = state;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VALVE_INFO_TM, (const char *)&packet, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a valve_info_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_valve_info_tm_send_struct(mavlink_channel_t chan, const mavlink_valve_info_tm_t* valve_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_valve_info_tm_send(chan, valve_info_tm->timestamp, valve_info_tm->servo_id, valve_info_tm->state, valve_info_tm->close_timestamp, valve_info_tm->aperture);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VALVE_INFO_TM, (const char *)valve_info_tm, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VALVE_INFO_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_valve_info_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t servo_id, uint8_t state, uint64_t close_timestamp, float aperture)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, close_timestamp);
+    _mav_put_float(buf, 16, aperture);
+    _mav_put_uint8_t(buf, 20, servo_id);
+    _mav_put_uint8_t(buf, 21, state);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VALVE_INFO_TM, buf, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+#else
+    mavlink_valve_info_tm_t *packet = (mavlink_valve_info_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->close_timestamp = close_timestamp;
+    packet->aperture = aperture;
+    packet->servo_id = servo_id;
+    packet->state = state;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VALVE_INFO_TM, (const char *)packet, MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN, MAVLINK_MSG_ID_VALVE_INFO_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VALVE_INFO_TM UNPACKING
+
+
+/**
+ * @brief Get field timestamp from valve_info_tm message
+ *
+ * @return [us] Timestamp
+ */
+static inline uint64_t mavlink_msg_valve_info_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field servo_id from valve_info_tm message
+ *
+ * @return  The ID of the valve
+ */
+static inline uint8_t mavlink_msg_valve_info_tm_get_servo_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  20);
+}
+
+/**
+ * @brief Get field state from valve_info_tm message
+ *
+ * @return  State of the valve (1 = open, 0 = closed)
+ */
+static inline uint8_t mavlink_msg_valve_info_tm_get_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  21);
+}
+
+/**
+ * @brief Get field close_timestamp from valve_info_tm message
+ *
+ * @return [ms] Time when the valve is scheduled to close (undefined if the valve is closed)
+ */
+static inline uint64_t mavlink_msg_valve_info_tm_get_close_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  8);
+}
+
+/**
+ * @brief Get field aperture from valve_info_tm message
+ *
+ * @return  Maximum valve aperture (open position) [0-1]
+ */
+static inline float mavlink_msg_valve_info_tm_get_aperture(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Decode a valve_info_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param valve_info_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_valve_info_tm_decode(const mavlink_message_t* msg, mavlink_valve_info_tm_t* valve_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    valve_info_tm->timestamp = mavlink_msg_valve_info_tm_get_timestamp(msg);
+    valve_info_tm->close_timestamp = mavlink_msg_valve_info_tm_get_close_timestamp(msg);
+    valve_info_tm->aperture = mavlink_msg_valve_info_tm_get_aperture(msg);
+    valve_info_tm->servo_id = mavlink_msg_valve_info_tm_get_servo_id(msg);
+    valve_info_tm->state = mavlink_msg_valve_info_tm_get_state(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VALVE_INFO_TM_LEN? msg->len : MAVLINK_MSG_ID_VALVE_INFO_TM_LEN;
+        memset(valve_info_tm, 0, MAVLINK_MSG_ID_VALVE_INFO_TM_LEN);
+    memcpy(valve_info_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/orion.h b/mavlink_lib/orion/orion.h
index 00afdb88576dc9223ef2a631d357a1db5c21d0ba..da08248d976599234bbec293003ac104d12992d4 100644
--- a/mavlink_lib/orion/orion.h
+++ b/mavlink_lib/orion/orion.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 9073854407394636743
+#define MAVLINK_THIS_XML_HASH -5011644279445830804
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +20,11 @@ extern "C" {
 // MESSAGE LENGTHS AND CRCS
 
 #ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 14, 4, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 12, 12, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 4, 4, 74, 64, 32, 60, 32, 32, 32, 32, 56, 22, 5, 19, 36, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 178, 158, 180, 170, 88, 43, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 17, 33, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 13, 4, 4, 4, 1, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 12, 12, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 4, 4, 74, 64, 32, 60, 32, 32, 32, 32, 56, 22, 5, 19, 36, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 178, 158, 180, 170, 88, 43, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 17, 33, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 238, 79, 167, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 246, 173, 183, 220, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 251, 51, 57, 72, 87, 229, 245, 212, 140, 148, 6, 165, 87, 255, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 188, 195, 99, 84, 135, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 234, 27, 97, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 183, 79, 167, 84, 86, 227, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 246, 173, 183, 220, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 251, 51, 57, 72, 87, 229, 245, 212, 140, 148, 6, 165, 87, 255, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 188, 195, 99, 220, 135, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 234, 27, 97, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #include "../protocol.h"
@@ -176,6 +176,18 @@ typedef enum ServosList
 } ServosList;
 #endif
 
+/** @brief Enumeration of TARS running states */
+#ifndef HAVE_ENUM_TARSList
+#define HAVE_ENUM_TARSList
+typedef enum TARSList
+{
+   TARS_OFF=0, /*  | */
+   TARS_1=1, /*  | */
+   TARS_3=2, /*  | */
+   TARSList_ENUM_END=3, /*  | */
+} TARSList;
+#endif
+
 /** @brief Enum of all the steppers */
 #ifndef HAVE_ENUM_StepperList
 #define HAVE_ENUM_StepperList
@@ -260,6 +272,8 @@ typedef enum Radio868Type
 #include "./mavlink_msg_set_ignition_time_tc.h"
 #include "./mavlink_msg_set_nitrogen_time_tc.h"
 #include "./mavlink_msg_set_cooling_time_tc.h"
+#include "./mavlink_msg_get_valve_info_tc.h"
+#include "./mavlink_msg_valve_info_tm.h"
 #include "./mavlink_msg_set_stepper_angle_tc.h"
 #include "./mavlink_msg_set_stepper_steps_tc.h"
 #include "./mavlink_msg_set_stepper_multiplier_tc.h"
@@ -310,11 +324,11 @@ typedef enum Radio868Type
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 9073854407394636743
+#define MAVLINK_THIS_XML_HASH -5011644279445830804
 
 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_CALIBRATION_PRESSURE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_MEA_MASS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REFERENCE_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, MAVLINK_MESSAGE_INFO_CALIBRATION_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_REQUEST, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_RESPONSE, MAVLINK_MESSAGE_INFO_ROCKET_RADIO_LINK_INFO_TM, MAVLINK_MESSAGE_INFO_GSE_RADIO_LINK_INFO_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 106 }, { "ARP_COMMAND_TC", 65 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "CALIBRATION_TM", 214 }, { "CAN_STATS_TM", 203 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 32 }, { "CURRENT_TM", 108 }, { "GPS_TM", 103 }, { "GSE_RADIO_LINK_INFO_TM", 243 }, { "GSE_TM", 212 }, { "GS_DISCOVERY_REQUEST", 240 }, { "GS_DISCOVERY_RESPONSE", 241 }, { "IMU_TM", 104 }, { "LOAD_TM", 110 }, { "LOGGER_TM", 201 }, { "MAVLINK_STATS_TM", 202 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 114 }, { "PRESSURE_TM", 105 }, { "RAW_EVENT_TC", 14 }, { "REFERENCE_TM", 115 }, { "REGISTRY_COORD_TM", 118 }, { "REGISTRY_FLOAT_TM", 116 }, { "REGISTRY_INT_TM", 117 }, { "RESET_SERVO_TC", 7 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_RADIO_LINK_INFO_TM", 242 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 112 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 113 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 17 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 63 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_CALIBRATION_PRESSURE_TC", 18 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "SET_INITIAL_MEA_MASS_TC", 19 }, { "SET_NITROGEN_TIME_TC", 34 }, { "SET_ORIENTATION_QUAT_TC", 12 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 64 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "SET_STEPPER_MULTIPLIER_TC", 62 }, { "SET_STEPPER_STEPS_TC", 61 }, { "SET_TARGET_COORDINATES_TC", 16 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 31 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 109 }, { "VOLTAGE_TM", 107 }, { "WACK_TM", 102 }, { "WIGGLE_SERVO_TC", 8 }}
+# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_CALIBRATION_PRESSURE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_MEA_MASS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, MAVLINK_MESSAGE_INFO_GET_VALVE_INFO_TC, MAVLINK_MESSAGE_INFO_VALVE_INFO_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REFERENCE_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, MAVLINK_MESSAGE_INFO_CALIBRATION_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_REQUEST, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_RESPONSE, MAVLINK_MESSAGE_INFO_ROCKET_RADIO_LINK_INFO_TM, MAVLINK_MESSAGE_INFO_GSE_RADIO_LINK_INFO_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 106 }, { "ARP_COMMAND_TC", 65 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "CALIBRATION_TM", 214 }, { "CAN_STATS_TM", 203 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 32 }, { "CURRENT_TM", 108 }, { "GET_VALVE_INFO_TC", 36 }, { "GPS_TM", 103 }, { "GSE_RADIO_LINK_INFO_TM", 243 }, { "GSE_TM", 212 }, { "GS_DISCOVERY_REQUEST", 240 }, { "GS_DISCOVERY_RESPONSE", 241 }, { "IMU_TM", 104 }, { "LOAD_TM", 110 }, { "LOGGER_TM", 201 }, { "MAVLINK_STATS_TM", 202 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 114 }, { "PRESSURE_TM", 105 }, { "RAW_EVENT_TC", 14 }, { "REFERENCE_TM", 115 }, { "REGISTRY_COORD_TM", 118 }, { "REGISTRY_FLOAT_TM", 116 }, { "REGISTRY_INT_TM", 117 }, { "RESET_SERVO_TC", 7 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_RADIO_LINK_INFO_TM", 242 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 112 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 113 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 17 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 63 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_CALIBRATION_PRESSURE_TC", 18 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "SET_INITIAL_MEA_MASS_TC", 19 }, { "SET_NITROGEN_TIME_TC", 34 }, { "SET_ORIENTATION_QUAT_TC", 12 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 64 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "SET_STEPPER_MULTIPLIER_TC", 62 }, { "SET_STEPPER_STEPS_TC", 61 }, { "SET_TARGET_COORDINATES_TC", 16 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 31 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 109 }, { "VALVE_INFO_TM", 37 }, { "VOLTAGE_TM", 107 }, { "WACK_TM", 102 }, { "WIGGLE_SERVO_TC", 8 }}
 # if MAVLINK_COMMAND_24BIT
 #  include "../mavlink_get_info.h"
 # endif
diff --git a/mavlink_lib/orion/testsuite.h b/mavlink_lib/orion/testsuite.h
index b24dc532632c5113bb3ea35d2bd7bbaf8e9669c4..93200628ab3d4e7ec594ed20e4f8bde6bd526dd6 100644
--- a/mavlink_lib/orion/testsuite.h
+++ b/mavlink_lib/orion/testsuite.h
@@ -1287,7 +1287,7 @@ static void mavlink_test_conrig_state_tc(uint8_t system_id, uint8_t component_id
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_conrig_state_tc_t packet_in = {
-        5,72,139,206,17,84,151,218,29,96,163,230,41,108
+        5,72,139,206,17,84,151,218,29,96,163,230,41
     };
     mavlink_conrig_state_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -1299,9 +1299,8 @@ static void mavlink_test_conrig_state_tc(uint8_t system_id, uint8_t component_id
         packet1.n2_release_btn = packet_in.n2_release_btn;
         packet1.n2_detach_btn = packet_in.n2_detach_btn;
         packet1.n2_quenching_btn = packet_in.n2_quenching_btn;
-        packet1.n2_3way_btn = packet_in.n2_3way_btn;
-        packet1.tars3_btn = packet_in.tars3_btn;
-        packet1.tars3m_btn = packet_in.tars3m_btn;
+        packet1.n2_3way_switch = packet_in.n2_3way_switch;
+        packet1.tars_switch = packet_in.tars_switch;
         packet1.nitrogen_btn = packet_in.nitrogen_btn;
         packet1.ignition_btn = packet_in.ignition_btn;
         packet1.arm_switch = packet_in.arm_switch;
@@ -1319,12 +1318,12 @@ static void mavlink_test_conrig_state_tc(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_conrig_state_tc_pack(system_id, component_id, &msg , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_btn , packet1.tars3_btn , packet1.tars3m_btn , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
+    mavlink_msg_conrig_state_tc_pack(system_id, component_id, &msg , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_switch , packet1.tars_switch , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
     mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_btn , packet1.tars3_btn , packet1.tars3m_btn , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
+    mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_switch , packet1.tars_switch , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
     mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1337,7 +1336,7 @@ static void mavlink_test_conrig_state_tc(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_conrig_state_tc_send(MAVLINK_COMM_1 , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_btn , packet1.tars3_btn , packet1.tars3m_btn , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
+    mavlink_msg_conrig_state_tc_send(MAVLINK_COMM_1 , packet1.ox_filling_btn , packet1.ox_release_btn , packet1.ox_detach_btn , packet1.ox_venting_btn , packet1.n2_filling_btn , packet1.n2_release_btn , packet1.n2_detach_btn , packet1.n2_quenching_btn , packet1.n2_3way_switch , packet1.tars_switch , packet1.nitrogen_btn , packet1.ignition_btn , packet1.arm_switch );
     mavlink_msg_conrig_state_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1524,6 +1523,128 @@ static void mavlink_test_set_cooling_time_tc(uint8_t system_id, uint8_t componen
 #endif
 }
 
+static void mavlink_test_get_valve_info_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GET_VALVE_INFO_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_get_valve_info_tc_t packet_in = {
+        5
+    };
+    mavlink_get_valve_info_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.servo_id = packet_in.servo_id;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GET_VALVE_INFO_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_get_valve_info_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_get_valve_info_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_get_valve_info_tc_pack(system_id, component_id, &msg , packet1.servo_id );
+    mavlink_msg_get_valve_info_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_get_valve_info_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
+    mavlink_msg_get_valve_info_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_get_valve_info_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_get_valve_info_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
+    mavlink_msg_get_valve_info_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("GET_VALVE_INFO_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GET_VALVE_INFO_TC) != NULL);
+#endif
+}
+
+static void mavlink_test_valve_info_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VALVE_INFO_TM >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_valve_info_tm_t packet_in = {
+        93372036854775807ULL,93372036854776311ULL,129.0,65,132
+    };
+    mavlink_valve_info_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.close_timestamp = packet_in.close_timestamp;
+        packet1.aperture = packet_in.aperture;
+        packet1.servo_id = packet_in.servo_id;
+        packet1.state = packet_in.state;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VALVE_INFO_TM_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_valve_info_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_valve_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_valve_info_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.servo_id , packet1.state , packet1.close_timestamp , packet1.aperture );
+    mavlink_msg_valve_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_valve_info_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.servo_id , packet1.state , packet1.close_timestamp , packet1.aperture );
+    mavlink_msg_valve_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_valve_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_valve_info_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.servo_id , packet1.state , packet1.close_timestamp , packet1.aperture );
+    mavlink_msg_valve_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("VALVE_INFO_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VALVE_INFO_TM) != NULL);
+#endif
+}
+
 static void mavlink_test_set_stepper_angle_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -4161,8 +4282,8 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.nitrogen_valve_state = packet_in.nitrogen_valve_state;
         packet1.chamber_valve_state = packet_in.chamber_valve_state;
         packet1.gmm_state = packet_in.gmm_state;
+        packet1.tars1_state = packet_in.tars1_state;
         packet1.tars3_state = packet_in.tars3_state;
-        packet1.tars3m_state = packet_in.tars3m_state;
         packet1.arming_state = packet_in.arming_state;
         packet1.main_board_state = packet_in.main_board_state;
         packet1.payload_board_state = packet_in.payload_board_state;
@@ -4184,12 +4305,12 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars3_state , packet1.tars3m_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
+    mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars1_state , packet1.tars3_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars3_state , packet1.tars3m_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
+    mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars1_state , packet1.tars3_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -4202,7 +4323,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars3_state , packet1.tars3m_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
+    mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.rocket_mass , packet1.ox_tank_mass , packet1.ox_vessel_mass , packet1.ox_filling_pressure , packet1.ox_vessel_pressure , packet1.n2_filling_pressure , packet1.n2_vessel_1_pressure , packet1.n2_vessel_2_pressure , packet1.ox_filling_valve_state , packet1.ox_release_valve_state , packet1.ox_detach_state , packet1.ox_venting_valve_state , packet1.n2_filling_valve_state , packet1.n2_release_valve_state , packet1.n2_detach_state , packet1.n2_quenching_valve_state , packet1.n2_3way_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.chamber_valve_state , packet1.gmm_state , packet1.tars1_state , packet1.tars3_state , packet1.arming_state , packet1.cpu_load , packet1.free_heap , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -4650,6 +4771,8 @@ static void mavlink_test_orion(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_set_ignition_time_tc(system_id, component_id, last_msg);
     mavlink_test_set_nitrogen_time_tc(system_id, component_id, last_msg);
     mavlink_test_set_cooling_time_tc(system_id, component_id, last_msg);
+    mavlink_test_get_valve_info_tc(system_id, component_id, last_msg);
+    mavlink_test_valve_info_tm(system_id, component_id, last_msg);
     mavlink_test_set_stepper_angle_tc(system_id, component_id, last_msg);
     mavlink_test_set_stepper_steps_tc(system_id, component_id, last_msg);
     mavlink_test_set_stepper_multiplier_tc(system_id, component_id, last_msg);
diff --git a/mavlink_lib/orion/version.h b/mavlink_lib/orion/version.h
index 5eb96632484058155fa5673b55cc95910e74323f..71dfc7a4ea5625e357a61b1c80e8e067425f8fa5 100644
--- a/mavlink_lib/orion/version.h
+++ b/mavlink_lib/orion/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Fri May 02 2025"
+#define MAVLINK_BUILD_DATE "Wed May 07 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 180
  
diff --git a/message_definitions/orion.xml b/message_definitions/orion.xml
index 9c8a33a449bd4cbc74b0e709dbd69bb27de4bbae..089c4ab4c5c623a46f8f88f1972aea9285d3bb14 100644
--- a/message_definitions/orion.xml
+++ b/message_definitions/orion.xml
@@ -297,6 +297,12 @@
                 <description>Valve enabling N2 to reach the pressure regulator and pressurize the N2O</description>
             </entry>
         </enum>
+        <enum name="TARSList">
+            <description>Enumeration of TARS running states</description>
+            <entry name="TARS_OFF" value="0"></entry>
+            <entry name="TARS_1" value="1"></entry>
+            <entry name="TARS_3" value="2"></entry>
+        </enum>
         <enum name="StepperList">
             <description>Enum of all the steppers</description>
             <entry name="STEPPER_X" value="1"></entry>
@@ -444,9 +450,8 @@
             <field name="n2_release_btn" type="uint8_t">N2 release line pressure valve button state</field>
             <field name="n2_detach_btn" type="uint8_t">N2 quick connector detach button state</field>
             <field name="n2_quenching_btn" type="uint8_t">N2 quenching valve button state</field>
-            <field name="n2_3way_btn" type="uint8_t">N2 3-way valve button state</field>
-            <field name="tars3_btn" type="uint8_t">TARS 3 algorithm button state</field>
-            <field name="tars3m_btn" type="uint8_t">TARS 3M algorithm button state</field>
+            <field name="n2_3way_switch" type="uint8_t">N2 3-way valve switch state</field>
+            <field name="tars_switch" type="uint8_t" enum="TARSList">TARS switch state</field>
             <field name="nitrogen_btn" type="uint8_t">Nitrogen valve button state</field>
             <field name="ignition_btn" type="uint8_t">Ignition button state</field>
             <field name="arm_switch" type="uint8_t">Arming switch state</field>
@@ -463,6 +468,18 @@
             <description>Sets the time in ms that the system will wait before disarming after firing</description>
             <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
         </message>
+        <message id="36" name="GET_VALVE_INFO_TC">
+            <description>Request valve information</description>
+            <field name="servo_id" type="uint8_t" enum="ServosList">The ID of the valve</field>
+        </message>
+        <message id="37" name="VALVE_INFO_TM">
+            <description>TM containing the valve information</description>
+            <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
+            <field name="servo_id" type="uint8_t" enum="ServosList">The ID of the valve</field>
+            <field name="state" type="uint8_t">State of the valve (1 = open, 0 = closed)</field>
+            <field name="close_timestamp" type="uint64_t" units="ms">Time when the valve is scheduled to close (undefined if the valve is closed)</field>
+            <field name="aperture" type="float">Maximum valve aperture (open position) [0-1]</field>
+        </message>
 
         <!-- FROM GROUND TO ARP -->
         <message id="60" name="SET_STEPPER_ANGLE_TC">
@@ -997,8 +1014,8 @@
             <field name="nitrogen_valve_state" type="uint8_t">Rocket main N2 valve state (1: open, 0: close)</field>
             <field name="chamber_valve_state" type="uint8_t">Chamber pressurization valve state (1: enabled, 0: disabled)</field>
             <field name="gmm_state" type="uint8_t">State of the GroundModeManager</field>
+            <field name="tars1_state" type="uint8_t">State of TARS 1</field>
             <field name="tars3_state" type="uint8_t">State of TARS 3</field>
-            <field name="tars3m_state" type="uint8_t">State of TARS 3 Maintenance</field>
             <field name="arming_state" type="uint8_t">Arming state (1: armed, 0: otherwise)</field>
             <field name="cpu_load" type="float">CPU load in percentage</field>
             <field name="free_heap" type="uint32_t">Amount of available heap memory</field>