diff --git a/mavlink_lib.py b/mavlink_lib.py
index eaa8902629cedc689bfa2e5ec6a14ae4ab776dd5..f978399cb403fa0c7b3b436aaef6222d15fc2e61 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -325,8 +325,8 @@ MAV_VN100_ID = 3 # VN100 IMU data
 enums['SensorsTMList'][3] = EnumEntry('MAV_VN100_ID', '''VN100 IMU data''')
 MAV_MPU9250_ID = 4 # MPU9250 IMU data
 enums['SensorsTMList'][4] = EnumEntry('MAV_MPU9250_ID', '''MPU9250 IMU data''')
-MAV_ADS_ID = 5 # ADS 4 channel ADC data
-enums['SensorsTMList'][5] = EnumEntry('MAV_ADS_ID', '''ADS 4 channel ADC data''')
+MAV_ADS_ID = 5 # ADS 8 channel ADC data
+enums['SensorsTMList'][5] = EnumEntry('MAV_ADS_ID', '''ADS 8 channel ADC data''')
 MAV_MS5803_ID = 6 # MS5803 barometer data
 enums['SensorsTMList'][6] = EnumEntry('MAV_MS5803_ID', '''MS5803 barometer data''')
 MAV_BME280_ID = 7 # BME280 barometer data
@@ -1355,23 +1355,23 @@ class MAVLink_adc_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ADC_TM
         name = 'ADC_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'channel_0', 'channel_1', 'channel_2', 'channel_3']
-        ordered_fieldnames = ['timestamp', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float']
+        fieldnames = ['timestamp', 'sensor_name', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7']
+        ordered_fieldnames = ['timestamp', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7', 'sensor_name']
+        fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "channel_0": "V", "channel_1": "V", "channel_2": "V", "channel_3": "V"}
-        format = '<Qffff20s'
-        native_format = bytearray('<Qffffc', 'ascii')
-        orders = [0, 5, 1, 2, 3, 4]
-        lengths = [1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 20]
-        crc_extra = 223
-        unpacker = struct.Struct('<Qffff20s')
+        fieldunits_by_name = {"timestamp": "us", "channel_0": "V", "channel_1": "V", "channel_2": "V", "channel_3": "V", "channel_4": "V", "channel_5": "V", "channel_6": "V", "channel_7": "V"}
+        format = '<Qffffffff20s'
+        native_format = bytearray('<Qffffffffc', 'ascii')
+        orders = [0, 9, 1, 2, 3, 4, 5, 6, 7, 8]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
+        crc_extra = 229
+        unpacker = struct.Struct('<Qffffffff20s')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3):
+        def __init__(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
                 MAVLink_message.__init__(self, MAVLink_adc_tm_message.id, MAVLink_adc_tm_message.name)
                 self._fieldnames = MAVLink_adc_tm_message.fieldnames
                 self._instance_field = MAVLink_adc_tm_message.instance_field
@@ -1382,9 +1382,13 @@ class MAVLink_adc_tm_message(MAVLink_message):
                 self.channel_1 = channel_1
                 self.channel_2 = channel_2
                 self.channel_3 = channel_3
+                self.channel_4 = channel_4
+                self.channel_5 = channel_5
+                self.channel_6 = channel_6
+                self.channel_7 = channel_7
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 223, struct.pack('<Qffff20s', self.timestamp, self.channel_0, self.channel_1, self.channel_2, self.channel_3, self.sensor_name), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 229, struct.pack('<Qffffffff20s', self.timestamp, self.channel_0, self.channel_1, self.channel_2, self.channel_3, self.channel_4, self.channel_5, self.channel_6, self.channel_7, self.sensor_name), force_mavlink1=force_mavlink1)
 
 class MAVLink_voltage_tm_message(MAVLink_message):
         '''
@@ -1670,23 +1674,23 @@ class MAVLink_receiver_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_RECEIVER_TM
         name = 'RECEIVER_TM'
-        fieldnames = ['timestamp', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'main_rx_fei', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'payload_rx_fei']
-        ordered_fieldnames = ['timestamp', 'main_rx_rssi', 'main_rx_fei', 'payload_rx_rssi', 'payload_rx_fei', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'main_radio_present', 'payload_radio_present']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float']
+        fieldnames = ['timestamp', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'main_rx_fei', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'payload_rx_fei', 'ethernet_present', 'ethernet_status', 'battery_voltage']
+        ordered_fieldnames = ['timestamp', 'main_rx_rssi', 'main_rx_fei', 'payload_rx_rssi', 'payload_rx_fei', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint8_t', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "main_rx_fei": "Hz", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "payload_rx_fei": "Hz"}
-        format = '<QffffHHHHHHHHHHBB'
-        native_format = bytearray('<QffffHHHHHHHHHHBB', 'ascii')
-        orders = [0, 15, 5, 6, 7, 8, 9, 1, 2, 16, 10, 11, 12, 13, 14, 3, 4]
-        lengths = [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]
-        crc_extra = 104
-        unpacker = struct.Struct('<QffffHHHHHHHHHHBB')
+        fieldunits_by_name = {"timestamp": "us", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "main_rx_fei": "Hz", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "payload_rx_fei": "Hz", "battery_voltage": "V"}
+        format = '<QfffffHHHHHHHHHHBBBB'
+        native_format = bytearray('<QfffffHHHHHHHHHHBBBB', 'ascii')
+        orders = [0, 16, 6, 7, 8, 9, 10, 1, 2, 17, 11, 12, 13, 14, 15, 3, 4, 18, 19, 5]
+        lengths = [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]
+        crc_extra = 117
+        unpacker = struct.Struct('<QfffffHHHHHHHHHHBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei):
+        def __init__(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
                 MAVLink_message.__init__(self, MAVLink_receiver_tm_message.id, MAVLink_receiver_tm_message.name)
                 self._fieldnames = MAVLink_receiver_tm_message.fieldnames
                 self._instance_field = MAVLink_receiver_tm_message.instance_field
@@ -1708,9 +1712,12 @@ class MAVLink_receiver_tm_message(MAVLink_message):
                 self.payload_rx_bitrate = payload_rx_bitrate
                 self.payload_rx_rssi = payload_rx_rssi
                 self.payload_rx_fei = payload_rx_fei
+                self.ethernet_present = ethernet_present
+                self.ethernet_status = ethernet_status
+                self.battery_voltage = battery_voltage
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 104, struct.pack('<QffffHHHHHHHHHHBB', self.timestamp, self.main_rx_rssi, self.main_rx_fei, self.payload_rx_rssi, self.payload_rx_fei, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.main_radio_present, self.payload_radio_present), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 117, struct.pack('<QfffffHHHHHHHHHHBBBB', self.timestamp, self.main_rx_rssi, self.main_rx_fei, self.payload_rx_rssi, self.payload_rx_fei, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
 
 class MAVLink_sys_tm_message(MAVLink_message):
         '''
@@ -2050,23 +2057,23 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
         name = 'ROCKET_FLIGHT_TM'
-        fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'logger_error']
-        ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'int8_t']
+        fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'logger_error']
+        ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'int8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
         fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
-        format = '<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb'
-        native_format = bytearray('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', 'ascii')
-        orders = [0, 39, 40, 41, 42, 43, 44, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 45, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 46, 47, 48, 49, 35, 36, 37, 38, 50]
-        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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 190
-        unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb')
+        format = '<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb'
+        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', 'ascii')
+        orders = [0, 40, 41, 42, 43, 44, 45, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 46, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 47, 48, 49, 50, 36, 37, 38, 39, 51]
+        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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 214
+        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
+        def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
                 MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.name)
                 self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames
                 self._instance_field = MAVLink_rocket_flight_tm_message.instance_field
@@ -2113,6 +2120,7 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
                 self.nas_bias_x = nas_bias_x
                 self.nas_bias_y = nas_bias_y
                 self.nas_bias_z = nas_bias_z
+                self.pin_quick_connector = pin_quick_connector
                 self.pin_launch = pin_launch
                 self.pin_nosecone = pin_nosecone
                 self.pin_expulsion = pin_expulsion
@@ -2124,7 +2132,7 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
                 self.logger_error = logger_error
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 190, struct.pack('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 214, struct.pack('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.pin_quick_connector, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
 
 class MAVLink_payload_flight_tm_message(MAVLink_message):
         '''
@@ -2132,23 +2140,23 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
         name = 'PAYLOAD_FLIGHT_TM'
-        fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'vsupply_5v', 'temperature', 'logger_error']
-        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'vsupply_5v', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'logger_error']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'int8_t']
+        fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'cutter_presence', 'temperature', 'logger_error']
+        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'cutter_presence', 'logger_error']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', 'int8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "vsupply_5v": "V", "temperature": "degC"}
-        format = '<QffffffffffffffffffffffffffffffffffffffBBBBBb'
-        native_format = bytearray('<QffffffffffffffffffffffffffffffffffffffBBBBBb', 'ascii')
-        orders = [0, 39, 40, 41, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 42, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 43, 34, 35, 36, 37, 38, 44]
+        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
+        format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBb'
+        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', 'ascii')
+        orders = [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 43, 37, 44]
         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, 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, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 71
-        unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffffBBBBBb')
+        crc_extra = 84
+        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBb')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, vsupply_5v, temperature, logger_error):
+        def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error):
                 MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name)
                 self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
                 self._instance_field = MAVLink_payload_flight_tm_message.instance_field
@@ -2195,12 +2203,12 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
                 self.battery_voltage = battery_voltage
                 self.cam_battery_voltage = cam_battery_voltage
                 self.current_consumption = current_consumption
-                self.vsupply_5v = vsupply_5v
+                self.cutter_presence = cutter_presence
                 self.temperature = temperature
                 self.logger_error = logger_error
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 71, struct.pack('<QffffffffffffffffffffffffffffffffffffffBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.vsupply_5v, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.logger_error), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 84, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
 
 class MAVLink_rocket_stats_tm_message(MAVLink_message):
         '''
@@ -2303,29 +2311,29 @@ class MAVLink_gse_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_GSE_TM
         name = 'GSE_TM'
-        fieldnames = ['timestamp', 'loadcell_tank', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'battery_voltage', 'current_consumption', 'main_board_status', 'payload_board_status', 'motor_board_status']
-        ordered_fieldnames = ['timestamp', 'loadcell_tank', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'main_board_status', 'payload_board_status', 'motor_board_status']
+        fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'battery_voltage', 'current_consumption', 'main_board_status', 'payload_board_status', 'motor_board_status']
+        ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'main_board_status', 'payload_board_status', 'motor_board_status']
         fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "loadcell_tank": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar"}
+        fieldunits_by_name = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar"}
         format = '<QffffffBBBBBBBBBB'
         native_format = bytearray('<QffffffBBBBBBBBBB', 'ascii')
         orders = [0, 1, 2, 3, 4, 7, 8, 9, 10, 11, 12, 13, 5, 6, 14, 15, 16]
         lengths = [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]
-        crc_extra = 89
+        crc_extra = 63
         unpacker = struct.Struct('<QffffffBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
+        def __init__(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
                 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
                 self._instance_offset = MAVLink_gse_tm_message.instance_offset
                 self.timestamp = timestamp
-                self.loadcell_tank = loadcell_tank
+                self.loadcell_rocket = loadcell_rocket
                 self.loadcell_vessel = loadcell_vessel
                 self.filling_pressure = filling_pressure
                 self.vessel_pressure = vessel_pressure
@@ -2343,7 +2351,7 @@ class MAVLink_gse_tm_message(MAVLink_message):
                 self.motor_board_status = motor_board_status
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 89, struct.pack('<QffffffBBBBBBBBBB', self.timestamp, self.loadcell_tank, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.arming_state, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.ignition_state, self.tars_state, self.main_board_status, self.payload_board_status, self.motor_board_status), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 63, struct.pack('<QffffffBBBBBBBBBB', self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.arming_state, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.ignition_state, self.tars_state, self.main_board_status, self.payload_board_status, self.motor_board_status), force_mavlink1=force_mavlink1)
 
 class MAVLink_motor_tm_message(MAVLink_message):
         '''
@@ -3395,7 +3403,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.pressure_tm_encode(timestamp, sensor_name, pressure), force_mavlink1=force_mavlink1)
 
-        def adc_tm_encode(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3):
+        def adc_tm_encode(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
                 '''
                 
 
@@ -3405,11 +3413,15 @@ class MAVLink(object):
                 channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
                 channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
                 channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
+                channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
+                channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
+                channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
+                channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
 
                 '''
-                return MAVLink_adc_tm_message(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3)
+                return MAVLink_adc_tm_message(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7)
 
-        def adc_tm_send(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, force_mavlink1=False):
+        def adc_tm_send(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7, force_mavlink1=False):
                 '''
                 
 
@@ -3419,9 +3431,13 @@ class MAVLink(object):
                 channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
                 channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
                 channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
+                channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
+                channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
+                channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
+                channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
 
                 '''
-                return self.send(self.adc_tm_encode(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3), force_mavlink1=force_mavlink1)
+                return self.send(self.adc_tm_encode(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7), force_mavlink1=force_mavlink1)
 
         def voltage_tm_encode(self, timestamp, sensor_name, voltage):
                 '''
@@ -3611,7 +3627,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.pin_tm_encode(timestamp, pin_id, last_change_timestamp, changes_counter, current_state), force_mavlink1=force_mavlink1)
 
-        def receiver_tm_encode(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei):
+        def receiver_tm_encode(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
                 '''
                 
 
@@ -3632,11 +3648,14 @@ class MAVLink(object):
                 payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
                 payload_rx_rssi           : Receive RSSI [dBm] (type:float)
                 payload_rx_fei            : Receive frequency error index [Hz] (type:float)
+                ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+                battery_voltage           : Battery voltage [V] (type:float)
 
                 '''
-                return MAVLink_receiver_tm_message(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei)
+                return MAVLink_receiver_tm_message(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage)
 
-        def receiver_tm_send(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, force_mavlink1=False):
+        def receiver_tm_send(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
                 '''
                 
 
@@ -3657,9 +3676,12 @@ class MAVLink(object):
                 payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
                 payload_rx_rssi           : Receive RSSI [dBm] (type:float)
                 payload_rx_fei            : Receive frequency error index [Hz] (type:float)
+                ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+                battery_voltage           : Battery voltage [V] (type:float)
 
                 '''
-                return self.send(self.receiver_tm_encode(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei), force_mavlink1=force_mavlink1)
+                return self.send(self.receiver_tm_encode(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
 
         def sys_tm_encode(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler):
                 '''
@@ -3957,7 +3979,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1)
 
-        def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
+        def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
                 '''
                 High Rate Telemetry
 
@@ -4003,6 +4025,7 @@ class MAVLink(object):
                 nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
                 nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
                 nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+                pin_quick_connector        : Quick connector detach pin (type:float)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
@@ -4014,9 +4037,9 @@ class MAVLink(object):
                 logger_error              : Logger error (0 = no error, -1 otherwise) (type:int8_t)
 
                 '''
-                return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error)
+                return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error)
 
-        def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error, force_mavlink1=False):
+        def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error, force_mavlink1=False):
                 '''
                 High Rate Telemetry
 
@@ -4062,6 +4085,7 @@ class MAVLink(object):
                 nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
                 nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
                 nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+                pin_quick_connector        : Quick connector detach pin (type:float)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
@@ -4073,9 +4097,9 @@ class MAVLink(object):
                 logger_error              : Logger error (0 = no error, -1 otherwise) (type:int8_t)
 
                 '''
-                return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error), force_mavlink1=force_mavlink1)
+                return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error), force_mavlink1=force_mavlink1)
 
-        def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, vsupply_5v, temperature, logger_error):
+        def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error):
                 '''
                 High Rate Telemetry
 
@@ -4121,14 +4145,14 @@ class MAVLink(object):
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
                 current_consumption        : Battery current [A] (type:float)
-                vsupply_5v                : Power supply 5V [V] (type:float)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 temperature               : Temperature [degC] (type:float)
                 logger_error              : Logger error (0 = no error) (type:int8_t)
 
                 '''
-                return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, vsupply_5v, temperature, logger_error)
+                return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error)
 
-        def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, vsupply_5v, temperature, logger_error, force_mavlink1=False):
+        def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error, force_mavlink1=False):
                 '''
                 High Rate Telemetry
 
@@ -4174,12 +4198,12 @@ class MAVLink(object):
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
                 current_consumption        : Battery current [A] (type:float)
-                vsupply_5v                : Power supply 5V [V] (type:float)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 temperature               : Temperature [degC] (type:float)
                 logger_error              : Logger error (0 = no error) (type:int8_t)
 
                 '''
-                return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, vsupply_5v, temperature, logger_error), force_mavlink1=force_mavlink1)
+                return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error), force_mavlink1=force_mavlink1)
 
         def rocket_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap):
                 '''
@@ -4279,12 +4303,12 @@ class MAVLink(object):
                 '''
                 return self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap), force_mavlink1=force_mavlink1)
 
-        def gse_tm_encode(self, timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
+        def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
                 '''
                 Ground Segment Equipment telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                loadcell_tank             : Rocket weight [kg] (type:float)
+                loadcell_rocket           : Rocket weight [kg] (type:float)
                 loadcell_vessel           : External tank weight [kg] (type:float)
                 filling_pressure          : Refueling line pressure [Bar] (type:float)
                 vessel_pressure           : Vessel tank pressure [Bar] (type:float)
@@ -4302,14 +4326,14 @@ class MAVLink(object):
                 motor_board_status        : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
 
                 '''
-                return MAVLink_gse_tm_message(timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status)
+                return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status)
 
-        def gse_tm_send(self, timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status, force_mavlink1=False):
+        def gse_tm_send(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status, force_mavlink1=False):
                 '''
                 Ground Segment Equipment telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                loadcell_tank             : Rocket weight [kg] (type:float)
+                loadcell_rocket           : Rocket weight [kg] (type:float)
                 loadcell_vessel           : External tank weight [kg] (type:float)
                 filling_pressure          : Refueling line pressure [Bar] (type:float)
                 vessel_pressure           : Vessel tank pressure [Bar] (type:float)
@@ -4327,7 +4351,7 @@ class MAVLink(object):
                 motor_board_status        : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
 
                 '''
-                return self.send(self.gse_tm_encode(timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status), force_mavlink1=force_mavlink1)
+                return self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status), force_mavlink1=force_mavlink1)
 
         def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption):
                 '''
diff --git a/mavlink_lib/gemini/gemini.h b/mavlink_lib/gemini/gemini.h
index 4c35d58a3b4cc2b8c975888195bcaa5c8c626de4..040cb53d6139a41bba26054408e5fc3c88ea700c 100644
--- a/mavlink_lib/gemini/gemini.h
+++ b/mavlink_lib/gemini/gemini.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -4665189295189570415
+#define MAVLINK_THIS_XML_HASH 5610706436220505481
 
 #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, 8, 2, 4, 8, 1, 5, 5, 7, 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, 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, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 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, 46, 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, 14, 14, 46, 28, 27, 53, 77, 29, 172, 166, 92, 76, 42, 34, 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}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 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, 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, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 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, 52, 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, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 34, 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}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 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, 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, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 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, 104, 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, 183, 242, 142, 108, 133, 234, 66, 11, 190, 71, 245, 115, 89, 196, 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}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 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, 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, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 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, 117, 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, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 196, 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}
 #endif
 
 #include "../protocol.h"
@@ -80,7 +80,7 @@ typedef enum SensorsTMList
    MAV_BMX160_ID=2, /* BMX160 IMU data | */
    MAV_VN100_ID=3, /* VN100 IMU data | */
    MAV_MPU9250_ID=4, /* MPU9250 IMU data | */
-   MAV_ADS_ID=5, /* ADS 4 channel ADC data | */
+   MAV_ADS_ID=5, /* ADS 8 channel ADC data | */
    MAV_MS5803_ID=6, /* MS5803 barometer data | */
    MAV_BME280_ID=7, /* BME280 barometer data | */
    MAV_CURRENT_SENSE_ID=8, /* Electrical current sensors data | */
@@ -230,7 +230,7 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -4665189295189570415
+#define MAVLINK_THIS_XML_HASH 5610706436220505481
 
 #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_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_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_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_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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_RECEIVER_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_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
diff --git a/mavlink_lib/gemini/mavlink.h b/mavlink_lib/gemini/mavlink.h
index e53a2adee09b33946177a4820750e591ce1e2a34..01417628cce516747ddcabb55a3b1205f1b9563b 100644
--- a/mavlink_lib/gemini/mavlink.h
+++ b/mavlink_lib/gemini/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -4665189295189570415
+#define MAVLINK_PRIMARY_XML_HASH 5610706436220505481
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/gemini/mavlink_msg_adc_tm.h b/mavlink_lib/gemini/mavlink_msg_adc_tm.h
index 5a38dd53e47ed95cbf189e782af538afdc7b2ec9..04c7612852769618318043c1a36059b224ba9a18 100644
--- a/mavlink_lib/gemini/mavlink_msg_adc_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_adc_tm.h
@@ -10,16 +10,20 @@ typedef struct __mavlink_adc_tm_t {
  float channel_1; /*< [V] ADC voltage measured on channel 1*/
  float channel_2; /*< [V] ADC voltage measured on channel 2*/
  float channel_3; /*< [V] ADC voltage measured on channel 3*/
+ float channel_4; /*< [V] ADC voltage measured on channel 4*/
+ float channel_5; /*< [V] ADC voltage measured on channel 5*/
+ float channel_6; /*< [V] ADC voltage measured on channel 6*/
+ float channel_7; /*< [V] ADC voltage measured on channel 7*/
  char sensor_name[20]; /*<  Sensor name*/
 } mavlink_adc_tm_t;
 
-#define MAVLINK_MSG_ID_ADC_TM_LEN 44
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 44
-#define MAVLINK_MSG_ID_105_LEN 44
-#define MAVLINK_MSG_ID_105_MIN_LEN 44
+#define MAVLINK_MSG_ID_ADC_TM_LEN 60
+#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 60
+#define MAVLINK_MSG_ID_105_LEN 60
+#define MAVLINK_MSG_ID_105_MIN_LEN 60
 
-#define MAVLINK_MSG_ID_ADC_TM_CRC 223
-#define MAVLINK_MSG_ID_105_CRC 223
+#define MAVLINK_MSG_ID_ADC_TM_CRC 229
+#define MAVLINK_MSG_ID_105_CRC 229
 
 #define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_NAME_LEN 20
 
@@ -27,25 +31,33 @@ typedef struct __mavlink_adc_tm_t {
 #define MAVLINK_MESSAGE_INFO_ADC_TM { \
     105, \
     "ADC_TM", \
-    6, \
+    10, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
-         { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_name) }, \
+         { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
          { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
          { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
          { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
          { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
+         { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
+         { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
+         { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
+         { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ADC_TM { \
     "ADC_TM", \
-    6, \
+    10, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
-         { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_name) }, \
+         { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
          { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
          { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
          { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
          { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
+         { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
+         { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
+         { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
+         { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
          } \
 }
 #endif
@@ -62,10 +74,14 @@ typedef struct __mavlink_adc_tm_t {
  * @param channel_1 [V] ADC voltage measured on channel 1
  * @param channel_2 [V] ADC voltage measured on channel 2
  * @param channel_3 [V] ADC voltage measured on channel 3
+ * @param channel_4 [V] ADC voltage measured on channel 4
+ * @param channel_5 [V] ADC voltage measured on channel 5
+ * @param channel_6 [V] ADC voltage measured on channel 6
+ * @param channel_7 [V] ADC voltage measured on channel 7
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
+                               uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
@@ -74,7 +90,11 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 12, channel_1);
     _mav_put_float(buf, 16, channel_2);
     _mav_put_float(buf, 20, channel_3);
-    _mav_put_char_array(buf, 24, sensor_name, 20);
+    _mav_put_float(buf, 24, channel_4);
+    _mav_put_float(buf, 28, channel_5);
+    _mav_put_float(buf, 32, channel_6);
+    _mav_put_float(buf, 36, channel_7);
+    _mav_put_char_array(buf, 40, sensor_name, 20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
 #else
     mavlink_adc_tm_t packet;
@@ -83,6 +103,10 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
     packet.channel_1 = channel_1;
     packet.channel_2 = channel_2;
     packet.channel_3 = channel_3;
+    packet.channel_4 = channel_4;
+    packet.channel_5 = channel_5;
+    packet.channel_6 = channel_6;
+    packet.channel_7 = channel_7;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
 #endif
@@ -103,11 +127,15 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
  * @param channel_1 [V] ADC voltage measured on channel 1
  * @param channel_2 [V] ADC voltage measured on channel 2
  * @param channel_3 [V] ADC voltage measured on channel 3
+ * @param channel_4 [V] ADC voltage measured on channel 4
+ * @param channel_5 [V] ADC voltage measured on channel 5
+ * @param channel_6 [V] ADC voltage measured on channel 6
+ * @param channel_7 [V] ADC voltage measured on channel 7
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3)
+                                   uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3,float channel_4,float channel_5,float channel_6,float channel_7)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
@@ -116,7 +144,11 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 12, channel_1);
     _mav_put_float(buf, 16, channel_2);
     _mav_put_float(buf, 20, channel_3);
-    _mav_put_char_array(buf, 24, sensor_name, 20);
+    _mav_put_float(buf, 24, channel_4);
+    _mav_put_float(buf, 28, channel_5);
+    _mav_put_float(buf, 32, channel_6);
+    _mav_put_float(buf, 36, channel_7);
+    _mav_put_char_array(buf, 40, sensor_name, 20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
 #else
     mavlink_adc_tm_t packet;
@@ -125,6 +157,10 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.channel_1 = channel_1;
     packet.channel_2 = channel_2;
     packet.channel_3 = channel_3;
+    packet.channel_4 = channel_4;
+    packet.channel_5 = channel_5;
+    packet.channel_6 = channel_6;
+    packet.channel_7 = channel_7;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
 #endif
@@ -143,7 +179,7 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
 {
-    return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
+    return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
 }
 
 /**
@@ -157,7 +193,7 @@ static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
 {
-    return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
+    return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
 }
 
 /**
@@ -170,10 +206,14 @@ static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t
  * @param channel_1 [V] ADC voltage measured on channel 1
  * @param channel_2 [V] ADC voltage measured on channel 2
  * @param channel_3 [V] ADC voltage measured on channel 3
+ * @param channel_4 [V] ADC voltage measured on channel 4
+ * @param channel_5 [V] ADC voltage measured on channel 5
+ * @param channel_6 [V] ADC voltage measured on channel 6
+ * @param channel_7 [V] ADC voltage measured on channel 7
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
+static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
@@ -182,7 +222,11 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 12, channel_1);
     _mav_put_float(buf, 16, channel_2);
     _mav_put_float(buf, 20, channel_3);
-    _mav_put_char_array(buf, 24, sensor_name, 20);
+    _mav_put_float(buf, 24, channel_4);
+    _mav_put_float(buf, 28, channel_5);
+    _mav_put_float(buf, 32, channel_6);
+    _mav_put_float(buf, 36, channel_7);
+    _mav_put_char_array(buf, 40, sensor_name, 20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 #else
     mavlink_adc_tm_t packet;
@@ -191,6 +235,10 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
     packet.channel_1 = channel_1;
     packet.channel_2 = channel_2;
     packet.channel_3 = channel_3;
+    packet.channel_4 = channel_4;
+    packet.channel_5 = channel_5;
+    packet.channel_6 = channel_6;
+    packet.channel_7 = channel_7;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 #endif
@@ -204,7 +252,7 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
+    mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 #endif
@@ -218,7 +266,7 @@ static inline void mavlink_msg_adc_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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
+static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -227,7 +275,11 @@ static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 12, channel_1);
     _mav_put_float(buf, 16, channel_2);
     _mav_put_float(buf, 20, channel_3);
-    _mav_put_char_array(buf, 24, sensor_name, 20);
+    _mav_put_float(buf, 24, channel_4);
+    _mav_put_float(buf, 28, channel_5);
+    _mav_put_float(buf, 32, channel_6);
+    _mav_put_float(buf, 36, channel_7);
+    _mav_put_char_array(buf, 40, sensor_name, 20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 #else
     mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
@@ -236,6 +288,10 @@ static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->channel_1 = channel_1;
     packet->channel_2 = channel_2;
     packet->channel_3 = channel_3;
+    packet->channel_4 = channel_4;
+    packet->channel_5 = channel_5;
+    packet->channel_6 = channel_6;
+    packet->channel_7 = channel_7;
     mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 #endif
@@ -264,7 +320,7 @@ static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t*
  */
 static inline uint16_t mavlink_msg_adc_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
 {
-    return _MAV_RETURN_char_array(msg, sensor_name, 20,  24);
+    return _MAV_RETURN_char_array(msg, sensor_name, 20,  40);
 }
 
 /**
@@ -307,6 +363,46 @@ static inline float mavlink_msg_adc_tm_get_channel_3(const mavlink_message_t* ms
     return _MAV_RETURN_float(msg,  20);
 }
 
+/**
+ * @brief Get field channel_4 from adc_tm message
+ *
+ * @return [V] ADC voltage measured on channel 4
+ */
+static inline float mavlink_msg_adc_tm_get_channel_4(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field channel_5 from adc_tm message
+ *
+ * @return [V] ADC voltage measured on channel 5
+ */
+static inline float mavlink_msg_adc_tm_get_channel_5(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field channel_6 from adc_tm message
+ *
+ * @return [V] ADC voltage measured on channel 6
+ */
+static inline float mavlink_msg_adc_tm_get_channel_6(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field channel_7 from adc_tm message
+ *
+ * @return [V] ADC voltage measured on channel 7
+ */
+static inline float mavlink_msg_adc_tm_get_channel_7(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  36);
+}
+
 /**
  * @brief Decode a adc_tm message into a struct
  *
@@ -321,6 +417,10 @@ static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavli
     adc_tm->channel_1 = mavlink_msg_adc_tm_get_channel_1(msg);
     adc_tm->channel_2 = mavlink_msg_adc_tm_get_channel_2(msg);
     adc_tm->channel_3 = mavlink_msg_adc_tm_get_channel_3(msg);
+    adc_tm->channel_4 = mavlink_msg_adc_tm_get_channel_4(msg);
+    adc_tm->channel_5 = mavlink_msg_adc_tm_get_channel_5(msg);
+    adc_tm->channel_6 = mavlink_msg_adc_tm_get_channel_6(msg);
+    adc_tm->channel_7 = mavlink_msg_adc_tm_get_channel_7(msg);
     mavlink_msg_adc_tm_get_sensor_name(msg, adc_tm->sensor_name);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
diff --git a/mavlink_lib/gemini/mavlink_msg_gse_tm.h b/mavlink_lib/gemini/mavlink_msg_gse_tm.h
index 71a0ed13ef80e1b4bc743f2a0c011d2efbe5fcc3..5b5742e639f0cc49886bd5df0396e8821a9075b3 100644
--- a/mavlink_lib/gemini/mavlink_msg_gse_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_gse_tm.h
@@ -6,7 +6,7 @@
 
 typedef struct __mavlink_gse_tm_t {
  uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float loadcell_tank; /*< [kg] Rocket weight*/
+ float loadcell_rocket; /*< [kg] Rocket weight*/
  float loadcell_vessel; /*< [kg] External tank weight*/
  float filling_pressure; /*< [Bar] Refueling line pressure*/
  float vessel_pressure; /*< [Bar] Vessel tank pressure*/
@@ -29,8 +29,8 @@ typedef struct __mavlink_gse_tm_t {
 #define MAVLINK_MSG_ID_212_LEN 42
 #define MAVLINK_MSG_ID_212_MIN_LEN 42
 
-#define MAVLINK_MSG_ID_GSE_TM_CRC 89
-#define MAVLINK_MSG_ID_212_CRC 89
+#define MAVLINK_MSG_ID_GSE_TM_CRC 63
+#define MAVLINK_MSG_ID_212_CRC 63
 
 
 
@@ -40,7 +40,7 @@ typedef struct __mavlink_gse_tm_t {
     "GSE_TM", \
     17, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
-         { "loadcell_tank", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_tank) }, \
+         { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
          { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
          { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
          { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
@@ -63,7 +63,7 @@ typedef struct __mavlink_gse_tm_t {
     "GSE_TM", \
     17, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
-         { "loadcell_tank", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_tank) }, \
+         { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
          { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
          { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
          { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
@@ -90,7 +90,7 @@ typedef struct __mavlink_gse_tm_t {
  * @param msg The MAVLink message to compress the data into
  *
  * @param timestamp [us] Timestamp in microseconds
- * @param loadcell_tank [kg] Rocket weight
+ * @param loadcell_rocket [kg] Rocket weight
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
@@ -109,12 +109,12 @@ 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 loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+                               uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, loadcell_tank);
+    _mav_put_float(buf, 8, loadcell_rocket);
     _mav_put_float(buf, 12, loadcell_vessel);
     _mav_put_float(buf, 16, filling_pressure);
     _mav_put_float(buf, 20, vessel_pressure);
@@ -135,7 +135,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
 #else
     mavlink_gse_tm_t packet;
     packet.timestamp = timestamp;
-    packet.loadcell_tank = loadcell_tank;
+    packet.loadcell_rocket = loadcell_rocket;
     packet.loadcell_vessel = loadcell_vessel;
     packet.filling_pressure = filling_pressure;
     packet.vessel_pressure = vessel_pressure;
@@ -166,7 +166,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
  * @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 in microseconds
- * @param loadcell_tank [kg] Rocket weight
+ * @param loadcell_rocket [kg] Rocket weight
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
@@ -186,12 +186,12 @@ 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 loadcell_tank,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption,uint8_t main_board_status,uint8_t payload_board_status,uint8_t motor_board_status)
+                                   uint64_t timestamp,float loadcell_rocket,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption,uint8_t main_board_status,uint8_t payload_board_status,uint8_t motor_board_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, loadcell_tank);
+    _mav_put_float(buf, 8, loadcell_rocket);
     _mav_put_float(buf, 12, loadcell_vessel);
     _mav_put_float(buf, 16, filling_pressure);
     _mav_put_float(buf, 20, vessel_pressure);
@@ -212,7 +212,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
 #else
     mavlink_gse_tm_t packet;
     packet.timestamp = timestamp;
-    packet.loadcell_tank = loadcell_tank;
+    packet.loadcell_rocket = loadcell_rocket;
     packet.loadcell_vessel = loadcell_vessel;
     packet.filling_pressure = filling_pressure;
     packet.vessel_pressure = vessel_pressure;
@@ -246,7 +246,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->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
 }
 
 /**
@@ -260,7 +260,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->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
 }
 
 /**
@@ -268,7 +268,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t
  * @param chan MAVLink channel to send the message
  *
  * @param timestamp [us] Timestamp in microseconds
- * @param loadcell_tank [kg] Rocket weight
+ * @param loadcell_rocket [kg] Rocket weight
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
@@ -287,12 +287,12 @@ 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 loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, loadcell_tank);
+    _mav_put_float(buf, 8, loadcell_rocket);
     _mav_put_float(buf, 12, loadcell_vessel);
     _mav_put_float(buf, 16, filling_pressure);
     _mav_put_float(buf, 20, vessel_pressure);
@@ -313,7 +313,7 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
 #else
     mavlink_gse_tm_t packet;
     packet.timestamp = timestamp;
-    packet.loadcell_tank = loadcell_tank;
+    packet.loadcell_rocket = loadcell_rocket;
     packet.loadcell_vessel = loadcell_vessel;
     packet.filling_pressure = filling_pressure;
     packet.vessel_pressure = vessel_pressure;
@@ -342,7 +342,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->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
 #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
@@ -356,12 +356,12 @@ 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 loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, loadcell_tank);
+    _mav_put_float(buf, 8, loadcell_rocket);
     _mav_put_float(buf, 12, loadcell_vessel);
     _mav_put_float(buf, 16, filling_pressure);
     _mav_put_float(buf, 20, vessel_pressure);
@@ -382,7 +382,7 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
 #else
     mavlink_gse_tm_t *packet = (mavlink_gse_tm_t *)msgbuf;
     packet->timestamp = timestamp;
-    packet->loadcell_tank = loadcell_tank;
+    packet->loadcell_rocket = loadcell_rocket;
     packet->loadcell_vessel = loadcell_vessel;
     packet->filling_pressure = filling_pressure;
     packet->vessel_pressure = vessel_pressure;
@@ -420,11 +420,11 @@ static inline uint64_t mavlink_msg_gse_tm_get_timestamp(const mavlink_message_t*
 }
 
 /**
- * @brief Get field loadcell_tank from gse_tm message
+ * @brief Get field loadcell_rocket from gse_tm message
  *
  * @return [kg] Rocket weight
  */
-static inline float mavlink_msg_gse_tm_get_loadcell_tank(const mavlink_message_t* msg)
+static inline float mavlink_msg_gse_tm_get_loadcell_rocket(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  8);
 }
@@ -589,7 +589,7 @@ static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavli
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     gse_tm->timestamp = mavlink_msg_gse_tm_get_timestamp(msg);
-    gse_tm->loadcell_tank = mavlink_msg_gse_tm_get_loadcell_tank(msg);
+    gse_tm->loadcell_rocket = mavlink_msg_gse_tm_get_loadcell_rocket(msg);
     gse_tm->loadcell_vessel = mavlink_msg_gse_tm_get_loadcell_vessel(msg);
     gse_tm->filling_pressure = mavlink_msg_gse_tm_get_filling_pressure(msg);
     gse_tm->vessel_pressure = mavlink_msg_gse_tm_get_vessel_pressure(msg);
diff --git a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
index 82b0324448d66f8ea03730b5df9f4a42a5034403..bfe077c3582106f59cfe4d17c86e22f178d0d299 100644
--- a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
@@ -42,23 +42,23 @@ typedef struct __mavlink_payload_flight_tm_t {
  float battery_voltage; /*< [V] Battery voltage*/
  float cam_battery_voltage; /*< [V] Camera battery voltage*/
  float current_consumption; /*< [A] Battery current*/
- float vsupply_5v; /*< [V] Power supply 5V*/
  float temperature; /*< [degC] Temperature*/
  uint8_t fmm_state; /*<  Flight Mode Manager State*/
  uint8_t nas_state; /*<  Navigation System FSM State*/
  uint8_t wes_state; /*<  Wind Estimation System FSM State*/
  uint8_t gps_fix; /*<  GPS fix (1 = fix, 0 = no fix)*/
  uint8_t pin_nosecone; /*<  Nosecone pin status (1 = connected, 0 = disconnected)*/
+ uint8_t cutter_presence; /*<  Cutter presence status (1 = present, 0 = missing)*/
  int8_t logger_error; /*<  Logger error (0 = no error)*/
 } mavlink_payload_flight_tm_t;
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 166
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 166
-#define MAVLINK_MSG_ID_209_LEN 166
-#define MAVLINK_MSG_ID_209_MIN_LEN 166
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 163
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 163
+#define MAVLINK_MSG_ID_209_LEN 163
+#define MAVLINK_MSG_ID_209_MIN_LEN 163
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 71
-#define MAVLINK_MSG_ID_209_CRC 71
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 84
+#define MAVLINK_MSG_ID_209_CRC 84
 
 
 
@@ -68,9 +68,9 @@ typedef struct __mavlink_payload_flight_tm_t {
     "PAYLOAD_FLIGHT_TM", \
     45, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
+         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
          { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
@@ -84,7 +84,7 @@ typedef struct __mavlink_payload_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
@@ -105,13 +105,13 @@ typedef struct __mavlink_payload_flight_tm_t {
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
          { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
          { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
          { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
          { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
-         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 165, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
          } \
 }
 #else
@@ -119,9 +119,9 @@ typedef struct __mavlink_payload_flight_tm_t {
     "PAYLOAD_FLIGHT_TM", \
     45, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
+         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
          { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
@@ -135,7 +135,7 @@ typedef struct __mavlink_payload_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
@@ -156,13 +156,13 @@ typedef struct __mavlink_payload_flight_tm_t {
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
          { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
          { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
          { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
          { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
-         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 165, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
          } \
 }
 #endif
@@ -215,13 +215,13 @@ typedef struct __mavlink_payload_flight_tm_t {
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
  * @param current_consumption [A] Battery current
- * @param vsupply_5v [V] Power supply 5V
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
  * @param logger_error  Logger error (0 = no error)
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error)
+                               uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -262,14 +262,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
     _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, vsupply_5v);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, fmm_state);
-    _mav_put_uint8_t(buf, 161, nas_state);
-    _mav_put_uint8_t(buf, 162, wes_state);
-    _mav_put_uint8_t(buf, 163, gps_fix);
-    _mav_put_uint8_t(buf, 164, pin_nosecone);
-    _mav_put_int8_t(buf, 165, logger_error);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, fmm_state);
+    _mav_put_uint8_t(buf, 157, nas_state);
+    _mav_put_uint8_t(buf, 158, wes_state);
+    _mav_put_uint8_t(buf, 159, gps_fix);
+    _mav_put_uint8_t(buf, 160, pin_nosecone);
+    _mav_put_uint8_t(buf, 161, cutter_presence);
+    _mav_put_int8_t(buf, 162, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -311,13 +311,13 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.vsupply_5v = vsupply_5v;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
     packet.pin_nosecone = pin_nosecone;
+    packet.cutter_presence = cutter_presence;
     packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
@@ -375,14 +375,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
  * @param current_consumption [A] Battery current
- * @param vsupply_5v [V] Power supply 5V
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
  * @param logger_error  Logger error (0 = no error)
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float cam_battery_voltage,float current_consumption,float vsupply_5v,float temperature,int8_t logger_error)
+                                   uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float cam_battery_voltage,float current_consumption,uint8_t cutter_presence,float temperature,int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -423,14 +423,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
     _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, vsupply_5v);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, fmm_state);
-    _mav_put_uint8_t(buf, 161, nas_state);
-    _mav_put_uint8_t(buf, 162, wes_state);
-    _mav_put_uint8_t(buf, 163, gps_fix);
-    _mav_put_uint8_t(buf, 164, pin_nosecone);
-    _mav_put_int8_t(buf, 165, logger_error);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, fmm_state);
+    _mav_put_uint8_t(buf, 157, nas_state);
+    _mav_put_uint8_t(buf, 158, wes_state);
+    _mav_put_uint8_t(buf, 159, gps_fix);
+    _mav_put_uint8_t(buf, 160, pin_nosecone);
+    _mav_put_uint8_t(buf, 161, cutter_presence);
+    _mav_put_int8_t(buf, 162, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -472,13 +472,13 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.vsupply_5v = vsupply_5v;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
     packet.pin_nosecone = pin_nosecone;
+    packet.cutter_presence = cutter_presence;
     packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
@@ -498,7 +498,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
-    return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 }
 
 /**
@@ -512,7 +512,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, u
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
-    return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 }
 
 /**
@@ -561,13 +561,13 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
  * @param current_consumption [A] Battery current
- * @param vsupply_5v [V] Power supply 5V
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
  * @param logger_error  Logger error (0 = no error)
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error)
+static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -608,14 +608,14 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
     _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, vsupply_5v);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, fmm_state);
-    _mav_put_uint8_t(buf, 161, nas_state);
-    _mav_put_uint8_t(buf, 162, wes_state);
-    _mav_put_uint8_t(buf, 163, gps_fix);
-    _mav_put_uint8_t(buf, 164, pin_nosecone);
-    _mav_put_int8_t(buf, 165, logger_error);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, fmm_state);
+    _mav_put_uint8_t(buf, 157, nas_state);
+    _mav_put_uint8_t(buf, 158, wes_state);
+    _mav_put_uint8_t(buf, 159, gps_fix);
+    _mav_put_uint8_t(buf, 160, pin_nosecone);
+    _mav_put_uint8_t(buf, 161, cutter_presence);
+    _mav_put_int8_t(buf, 162, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #else
@@ -657,13 +657,13 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.vsupply_5v = vsupply_5v;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
     packet.pin_nosecone = pin_nosecone;
+    packet.cutter_presence = cutter_presence;
     packet.logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
@@ -678,7 +678,7 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
 static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #endif
@@ -692,7 +692,7 @@ static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t c
   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_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error)
+static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -733,14 +733,14 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
     _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, vsupply_5v);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, fmm_state);
-    _mav_put_uint8_t(buf, 161, nas_state);
-    _mav_put_uint8_t(buf, 162, wes_state);
-    _mav_put_uint8_t(buf, 163, gps_fix);
-    _mav_put_uint8_t(buf, 164, pin_nosecone);
-    _mav_put_int8_t(buf, 165, logger_error);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, fmm_state);
+    _mav_put_uint8_t(buf, 157, nas_state);
+    _mav_put_uint8_t(buf, 158, wes_state);
+    _mav_put_uint8_t(buf, 159, gps_fix);
+    _mav_put_uint8_t(buf, 160, pin_nosecone);
+    _mav_put_uint8_t(buf, 161, cutter_presence);
+    _mav_put_int8_t(buf, 162, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #else
@@ -782,13 +782,13 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg
     packet->battery_voltage = battery_voltage;
     packet->cam_battery_voltage = cam_battery_voltage;
     packet->current_consumption = current_consumption;
-    packet->vsupply_5v = vsupply_5v;
     packet->temperature = temperature;
     packet->fmm_state = fmm_state;
     packet->nas_state = nas_state;
     packet->wes_state = wes_state;
     packet->gps_fix = gps_fix;
     packet->pin_nosecone = pin_nosecone;
+    packet->cutter_presence = cutter_presence;
     packet->logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
@@ -818,7 +818,7 @@ static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
@@ -828,7 +828,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  161);
+    return _MAV_RETURN_uint8_t(msg,  157);
 }
 
 /**
@@ -838,7 +838,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_wes_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  162);
+    return _MAV_RETURN_uint8_t(msg,  158);
 }
 
 /**
@@ -978,7 +978,7 @@ static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_messag
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  163);
+    return _MAV_RETURN_uint8_t(msg,  159);
 }
 
 /**
@@ -1188,7 +1188,7 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_messag
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  164);
+    return _MAV_RETURN_uint8_t(msg,  160);
 }
 
 /**
@@ -1222,13 +1222,13 @@ static inline float mavlink_msg_payload_flight_tm_get_current_consumption(const
 }
 
 /**
- * @brief Get field vsupply_5v from payload_flight_tm message
+ * @brief Get field cutter_presence from payload_flight_tm message
  *
- * @return [V] Power supply 5V
+ * @return  Cutter presence status (1 = present, 0 = missing)
  */
-static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  152);
+    return _MAV_RETURN_uint8_t(msg,  161);
 }
 
 /**
@@ -1238,7 +1238,7 @@ static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_m
  */
 static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  156);
+    return _MAV_RETURN_float(msg,  152);
 }
 
 /**
@@ -1248,7 +1248,7 @@ static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_
  */
 static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int8_t(msg,  165);
+    return _MAV_RETURN_int8_t(msg,  162);
 }
 
 /**
@@ -1297,13 +1297,13 @@ static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t*
     payload_flight_tm->battery_voltage = mavlink_msg_payload_flight_tm_get_battery_voltage(msg);
     payload_flight_tm->cam_battery_voltage = mavlink_msg_payload_flight_tm_get_cam_battery_voltage(msg);
     payload_flight_tm->current_consumption = mavlink_msg_payload_flight_tm_get_current_consumption(msg);
-    payload_flight_tm->vsupply_5v = mavlink_msg_payload_flight_tm_get_vsupply_5v(msg);
     payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg);
     payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg);
     payload_flight_tm->nas_state = mavlink_msg_payload_flight_tm_get_nas_state(msg);
     payload_flight_tm->wes_state = mavlink_msg_payload_flight_tm_get_wes_state(msg);
     payload_flight_tm->gps_fix = mavlink_msg_payload_flight_tm_get_gps_fix(msg);
     payload_flight_tm->pin_nosecone = mavlink_msg_payload_flight_tm_get_pin_nosecone(msg);
+    payload_flight_tm->cutter_presence = mavlink_msg_payload_flight_tm_get_cutter_presence(msg);
     payload_flight_tm->logger_error = mavlink_msg_payload_flight_tm_get_logger_error(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN;
diff --git a/mavlink_lib/gemini/mavlink_msg_receiver_tm.h b/mavlink_lib/gemini/mavlink_msg_receiver_tm.h
index bf484b63adb0c91d1ebbdaf9e3823a2c04d7b906..d87647ee1d1ad1a8b59605721d6fca6469887093 100644
--- a/mavlink_lib/gemini/mavlink_msg_receiver_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_receiver_tm.h
@@ -10,6 +10,7 @@ typedef struct __mavlink_receiver_tm_t {
  float main_rx_fei; /*< [Hz] Receive frequency error index*/
  float payload_rx_rssi; /*< [dBm] Receive RSSI*/
  float payload_rx_fei; /*< [Hz] Receive frequency error index*/
+ float battery_voltage; /*< [V] Battery voltage*/
  uint16_t main_packet_tx_error_count; /*<  Number of errors during send*/
  uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
  uint16_t main_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
@@ -22,15 +23,17 @@ typedef struct __mavlink_receiver_tm_t {
  uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
  uint8_t main_radio_present; /*<  Boolean indicating the presence of the main radio*/
  uint8_t payload_radio_present; /*<  Boolean indicating the presence of the payload radio*/
+ uint8_t ethernet_present; /*<  Boolean indicating the presence of the ethernet module*/
+ uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
 } mavlink_receiver_tm_t;
 
-#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 46
-#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_150_LEN 46
-#define MAVLINK_MSG_ID_150_MIN_LEN 46
+#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 52
+#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 52
+#define MAVLINK_MSG_ID_150_LEN 52
+#define MAVLINK_MSG_ID_150_MIN_LEN 52
 
-#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 104
-#define MAVLINK_MSG_ID_150_CRC 104
+#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 117
+#define MAVLINK_MSG_ID_150_CRC 117
 
 
 
@@ -38,47 +41,53 @@ typedef struct __mavlink_receiver_tm_t {
 #define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
     150, \
     "RECEIVER_TM", \
-    17, \
+    20, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
+         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
+         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
+         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
+         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
+         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
+         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
          { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
          { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
+         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
+         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
+         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
+         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
+         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
+         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
          { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
          { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
+         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
     "RECEIVER_TM", \
-    17, \
+    20, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
+         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
+         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
+         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
+         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
+         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
+         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
          { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
          { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
+         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
+         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
+         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
+         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
+         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
+         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
          { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
          { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
+         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
          } \
 }
 #endif
@@ -106,10 +115,13 @@ typedef struct __mavlink_receiver_tm_t {
  * @param payload_rx_bitrate [b/s] Receive bitrate
  * @param payload_rx_rssi [dBm] Receive RSSI
  * @param payload_rx_fei [Hz] Receive frequency error index
+ * @param ethernet_present  Boolean indicating the presence of the ethernet module
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @param battery_voltage [V] Battery voltage
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei)
+                               uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
@@ -118,18 +130,21 @@ static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 12, main_rx_fei);
     _mav_put_float(buf, 16, payload_rx_rssi);
     _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_uint16_t(buf, 24, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 26, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 28, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 30, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 32, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 34, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 36, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 40, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 42, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 44, main_radio_present);
-    _mav_put_uint8_t(buf, 45, payload_radio_present);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 48, main_radio_present);
+    _mav_put_uint8_t(buf, 49, payload_radio_present);
+    _mav_put_uint8_t(buf, 50, ethernet_present);
+    _mav_put_uint8_t(buf, 51, ethernet_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
 #else
@@ -139,6 +154,7 @@ static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t c
     packet.main_rx_fei = main_rx_fei;
     packet.payload_rx_rssi = payload_rx_rssi;
     packet.payload_rx_fei = payload_rx_fei;
+    packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
@@ -151,6 +167,8 @@ static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t c
     packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.main_radio_present = main_radio_present;
     packet.payload_radio_present = payload_radio_present;
+    packet.ethernet_present = ethernet_present;
+    packet.ethernet_status = ethernet_status;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
 #endif
@@ -182,11 +200,14 @@ static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t c
  * @param payload_rx_bitrate [b/s] Receive bitrate
  * @param payload_rx_rssi [dBm] Receive RSSI
  * @param payload_rx_fei [Hz] Receive frequency error index
+ * @param ethernet_present  Boolean indicating the presence of the ethernet module
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @param battery_voltage [V] Battery voltage
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,float main_rx_fei,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,float payload_rx_fei)
+                                   uint64_t timestamp,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,float main_rx_fei,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,float payload_rx_fei,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
@@ -195,18 +216,21 @@ static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint
     _mav_put_float(buf, 12, main_rx_fei);
     _mav_put_float(buf, 16, payload_rx_rssi);
     _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_uint16_t(buf, 24, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 26, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 28, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 30, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 32, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 34, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 36, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 40, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 42, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 44, main_radio_present);
-    _mav_put_uint8_t(buf, 45, payload_radio_present);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 48, main_radio_present);
+    _mav_put_uint8_t(buf, 49, payload_radio_present);
+    _mav_put_uint8_t(buf, 50, ethernet_present);
+    _mav_put_uint8_t(buf, 51, ethernet_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
 #else
@@ -216,6 +240,7 @@ static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint
     packet.main_rx_fei = main_rx_fei;
     packet.payload_rx_rssi = payload_rx_rssi;
     packet.payload_rx_fei = payload_rx_fei;
+    packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
@@ -228,6 +253,8 @@ static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint
     packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.main_radio_present = main_radio_present;
     packet.payload_radio_present = payload_radio_present;
+    packet.ethernet_present = ethernet_present;
+    packet.ethernet_status = ethernet_status;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
 #endif
@@ -246,7 +273,7 @@ static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint
  */
 static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
 {
-    return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei);
+    return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
 }
 
 /**
@@ -260,7 +287,7 @@ static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t
  */
 static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
 {
-    return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei);
+    return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
 }
 
 /**
@@ -284,10 +311,13 @@ static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, ui
  * @param payload_rx_bitrate [b/s] Receive bitrate
  * @param payload_rx_rssi [dBm] Receive RSSI
  * @param payload_rx_fei [Hz] Receive frequency error index
+ * @param ethernet_present  Boolean indicating the presence of the ethernet module
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @param battery_voltage [V] Battery voltage
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei)
+static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
@@ -296,18 +326,21 @@ static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t
     _mav_put_float(buf, 12, main_rx_fei);
     _mav_put_float(buf, 16, payload_rx_rssi);
     _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_uint16_t(buf, 24, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 26, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 28, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 30, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 32, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 34, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 36, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 40, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 42, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 44, main_radio_present);
-    _mav_put_uint8_t(buf, 45, payload_radio_present);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 48, main_radio_present);
+    _mav_put_uint8_t(buf, 49, payload_radio_present);
+    _mav_put_uint8_t(buf, 50, ethernet_present);
+    _mav_put_uint8_t(buf, 51, ethernet_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
 #else
@@ -317,6 +350,7 @@ static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t
     packet.main_rx_fei = main_rx_fei;
     packet.payload_rx_rssi = payload_rx_rssi;
     packet.payload_rx_fei = payload_rx_fei;
+    packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
@@ -329,6 +363,8 @@ static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t
     packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.main_radio_present = main_radio_present;
     packet.payload_radio_present = payload_radio_present;
+    packet.ethernet_present = ethernet_present;
+    packet.ethernet_status = ethernet_status;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)&packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
 #endif
@@ -342,7 +378,7 @@ static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t
 static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, const mavlink_receiver_tm_t* receiver_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei);
+    mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)receiver_tm, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
 #endif
@@ -356,7 +392,7 @@ static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, c
   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_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei)
+static inline void mavlink_msg_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -365,18 +401,21 @@ static inline void mavlink_msg_receiver_tm_send_buf(mavlink_message_t *msgbuf, m
     _mav_put_float(buf, 12, main_rx_fei);
     _mav_put_float(buf, 16, payload_rx_rssi);
     _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_uint16_t(buf, 24, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 26, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 28, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 30, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 32, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 34, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 36, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 40, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 42, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 44, main_radio_present);
-    _mav_put_uint8_t(buf, 45, payload_radio_present);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 48, main_radio_present);
+    _mav_put_uint8_t(buf, 49, payload_radio_present);
+    _mav_put_uint8_t(buf, 50, ethernet_present);
+    _mav_put_uint8_t(buf, 51, ethernet_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
 #else
@@ -386,6 +425,7 @@ static inline void mavlink_msg_receiver_tm_send_buf(mavlink_message_t *msgbuf, m
     packet->main_rx_fei = main_rx_fei;
     packet->payload_rx_rssi = payload_rx_rssi;
     packet->payload_rx_fei = payload_rx_fei;
+    packet->battery_voltage = battery_voltage;
     packet->main_packet_tx_error_count = main_packet_tx_error_count;
     packet->main_tx_bitrate = main_tx_bitrate;
     packet->main_packet_rx_success_count = main_packet_rx_success_count;
@@ -398,6 +438,8 @@ static inline void mavlink_msg_receiver_tm_send_buf(mavlink_message_t *msgbuf, m
     packet->payload_rx_bitrate = payload_rx_bitrate;
     packet->main_radio_present = main_radio_present;
     packet->payload_radio_present = payload_radio_present;
+    packet->ethernet_present = ethernet_present;
+    packet->ethernet_status = ethernet_status;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
 #endif
@@ -426,7 +468,7 @@ static inline uint64_t mavlink_msg_receiver_tm_get_timestamp(const mavlink_messa
  */
 static inline uint8_t mavlink_msg_receiver_tm_get_main_radio_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  44);
+    return _MAV_RETURN_uint8_t(msg,  48);
 }
 
 /**
@@ -436,7 +478,7 @@ static inline uint8_t mavlink_msg_receiver_tm_get_main_radio_present(const mavli
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  24);
+    return _MAV_RETURN_uint16_t(msg,  28);
 }
 
 /**
@@ -446,7 +488,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_tx_error_count(co
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  26);
+    return _MAV_RETURN_uint16_t(msg,  30);
 }
 
 /**
@@ -456,7 +498,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_main_tx_bitrate(const mavlink
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  28);
+    return _MAV_RETURN_uint16_t(msg,  32);
 }
 
 /**
@@ -466,7 +508,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_success_count(
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  30);
+    return _MAV_RETURN_uint16_t(msg,  34);
 }
 
 /**
@@ -476,7 +518,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(con
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  32);
+    return _MAV_RETURN_uint16_t(msg,  36);
 }
 
 /**
@@ -506,7 +548,7 @@ static inline float mavlink_msg_receiver_tm_get_main_rx_fei(const mavlink_messag
  */
 static inline uint8_t mavlink_msg_receiver_tm_get_payload_radio_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  45);
+    return _MAV_RETURN_uint8_t(msg,  49);
 }
 
 /**
@@ -516,7 +558,7 @@ static inline uint8_t mavlink_msg_receiver_tm_get_payload_radio_present(const ma
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  34);
+    return _MAV_RETURN_uint16_t(msg,  38);
 }
 
 /**
@@ -526,7 +568,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_tx_error_count
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  36);
+    return _MAV_RETURN_uint16_t(msg,  40);
 }
 
 /**
@@ -536,7 +578,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_payload_tx_bitrate(const mavl
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  38);
+    return _MAV_RETURN_uint16_t(msg,  42);
 }
 
 /**
@@ -546,7 +588,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_success_cou
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  40);
+    return _MAV_RETURN_uint16_t(msg,  44);
 }
 
 /**
@@ -556,7 +598,7 @@ static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(
  */
 static inline uint16_t mavlink_msg_receiver_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  42);
+    return _MAV_RETURN_uint16_t(msg,  46);
 }
 
 /**
@@ -579,6 +621,36 @@ static inline float mavlink_msg_receiver_tm_get_payload_rx_fei(const mavlink_mes
     return _MAV_RETURN_float(msg,  20);
 }
 
+/**
+ * @brief Get field ethernet_present from receiver_tm message
+ *
+ * @return  Boolean indicating the presence of the ethernet module
+ */
+static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_present(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  50);
+}
+
+/**
+ * @brief Get field ethernet_status from receiver_tm message
+ *
+ * @return  Status flag indicating the status of the ethernet PHY
+ */
+static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  51);
+}
+
+/**
+ * @brief Get field battery_voltage from receiver_tm message
+ *
+ * @return [V] Battery voltage
+ */
+static inline float mavlink_msg_receiver_tm_get_battery_voltage(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
 /**
  * @brief Decode a receiver_tm message into a struct
  *
@@ -593,6 +665,7 @@ static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg,
     receiver_tm->main_rx_fei = mavlink_msg_receiver_tm_get_main_rx_fei(msg);
     receiver_tm->payload_rx_rssi = mavlink_msg_receiver_tm_get_payload_rx_rssi(msg);
     receiver_tm->payload_rx_fei = mavlink_msg_receiver_tm_get_payload_rx_fei(msg);
+    receiver_tm->battery_voltage = mavlink_msg_receiver_tm_get_battery_voltage(msg);
     receiver_tm->main_packet_tx_error_count = mavlink_msg_receiver_tm_get_main_packet_tx_error_count(msg);
     receiver_tm->main_tx_bitrate = mavlink_msg_receiver_tm_get_main_tx_bitrate(msg);
     receiver_tm->main_packet_rx_success_count = mavlink_msg_receiver_tm_get_main_packet_rx_success_count(msg);
@@ -605,6 +678,8 @@ static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg,
     receiver_tm->payload_rx_bitrate = mavlink_msg_receiver_tm_get_payload_rx_bitrate(msg);
     receiver_tm->main_radio_present = mavlink_msg_receiver_tm_get_main_radio_present(msg);
     receiver_tm->payload_radio_present = mavlink_msg_receiver_tm_get_payload_radio_present(msg);
+    receiver_tm->ethernet_present = mavlink_msg_receiver_tm_get_ethernet_present(msg);
+    receiver_tm->ethernet_status = mavlink_msg_receiver_tm_get_ethernet_status(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_RECEIVER_TM_LEN? msg->len : MAVLINK_MSG_ID_RECEIVER_TM_LEN;
         memset(receiver_tm, 0, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
diff --git a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h
index 844836c0fc95e18565913f186cd3a433eefc69a1..e3949ca456e8719920b4822b1e08e708b2e51b26 100644
--- a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h
@@ -40,6 +40,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  float nas_bias_x; /*<  Navigation system gyroscope bias on x axis*/
  float nas_bias_y; /*<  Navigation system gyroscope bias on y axis*/
  float nas_bias_z; /*<  Navigation system gyroscope bias on z axis*/
+ float pin_quick_connector; /*<   Quick connector detach pin */
  float battery_voltage; /*< [V] Battery voltage*/
  float cam_battery_voltage; /*< [V] Camera battery voltage*/
  float current_consumption; /*< [A] Battery current*/
@@ -58,13 +59,13 @@ typedef struct __mavlink_rocket_flight_tm_t {
  int8_t logger_error; /*<  Logger error (0 = no error, -1 otherwise)*/
 } mavlink_rocket_flight_tm_t;
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 172
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 172
-#define MAVLINK_MSG_ID_208_LEN 172
-#define MAVLINK_MSG_ID_208_MIN_LEN 172
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 176
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 176
+#define MAVLINK_MSG_ID_208_LEN 176
+#define MAVLINK_MSG_ID_208_MIN_LEN 176
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 190
-#define MAVLINK_MSG_ID_208_CRC 190
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 214
+#define MAVLINK_MSG_ID_208_CRC 214
 
 
 
@@ -72,14 +73,14 @@ typedef struct __mavlink_rocket_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     208, \
     "ROCKET_FLIGHT_TM", \
-    51, \
+    52, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
-         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
+         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
+         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
+         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
+         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
          { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
@@ -97,7 +98,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
@@ -115,28 +116,29 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
          { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
-         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
+         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
+         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     "ROCKET_FLIGHT_TM", \
-    51, \
+    52, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
-         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
+         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
+         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
+         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
+         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
          { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
@@ -154,7 +156,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
@@ -172,15 +174,16 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
          { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
-         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
+         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
+         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
          } \
 }
 #endif
@@ -233,6 +236,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  * @param nas_bias_x  Navigation system gyroscope bias on x axis
  * @param nas_bias_y  Navigation system gyroscope bias on y axis
  * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param pin_quick_connector   Quick connector detach pin 
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
@@ -245,7 +249,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -284,22 +288,23 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, battery_voltage);
-    _mav_put_float(buf, 148, cam_battery_voltage);
-    _mav_put_float(buf, 152, current_consumption);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, ada_state);
-    _mav_put_uint8_t(buf, 161, fmm_state);
-    _mav_put_uint8_t(buf, 162, dpl_state);
-    _mav_put_uint8_t(buf, 163, abk_state);
-    _mav_put_uint8_t(buf, 164, nas_state);
-    _mav_put_uint8_t(buf, 165, mea_state);
-    _mav_put_uint8_t(buf, 166, gps_fix);
-    _mav_put_uint8_t(buf, 167, pin_launch);
-    _mav_put_uint8_t(buf, 168, pin_nosecone);
-    _mav_put_uint8_t(buf, 169, pin_expulsion);
-    _mav_put_uint8_t(buf, 170, cutter_presence);
-    _mav_put_int8_t(buf, 171, logger_error);
+    _mav_put_float(buf, 144, pin_quick_connector);
+    _mav_put_float(buf, 148, battery_voltage);
+    _mav_put_float(buf, 152, cam_battery_voltage);
+    _mav_put_float(buf, 156, current_consumption);
+    _mav_put_float(buf, 160, temperature);
+    _mav_put_uint8_t(buf, 164, ada_state);
+    _mav_put_uint8_t(buf, 165, fmm_state);
+    _mav_put_uint8_t(buf, 166, dpl_state);
+    _mav_put_uint8_t(buf, 167, abk_state);
+    _mav_put_uint8_t(buf, 168, nas_state);
+    _mav_put_uint8_t(buf, 169, mea_state);
+    _mav_put_uint8_t(buf, 170, gps_fix);
+    _mav_put_uint8_t(buf, 171, pin_launch);
+    _mav_put_uint8_t(buf, 172, pin_nosecone);
+    _mav_put_uint8_t(buf, 173, pin_expulsion);
+    _mav_put_uint8_t(buf, 174, cutter_presence);
+    _mav_put_int8_t(buf, 175, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -339,6 +344,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
+    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
@@ -411,6 +417,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
  * @param nas_bias_x  Navigation system gyroscope bias on x axis
  * @param nas_bias_y  Navigation system gyroscope bias on y axis
  * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param pin_quick_connector   Quick connector detach pin 
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
@@ -424,7 +431,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float current_consumption,float temperature,int8_t logger_error)
+                                   uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float pin_quick_connector,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float current_consumption,float temperature,int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -463,22 +470,23 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, battery_voltage);
-    _mav_put_float(buf, 148, cam_battery_voltage);
-    _mav_put_float(buf, 152, current_consumption);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, ada_state);
-    _mav_put_uint8_t(buf, 161, fmm_state);
-    _mav_put_uint8_t(buf, 162, dpl_state);
-    _mav_put_uint8_t(buf, 163, abk_state);
-    _mav_put_uint8_t(buf, 164, nas_state);
-    _mav_put_uint8_t(buf, 165, mea_state);
-    _mav_put_uint8_t(buf, 166, gps_fix);
-    _mav_put_uint8_t(buf, 167, pin_launch);
-    _mav_put_uint8_t(buf, 168, pin_nosecone);
-    _mav_put_uint8_t(buf, 169, pin_expulsion);
-    _mav_put_uint8_t(buf, 170, cutter_presence);
-    _mav_put_int8_t(buf, 171, logger_error);
+    _mav_put_float(buf, 144, pin_quick_connector);
+    _mav_put_float(buf, 148, battery_voltage);
+    _mav_put_float(buf, 152, cam_battery_voltage);
+    _mav_put_float(buf, 156, current_consumption);
+    _mav_put_float(buf, 160, temperature);
+    _mav_put_uint8_t(buf, 164, ada_state);
+    _mav_put_uint8_t(buf, 165, fmm_state);
+    _mav_put_uint8_t(buf, 166, dpl_state);
+    _mav_put_uint8_t(buf, 167, abk_state);
+    _mav_put_uint8_t(buf, 168, nas_state);
+    _mav_put_uint8_t(buf, 169, mea_state);
+    _mav_put_uint8_t(buf, 170, gps_fix);
+    _mav_put_uint8_t(buf, 171, pin_launch);
+    _mav_put_uint8_t(buf, 172, pin_nosecone);
+    _mav_put_uint8_t(buf, 173, pin_expulsion);
+    _mav_put_uint8_t(buf, 174, cutter_presence);
+    _mav_put_int8_t(buf, 175, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -518,6 +526,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
+    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
@@ -552,7 +561,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 }
 
 /**
@@ -566,7 +575,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 }
 
 /**
@@ -615,6 +624,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
  * @param nas_bias_x  Navigation system gyroscope bias on x axis
  * @param nas_bias_y  Navigation system gyroscope bias on y axis
  * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param pin_quick_connector   Quick connector detach pin 
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
@@ -627,7 +637,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -666,22 +676,23 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, battery_voltage);
-    _mav_put_float(buf, 148, cam_battery_voltage);
-    _mav_put_float(buf, 152, current_consumption);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, ada_state);
-    _mav_put_uint8_t(buf, 161, fmm_state);
-    _mav_put_uint8_t(buf, 162, dpl_state);
-    _mav_put_uint8_t(buf, 163, abk_state);
-    _mav_put_uint8_t(buf, 164, nas_state);
-    _mav_put_uint8_t(buf, 165, mea_state);
-    _mav_put_uint8_t(buf, 166, gps_fix);
-    _mav_put_uint8_t(buf, 167, pin_launch);
-    _mav_put_uint8_t(buf, 168, pin_nosecone);
-    _mav_put_uint8_t(buf, 169, pin_expulsion);
-    _mav_put_uint8_t(buf, 170, cutter_presence);
-    _mav_put_int8_t(buf, 171, logger_error);
+    _mav_put_float(buf, 144, pin_quick_connector);
+    _mav_put_float(buf, 148, battery_voltage);
+    _mav_put_float(buf, 152, cam_battery_voltage);
+    _mav_put_float(buf, 156, current_consumption);
+    _mav_put_float(buf, 160, temperature);
+    _mav_put_uint8_t(buf, 164, ada_state);
+    _mav_put_uint8_t(buf, 165, fmm_state);
+    _mav_put_uint8_t(buf, 166, dpl_state);
+    _mav_put_uint8_t(buf, 167, abk_state);
+    _mav_put_uint8_t(buf, 168, nas_state);
+    _mav_put_uint8_t(buf, 169, mea_state);
+    _mav_put_uint8_t(buf, 170, gps_fix);
+    _mav_put_uint8_t(buf, 171, pin_launch);
+    _mav_put_uint8_t(buf, 172, pin_nosecone);
+    _mav_put_uint8_t(buf, 173, pin_expulsion);
+    _mav_put_uint8_t(buf, 174, cutter_presence);
+    _mav_put_int8_t(buf, 175, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #else
@@ -721,6 +732,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
+    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
     packet.current_consumption = current_consumption;
@@ -750,7 +762,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
 static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #endif
@@ -764,7 +776,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t ch
   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_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -803,22 +815,23 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, battery_voltage);
-    _mav_put_float(buf, 148, cam_battery_voltage);
-    _mav_put_float(buf, 152, current_consumption);
-    _mav_put_float(buf, 156, temperature);
-    _mav_put_uint8_t(buf, 160, ada_state);
-    _mav_put_uint8_t(buf, 161, fmm_state);
-    _mav_put_uint8_t(buf, 162, dpl_state);
-    _mav_put_uint8_t(buf, 163, abk_state);
-    _mav_put_uint8_t(buf, 164, nas_state);
-    _mav_put_uint8_t(buf, 165, mea_state);
-    _mav_put_uint8_t(buf, 166, gps_fix);
-    _mav_put_uint8_t(buf, 167, pin_launch);
-    _mav_put_uint8_t(buf, 168, pin_nosecone);
-    _mav_put_uint8_t(buf, 169, pin_expulsion);
-    _mav_put_uint8_t(buf, 170, cutter_presence);
-    _mav_put_int8_t(buf, 171, logger_error);
+    _mav_put_float(buf, 144, pin_quick_connector);
+    _mav_put_float(buf, 148, battery_voltage);
+    _mav_put_float(buf, 152, cam_battery_voltage);
+    _mav_put_float(buf, 156, current_consumption);
+    _mav_put_float(buf, 160, temperature);
+    _mav_put_uint8_t(buf, 164, ada_state);
+    _mav_put_uint8_t(buf, 165, fmm_state);
+    _mav_put_uint8_t(buf, 166, dpl_state);
+    _mav_put_uint8_t(buf, 167, abk_state);
+    _mav_put_uint8_t(buf, 168, nas_state);
+    _mav_put_uint8_t(buf, 169, mea_state);
+    _mav_put_uint8_t(buf, 170, gps_fix);
+    _mav_put_uint8_t(buf, 171, pin_launch);
+    _mav_put_uint8_t(buf, 172, pin_nosecone);
+    _mav_put_uint8_t(buf, 173, pin_expulsion);
+    _mav_put_uint8_t(buf, 174, cutter_presence);
+    _mav_put_int8_t(buf, 175, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #else
@@ -858,6 +871,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     packet->nas_bias_x = nas_bias_x;
     packet->nas_bias_y = nas_bias_y;
     packet->nas_bias_z = nas_bias_z;
+    packet->pin_quick_connector = pin_quick_connector;
     packet->battery_voltage = battery_voltage;
     packet->cam_battery_voltage = cam_battery_voltage;
     packet->current_consumption = current_consumption;
@@ -902,7 +916,7 @@ static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  164);
 }
 
 /**
@@ -912,7 +926,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  161);
+    return _MAV_RETURN_uint8_t(msg,  165);
 }
 
 /**
@@ -922,7 +936,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  162);
+    return _MAV_RETURN_uint8_t(msg,  166);
 }
 
 /**
@@ -932,7 +946,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  163);
+    return _MAV_RETURN_uint8_t(msg,  167);
 }
 
 /**
@@ -942,7 +956,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  164);
+    return _MAV_RETURN_uint8_t(msg,  168);
 }
 
 /**
@@ -952,7 +966,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_mea_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  165);
+    return _MAV_RETURN_uint8_t(msg,  169);
 }
 
 /**
@@ -1132,7 +1146,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  166);
+    return _MAV_RETURN_uint8_t(msg,  170);
 }
 
 /**
@@ -1305,6 +1319,16 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_me
     return _MAV_RETURN_float(msg,  140);
 }
 
+/**
+ * @brief Get field pin_quick_connector from rocket_flight_tm message
+ *
+ * @return   Quick connector detach pin 
+ */
+static inline float mavlink_msg_rocket_flight_tm_get_pin_quick_connector(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  144);
+}
+
 /**
  * @brief Get field pin_launch from rocket_flight_tm message
  *
@@ -1312,7 +1336,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_me
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  167);
+    return _MAV_RETURN_uint8_t(msg,  171);
 }
 
 /**
@@ -1322,7 +1346,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  168);
+    return _MAV_RETURN_uint8_t(msg,  172);
 }
 
 /**
@@ -1332,7 +1356,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlin
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  169);
+    return _MAV_RETURN_uint8_t(msg,  173);
 }
 
 /**
@@ -1342,7 +1366,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavli
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  170);
+    return _MAV_RETURN_uint8_t(msg,  174);
 }
 
 /**
@@ -1352,7 +1376,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mav
  */
 static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  144);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1362,7 +1386,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavli
  */
 static inline float mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  148);
+    return _MAV_RETURN_float(msg,  152);
 }
 
 /**
@@ -1372,7 +1396,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(const m
  */
 static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  152);
+    return _MAV_RETURN_float(msg,  156);
 }
 
 /**
@@ -1382,7 +1406,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const m
  */
 static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  156);
+    return _MAV_RETURN_float(msg,  160);
 }
 
 /**
@@ -1392,7 +1416,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_m
  */
 static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int8_t(msg,  171);
+    return _MAV_RETURN_int8_t(msg,  175);
 }
 
 /**
@@ -1439,6 +1463,7 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t*
     rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg);
     rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg);
     rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg);
+    rocket_flight_tm->pin_quick_connector = mavlink_msg_rocket_flight_tm_get_pin_quick_connector(msg);
     rocket_flight_tm->battery_voltage = mavlink_msg_rocket_flight_tm_get_battery_voltage(msg);
     rocket_flight_tm->cam_battery_voltage = mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(msg);
     rocket_flight_tm->current_consumption = mavlink_msg_rocket_flight_tm_get_current_consumption(msg);
diff --git a/mavlink_lib/gemini/testsuite.h b/mavlink_lib/gemini/testsuite.h
index 236221d483af6c06eca6628c59922dbd4c3af57c..74a11a2cf76be26e0419f27952ab8dc00832eb7c 100644
--- a/mavlink_lib/gemini/testsuite.h
+++ b/mavlink_lib/gemini/testsuite.h
@@ -1551,7 +1551,7 @@ static void mavlink_test_adc_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_adc_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,"YZABCDEFGHIJKLMNOPQ"
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,"OPQRSTUVWXYZABCDEFG"
     };
     mavlink_adc_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -1560,6 +1560,10 @@ static void mavlink_test_adc_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.channel_1 = packet_in.channel_1;
         packet1.channel_2 = packet_in.channel_2;
         packet1.channel_3 = packet_in.channel_3;
+        packet1.channel_4 = packet_in.channel_4;
+        packet1.channel_5 = packet_in.channel_5;
+        packet1.channel_6 = packet_in.channel_6;
+        packet1.channel_7 = packet_in.channel_7;
         
         mav_array_memcpy(packet1.sensor_name, packet_in.sensor_name, sizeof(char)*20);
         
@@ -1575,12 +1579,12 @@ static void mavlink_test_adc_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_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
+    mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
     mavlink_msg_adc_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
+    mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
     mavlink_msg_adc_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1593,7 +1597,7 @@ static void mavlink_test_adc_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_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
+    mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
     mavlink_msg_adc_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2109,7 +2113,7 @@ static void mavlink_test_receiver_tm(uint8_t system_id, uint8_t component_id, ma
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_receiver_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,18483,18587,18691,18795,18899,19003,19107,19211,19315,19419,137,204
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,18691,18795,18899,19003,19107,19211,19315,19419,19523,19627,149,216,27,94
     };
     mavlink_receiver_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2118,6 +2122,7 @@ static void mavlink_test_receiver_tm(uint8_t system_id, uint8_t component_id, ma
         packet1.main_rx_fei = packet_in.main_rx_fei;
         packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
         packet1.payload_rx_fei = packet_in.payload_rx_fei;
+        packet1.battery_voltage = packet_in.battery_voltage;
         packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
         packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
         packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
@@ -2130,6 +2135,8 @@ static void mavlink_test_receiver_tm(uint8_t system_id, uint8_t component_id, ma
         packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
         packet1.main_radio_present = packet_in.main_radio_present;
         packet1.payload_radio_present = packet_in.payload_radio_present;
+        packet1.ethernet_present = packet_in.ethernet_present;
+        packet1.ethernet_status = packet_in.ethernet_status;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -2144,12 +2151,12 @@ static void mavlink_test_receiver_tm(uint8_t system_id, uint8_t component_id, ma
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei );
+    mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
     mavlink_msg_receiver_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei );
+    mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
     mavlink_msg_receiver_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2162,7 +2169,7 @@ static void mavlink_test_receiver_tm(uint8_t system_id, uint8_t component_id, ma
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei );
+    mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
     mavlink_msg_receiver_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2732,7 +2739,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_rocket_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,229,40,107,174,241,52,119,186,253,64,131,198
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,1137.0,241,52,119,186,253,64,131,198,9,76,143,210
     };
     mavlink_rocket_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2771,6 +2778,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         packet1.nas_bias_x = packet_in.nas_bias_x;
         packet1.nas_bias_y = packet_in.nas_bias_y;
         packet1.nas_bias_z = packet_in.nas_bias_z;
+        packet1.pin_quick_connector = packet_in.pin_quick_connector;
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
         packet1.current_consumption = packet_in.current_consumption;
@@ -2801,12 +2809,12 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2819,7 +2827,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2841,7 +2849,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_payload_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,229,40,107,174,241,52
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107
     };
     mavlink_payload_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2882,13 +2890,13 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
         packet1.current_consumption = packet_in.current_consumption;
-        packet1.vsupply_5v = packet_in.vsupply_5v;
         packet1.temperature = packet_in.temperature;
         packet1.fmm_state = packet_in.fmm_state;
         packet1.nas_state = packet_in.nas_state;
         packet1.wes_state = packet_in.wes_state;
         packet1.gps_fix = packet_in.gps_fix;
         packet1.pin_nosecone = packet_in.pin_nosecone;
+        packet1.cutter_presence = packet_in.cutter_presence;
         packet1.logger_error = packet_in.logger_error;
         
         
@@ -2904,12 +2912,12 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2922,7 +2930,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3098,7 +3106,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
     mavlink_gse_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.timestamp = packet_in.timestamp;
-        packet1.loadcell_tank = packet_in.loadcell_tank;
+        packet1.loadcell_rocket = packet_in.loadcell_rocket;
         packet1.loadcell_vessel = packet_in.loadcell_vessel;
         packet1.filling_pressure = packet_in.filling_pressure;
         packet1.vessel_pressure = packet_in.vessel_pressure;
@@ -3128,12 +3136,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.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
     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.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
     mavlink_msg_gse_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3146,7 +3154,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.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
     mavlink_msg_gse_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
diff --git a/mavlink_lib/gemini/version.h b/mavlink_lib/gemini/version.h
index dca8b488b948963dd76e3891f0cf93c5bb94ba81..c779f4d3f184f8ffba33d360a1889e43eeac4206 100644
--- a/mavlink_lib/gemini/version.h
+++ b/mavlink_lib/gemini/version.h
@@ -7,8 +7,8 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Aug 29 2023"
+#define MAVLINK_BUILD_DATE "Mon Sep 11 2023"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 172
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
  
 #endif // MAVLINK_VERSION_H
diff --git a/message_definitions/gemini.xml b/message_definitions/gemini.xml
index acf3fd98ea3962e04969fdd4bc6f137ef438f5ba..b2164311389b1ebcbbd078f590dfa6bb95301252 100644
--- a/message_definitions/gemini.xml
+++ b/message_definitions/gemini.xml
@@ -72,7 +72,7 @@
                 <description>MPU9250 IMU data</description>
             </entry>
             <entry name="MAV_ADS_ID" value="5">
-                <description>ADS 4 channel ADC data</description>
+                <description>ADS 8 channel ADC data</description>
             </entry>
             <entry name="MAV_MS5803_ID" value="6">
                 <description>MS5803 barometer data</description>
@@ -371,6 +371,10 @@
             <field name="channel_1" type="float" units="V">ADC voltage measured on channel 1</field>
             <field name="channel_2" type="float" units="V">ADC voltage measured on channel 2</field>
             <field name="channel_3" type="float" units="V">ADC voltage measured on channel 3</field>
+            <field name="channel_4" type="float" units="V">ADC voltage measured on channel 4</field>
+            <field name="channel_5" type="float" units="V">ADC voltage measured on channel 5</field>
+            <field name="channel_6" type="float" units="V">ADC voltage measured on channel 6</field>
+            <field name="channel_7" type="float" units="V">ADC voltage measured on channel 7</field>
         </message>
         <message id="106" name="VOLTAGE_TM">
             <description></description>
@@ -447,6 +451,9 @@
             <field name="payload_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
             <field name="payload_rx_rssi" type="float" units="dBm">Receive RSSI</field>
             <field name="payload_rx_fei" type="float" units="Hz">Receive frequency error index</field>
+            <field name="ethernet_present" type="uint8_t">Boolean indicating the presence of the ethernet module</field>
+            <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field>
+            <field name="battery_voltage" type="float" units="V">Battery voltage</field>
         </message>
 
         <!-- FROM ROCKET TO GROUND: SPECIFIC -->
@@ -602,6 +609,7 @@
             <field name="nas_bias_x" type="float">Navigation system gyroscope bias on x axis</field>
             <field name="nas_bias_y" type="float">Navigation system gyroscope bias on y axis</field>
             <field name="nas_bias_z" type="float">Navigation system gyroscope bias on z axis</field>
+            <field name="pin_quick_connector" type="float"> Quick connector detach pin </field>
             <field name="pin_launch" type="uint8_t">Launch pin status (1 = connected, 0 = disconnected)</field>
             <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field>
             <field name="pin_expulsion" type="uint8_t">Servo sensor status (1 = actuated, 0 = idle)</field>
@@ -656,7 +664,7 @@
             <field name="battery_voltage" type="float" units="V">Battery voltage</field>
             <field name="cam_battery_voltage" type="float" units="V">Camera battery voltage</field>
             <field name="current_consumption" type="float" units="A">Battery current</field>
-            <field name="vsupply_5v" type="float" units="V">Power supply 5V</field>
+            <field name="cutter_presence" type="uint8_t">Cutter presence status (1 = present, 0 = missing)</field>
             <field name="temperature" type="float" units="degC">Temperature</field>
             <field name="logger_error" type="int8_t">Logger error (0 = no error)</field>
         </message>
@@ -702,7 +710,7 @@
         <message id="212" name="GSE_TM">
             <description>Ground Segment Equipment telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
-            <field name="loadcell_tank" type="float" units="kg">Rocket weight</field>
+            <field name="loadcell_rocket" type="float" units="kg">Rocket weight</field>
             <field name="loadcell_vessel" type="float" units="kg">External tank weight</field>
             <field name="filling_pressure" type="float" units="Bar">Refueling line pressure</field>
             <field name="vessel_pressure" type="float" units="Bar">Vessel tank pressure</field>