diff --git a/mavlink_lib.py b/mavlink_lib.py
index e0b18bffd1ce4b1314ed6e3b19ecf0d1cfdbf744..28d1b9d394ea5095a33b3833535f97bb74c6e390 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -274,16 +274,18 @@ MAV_SYSID_PAYLOAD = 2 #
 enums['SysIDs'][2] = EnumEntry('MAV_SYSID_PAYLOAD', '''''')
 MAV_SYSID_RIG = 3 # 
 enums['SysIDs'][3] = EnumEntry('MAV_SYSID_RIG', '''''')
-MAV_SYSID_GS = 4 # 
-enums['SysIDs'][4] = EnumEntry('MAV_SYSID_GS', '''''')
-MAV_SYSID_ARP = 5 # 
-enums['SysIDs'][5] = EnumEntry('MAV_SYSID_ARP', '''''')
-MAV_SYSID_GS_BACKUP = 6 # 
-enums['SysIDs'][6] = EnumEntry('MAV_SYSID_GS_BACKUP', '''''')
-MAV_SYSID_ARP_BACKUP = 7 # 
-enums['SysIDs'][7] = EnumEntry('MAV_SYSID_ARP_BACKUP', '''''')
-SysIDs_ENUM_END = 8 # 
-enums['SysIDs'][8] = EnumEntry('SysIDs_ENUM_END', '''''')
+MAV_SYSID_CONRIG = 4 # 
+enums['SysIDs'][4] = EnumEntry('MAV_SYSID_CONRIG', '''''')
+MAV_SYSID_GS = 5 # 
+enums['SysIDs'][5] = EnumEntry('MAV_SYSID_GS', '''''')
+MAV_SYSID_ARP = 6 # 
+enums['SysIDs'][6] = EnumEntry('MAV_SYSID_ARP', '''''')
+MAV_SYSID_GS_BACKUP = 7 # 
+enums['SysIDs'][7] = EnumEntry('MAV_SYSID_GS_BACKUP', '''''')
+MAV_SYSID_ARP_BACKUP = 8 # 
+enums['SysIDs'][8] = EnumEntry('MAV_SYSID_ARP_BACKUP', '''''')
+SysIDs_ENUM_END = 9 # 
+enums['SysIDs'][9] = EnumEntry('SysIDs_ENUM_END', '''''')
 
 # SystemTMList
 enums['SystemTMList'] = {}
@@ -507,6 +509,30 @@ enums['PinsList'][2] = EnumEntry('NOSECONE_PIN', '''''')
 PinsList_ENUM_END = 3 # 
 enums['PinsList'][3] = EnumEntry('PinsList_ENUM_END', '''''')
 
+# Radio433Type
+enums['Radio433Type'] = {}
+RADIO_433_TYPE_NONE = 0 # No 433 Mhz transceiver
+enums['Radio433Type'][0] = EnumEntry('RADIO_433_TYPE_NONE', '''No 433 Mhz transceiver''')
+RADIO_433_TYPE_SKYWARD = 1 # Skyward 433 Mhz transceiver
+enums['Radio433Type'][1] = EnumEntry('RADIO_433_TYPE_SKYWARD', '''Skyward 433 Mhz transceiver''')
+RADIO_433_TYPE_EBYTE = 2 # Ebyte 433 Mhz transceiver (backup)
+enums['Radio433Type'][2] = EnumEntry('RADIO_433_TYPE_EBYTE', '''Ebyte 433 Mhz transceiver (backup)''')
+RADIO_433_TYPE_LORA = 3 # LoRa (Ebyte) 433 Mhz transceiver
+enums['Radio433Type'][3] = EnumEntry('RADIO_433_TYPE_LORA', '''LoRa (Ebyte) 433 Mhz transceiver''')
+Radio433Type_ENUM_END = 4 # 
+enums['Radio433Type'][4] = EnumEntry('Radio433Type_ENUM_END', '''''')
+
+# Radio868Type
+enums['Radio868Type'] = {}
+RADIO_868_TYPE_NONE = 0 # No 868 Mhz transceiver
+enums['Radio868Type'][0] = EnumEntry('RADIO_868_TYPE_NONE', '''No 868 Mhz transceiver''')
+RADIO_868_TYPE_SKYWARD = 1 # Skyward 868 Mhz transceiver
+enums['Radio868Type'][1] = EnumEntry('RADIO_868_TYPE_SKYWARD', '''Skyward 868 Mhz transceiver''')
+RADIO_868_TYPE_EBYTE = 2 # Ebyte 868 Mhz transceiver (backup)
+enums['Radio868Type'][2] = EnumEntry('RADIO_868_TYPE_EBYTE', '''Ebyte 868 Mhz transceiver (backup)''')
+Radio868Type_ENUM_END = 3 # 
+enums['Radio868Type'][3] = EnumEntry('Radio868Type_ENUM_END', '''''')
+
 # message IDs
 MAVLINK_MSG_ID_BAD_DATA = -1
 MAVLINK_MSG_ID_UNKNOWN = -2
@@ -576,6 +602,10 @@ MAVLINK_MSG_ID_PAYLOAD_STATS_TM = 211
 MAVLINK_MSG_ID_GSE_TM = 212
 MAVLINK_MSG_ID_MOTOR_TM = 213
 MAVLINK_MSG_ID_CALIBRATION_TM = 214
+MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST = 240
+MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE = 241
+MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM = 242
+MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM = 243
 
 class MAVLink_ping_tc_message(MAVLink_message):
         '''
@@ -2301,23 +2331,23 @@ class MAVLink_arp_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ARP_TM
         name = 'ARP_TM'
-        fieldnames = ['timestamp', 'state', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', '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', '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', 'ethernet_present', 'ethernet_status', 'battery_voltage', 'log_number']
-        ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'payload_rx_rssi', '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', 'log_number', 'state', 'gps_fix', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
-        fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float', 'int16_t']
+        fieldnames = ['timestamp', 'state', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'battery_voltage', 'log_number']
+        ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'battery_voltage', 'log_number', 'state', 'gps_fix']
+        fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'int16_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "battery_voltage": "V"}
-        format = '<QfffffffffffffffffHHHHHHHHHHhBBBBBB'
-        native_format = bytearray('<QfffffffffffffffffHHHHHHHHHHhBBBBBB', 'ascii')
-        orders = [0, 29, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 30, 31, 18, 19, 20, 21, 22, 15, 32, 23, 24, 25, 26, 27, 16, 33, 34, 17, 28]
-        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]
-        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]
-        crc_extra = 239
-        unpacker = struct.Struct('<QfffffffffffffffffHHHHHHHHHHhBBBBBB')
+        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "battery_voltage": "V"}
+        format = '<QfffffffffffffffhBB'
+        native_format = bytearray('<QfffffffffffffffhBB', 'ascii')
+        orders = [0, 17, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 18, 15, 16]
+        lengths = [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]
+        crc_extra = 17
+        unpacker = struct.Struct('<QfffffffffffffffhBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, 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, 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, ethernet_present, ethernet_status, battery_voltage, log_number):
+        def __init__(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, battery_voltage, log_number):
                 MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.name)
                 self._fieldnames = MAVLink_arp_tm_message.fieldnames
                 self._instance_field = MAVLink_arp_tm_message.instance_field
@@ -2339,27 +2369,11 @@ class MAVLink_arp_tm_message(MAVLink_message):
                 self.gps_longitude = gps_longitude
                 self.gps_height = gps_height
                 self.gps_fix = gps_fix
-                self.main_radio_present = main_radio_present
-                self.main_packet_tx_error_count = main_packet_tx_error_count
-                self.main_tx_bitrate = main_tx_bitrate
-                self.main_packet_rx_success_count = main_packet_rx_success_count
-                self.main_packet_rx_drop_count = main_packet_rx_drop_count
-                self.main_rx_bitrate = main_rx_bitrate
-                self.main_rx_rssi = main_rx_rssi
-                self.payload_radio_present = payload_radio_present
-                self.payload_packet_tx_error_count = payload_packet_tx_error_count
-                self.payload_tx_bitrate = payload_tx_bitrate
-                self.payload_packet_rx_success_count = payload_packet_rx_success_count
-                self.payload_packet_rx_drop_count = payload_packet_rx_drop_count
-                self.payload_rx_bitrate = payload_rx_bitrate
-                self.payload_rx_rssi = payload_rx_rssi
-                self.ethernet_present = ethernet_present
-                self.ethernet_status = ethernet_status
                 self.battery_voltage = battery_voltage
                 self.log_number = log_number
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 239, struct.pack('<QfffffffffffffffffHHHHHHHHHHhBBBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.payload_rx_rssi, 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.log_number, self.state, self.gps_fix, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 17, struct.pack('<QfffffffffffffffhBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.battery_voltage, self.log_number, self.state, self.gps_fix), force_mavlink1=force_mavlink1)
 
 class MAVLink_sys_tm_message(MAVLink_message):
         '''
@@ -3156,6 +3170,161 @@ class MAVLink_calibration_tm_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 210, struct.pack('<Qfffffffffffffffff', self.timestamp, self.gyro_bias_x, self.gyro_bias_y, self.gyro_bias_z, self.mag_bias_x, self.mag_bias_y, self.mag_bias_z, self.mag_scale_x, self.mag_scale_y, self.mag_scale_z, self.static_press_1_bias, self.static_press_1_scale, self.static_press_2_bias, self.static_press_2_scale, self.dpl_bay_press_bias, self.dpl_bay_press_scale, self.dynamic_press_bias, self.dynamic_press_scale), force_mavlink1=force_mavlink1)
 
+class MAVLink_gs_discovery_request_message(MAVLink_message):
+        '''
+        Request for discovery of devices in the GS network
+        '''
+        id = MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST
+        name = 'GS_DISCOVERY_REQUEST'
+        fieldnames = ['source_ip', 'source_port']
+        ordered_fieldnames = ['source_ip', 'source_port']
+        fieldtypes = ['uint32_t', 'uint16_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {}
+        format = '<IH'
+        native_format = bytearray('<IH', 'ascii')
+        orders = [0, 1]
+        lengths = [1, 1]
+        array_lengths = [0, 0]
+        crc_extra = 234
+        unpacker = struct.Struct('<IH')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, source_ip, source_port):
+                MAVLink_message.__init__(self, MAVLink_gs_discovery_request_message.id, MAVLink_gs_discovery_request_message.name)
+                self._fieldnames = MAVLink_gs_discovery_request_message.fieldnames
+                self._instance_field = MAVLink_gs_discovery_request_message.instance_field
+                self._instance_offset = MAVLink_gs_discovery_request_message.instance_offset
+                self.source_ip = source_ip
+                self.source_port = source_port
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 234, struct.pack('<IH', self.source_ip, self.source_port), force_mavlink1=force_mavlink1)
+
+class MAVLink_gs_discovery_response_message(MAVLink_message):
+        '''
+        Response for discovery of devices in the GS network
+        '''
+        id = MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE
+        name = 'GS_DISCOVERY_RESPONSE'
+        fieldnames = ['ip', 'port', 'device_id', 'radio_433_type', 'radio_868_type', 'radio_433_frequency', 'radio_868_frequency']
+        ordered_fieldnames = ['ip', 'radio_433_frequency', 'radio_868_frequency', 'port', 'device_id', 'radio_433_type', 'radio_868_type']
+        fieldtypes = ['uint32_t', 'uint16_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint32_t', 'uint32_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {"radio_433_type": "Radio433Type", "radio_868_type": "Radio868Type"}
+        fieldunits_by_name = {"radio_433_frequency": "Hz", "radio_868_frequency": "Hz"}
+        format = '<IIIHBBB'
+        native_format = bytearray('<IIIHBBB', 'ascii')
+        orders = [0, 3, 4, 5, 6, 1, 2]
+        lengths = [1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 27
+        unpacker = struct.Struct('<IIIHBBB')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, ip, port, device_id, radio_433_type, radio_868_type, radio_433_frequency, radio_868_frequency):
+                MAVLink_message.__init__(self, MAVLink_gs_discovery_response_message.id, MAVLink_gs_discovery_response_message.name)
+                self._fieldnames = MAVLink_gs_discovery_response_message.fieldnames
+                self._instance_field = MAVLink_gs_discovery_response_message.instance_field
+                self._instance_offset = MAVLink_gs_discovery_response_message.instance_offset
+                self.ip = ip
+                self.port = port
+                self.device_id = device_id
+                self.radio_433_type = radio_433_type
+                self.radio_868_type = radio_868_type
+                self.radio_433_frequency = radio_433_frequency
+                self.radio_868_frequency = radio_868_frequency
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 27, struct.pack('<IIIHBBB', self.ip, self.radio_433_frequency, self.radio_868_frequency, self.port, self.device_id, self.radio_433_type, self.radio_868_type), force_mavlink1=force_mavlink1)
+
+class MAVLink_rocket_radio_link_info_tm_message(MAVLink_message):
+        '''
+        Radio link information telemetry
+        '''
+        id = MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM
+        name = 'ROCKET_RADIO_LINK_INFO_TM'
+        fieldnames = ['timestamp', 'radio_433_type', 'radio_868_type', 'main_rssi', 'main_rx_success_count', 'main_rx_drop_count', 'main_bitrate', 'main_frequency', 'payload_rssi', 'payload_rx_success_count', 'payload_rx_drop_count', 'payload_bitrate', 'payload_frequency', 'ethernet_status']
+        ordered_fieldnames = ['timestamp', 'main_frequency', 'payload_frequency', 'main_rx_success_count', 'main_rx_drop_count', 'main_bitrate', 'payload_rx_success_count', 'payload_rx_drop_count', 'payload_bitrate', 'radio_433_type', 'radio_868_type', 'main_rssi', 'payload_rssi', 'ethernet_status']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'int8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint32_t', 'int8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint32_t', 'uint8_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {"radio_433_type": "Radio433Type", "radio_868_type": "Radio868Type"}
+        fieldunits_by_name = {"timestamp": "us", "main_rssi": "dBm", "main_bitrate": "b/s", "main_frequency": "Hz", "payload_rssi": "dBm", "payload_bitrate": "b/s", "payload_frequency": "Hz"}
+        format = '<QIIHHHHHHBBbbB'
+        native_format = bytearray('<QIIHHHHHHBBbbB', 'ascii')
+        orders = [0, 9, 10, 11, 3, 4, 5, 1, 12, 6, 7, 8, 2, 13]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 97
+        unpacker = struct.Struct('<QIIHHHHHHBBbbB')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timestamp, radio_433_type, radio_868_type, main_rssi, main_rx_success_count, main_rx_drop_count, main_bitrate, main_frequency, payload_rssi, payload_rx_success_count, payload_rx_drop_count, payload_bitrate, payload_frequency, ethernet_status):
+                MAVLink_message.__init__(self, MAVLink_rocket_radio_link_info_tm_message.id, MAVLink_rocket_radio_link_info_tm_message.name)
+                self._fieldnames = MAVLink_rocket_radio_link_info_tm_message.fieldnames
+                self._instance_field = MAVLink_rocket_radio_link_info_tm_message.instance_field
+                self._instance_offset = MAVLink_rocket_radio_link_info_tm_message.instance_offset
+                self.timestamp = timestamp
+                self.radio_433_type = radio_433_type
+                self.radio_868_type = radio_868_type
+                self.main_rssi = main_rssi
+                self.main_rx_success_count = main_rx_success_count
+                self.main_rx_drop_count = main_rx_drop_count
+                self.main_bitrate = main_bitrate
+                self.main_frequency = main_frequency
+                self.payload_rssi = payload_rssi
+                self.payload_rx_success_count = payload_rx_success_count
+                self.payload_rx_drop_count = payload_rx_drop_count
+                self.payload_bitrate = payload_bitrate
+                self.payload_frequency = payload_frequency
+                self.ethernet_status = ethernet_status
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 97, struct.pack('<QIIHHHHHHBBbbB', self.timestamp, self.main_frequency, self.payload_frequency, self.main_rx_success_count, self.main_rx_drop_count, self.main_bitrate, self.payload_rx_success_count, self.payload_rx_drop_count, self.payload_bitrate, self.radio_433_type, self.radio_868_type, self.main_rssi, self.payload_rssi, self.ethernet_status), force_mavlink1=force_mavlink1)
+
+class MAVLink_gse_radio_link_info_tm_message(MAVLink_message):
+        '''
+        Radio link information telemetry
+        '''
+        id = MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM
+        name = 'GSE_RADIO_LINK_INFO_TM'
+        fieldnames = ['timestamp', 'rssi', 'snr', 'rx_success_count', 'rx_drop_count', 'bitrate', 'frequency', 'ethernet_status']
+        ordered_fieldnames = ['timestamp', 'frequency', 'rx_success_count', 'rx_drop_count', 'bitrate', 'rssi', 'snr', 'ethernet_status']
+        fieldtypes = ['uint64_t', 'int8_t', 'int8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint32_t', 'uint8_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {"timestamp": "us", "rssi": "dBm", "snr": "dB", "bitrate": "b/s", "frequency": "Hz"}
+        format = '<QIHHHbbB'
+        native_format = bytearray('<QIHHHbbB', 'ascii')
+        orders = [0, 5, 6, 2, 3, 4, 1, 7]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 8
+        unpacker = struct.Struct('<QIHHHbbB')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timestamp, rssi, snr, rx_success_count, rx_drop_count, bitrate, frequency, ethernet_status):
+                MAVLink_message.__init__(self, MAVLink_gse_radio_link_info_tm_message.id, MAVLink_gse_radio_link_info_tm_message.name)
+                self._fieldnames = MAVLink_gse_radio_link_info_tm_message.fieldnames
+                self._instance_field = MAVLink_gse_radio_link_info_tm_message.instance_field
+                self._instance_offset = MAVLink_gse_radio_link_info_tm_message.instance_offset
+                self.timestamp = timestamp
+                self.rssi = rssi
+                self.snr = snr
+                self.rx_success_count = rx_success_count
+                self.rx_drop_count = rx_drop_count
+                self.bitrate = bitrate
+                self.frequency = frequency
+                self.ethernet_status = ethernet_status
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 8, struct.pack('<QIHHHbbB', self.timestamp, self.frequency, self.rx_success_count, self.rx_drop_count, self.bitrate, self.rssi, self.snr, self.ethernet_status), force_mavlink1=force_mavlink1)
+
 
 mavlink_map = {
         MAVLINK_MSG_ID_PING_TC : MAVLink_ping_tc_message,
@@ -3224,6 +3393,10 @@ mavlink_map = {
         MAVLINK_MSG_ID_GSE_TM : MAVLink_gse_tm_message,
         MAVLINK_MSG_ID_MOTOR_TM : MAVLink_motor_tm_message,
         MAVLINK_MSG_ID_CALIBRATION_TM : MAVLink_calibration_tm_message,
+        MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST : MAVLink_gs_discovery_request_message,
+        MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE : MAVLink_gs_discovery_response_message,
+        MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM : MAVLink_rocket_radio_link_info_tm_message,
+        MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM : MAVLink_gse_radio_link_info_tm_message,
 }
 
 class MAVError(Exception):
@@ -4775,7 +4948,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.registry_coord_tm_encode(timestamp, key_id, key_name, latitude, longitude), force_mavlink1=force_mavlink1)
 
-        def arp_tm_encode(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, 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, 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, ethernet_present, ethernet_status, battery_voltage, log_number):
+        def arp_tm_encode(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, battery_voltage, log_number):
                 '''
                 
 
@@ -4796,29 +4969,13 @@ class MAVLink(object):
                 gps_longitude             : Longitude [deg] (type:float)
                 gps_height                : Altitude [m] (type:float)
                 gps_fix                   : Wether the GPS has a FIX (type:uint8_t)
-                main_radio_present        : Boolean indicating the presence of the main radio (type:uint8_t)
-                main_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                main_tx_bitrate           : Send bitrate [b/s] (type:uint16_t)
-                main_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
-                main_rx_rssi              : Receive RSSI [dBm] (type:float)
-                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
-                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
-                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
-                payload_rx_rssi           : Receive RSSI [dBm] (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)
                 log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
 
                 '''
-                return MAVLink_arp_tm_message(timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, 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, 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, ethernet_present, ethernet_status, battery_voltage, log_number)
+                return MAVLink_arp_tm_message(timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, battery_voltage, log_number)
 
-        def arp_tm_send(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, 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, 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, ethernet_present, ethernet_status, battery_voltage, log_number, force_mavlink1=False):
+        def arp_tm_send(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, battery_voltage, log_number, force_mavlink1=False):
                 '''
                 
 
@@ -4839,27 +4996,11 @@ class MAVLink(object):
                 gps_longitude             : Longitude [deg] (type:float)
                 gps_height                : Altitude [m] (type:float)
                 gps_fix                   : Wether the GPS has a FIX (type:uint8_t)
-                main_radio_present        : Boolean indicating the presence of the main radio (type:uint8_t)
-                main_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                main_tx_bitrate           : Send bitrate [b/s] (type:uint16_t)
-                main_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
-                main_rx_rssi              : Receive RSSI [dBm] (type:float)
-                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
-                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
-                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
-                payload_rx_rssi           : Receive RSSI [dBm] (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)
                 log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
 
                 '''
-                return self.send(self.arp_tm_encode(timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, 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, 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, ethernet_present, ethernet_status, battery_voltage, log_number), force_mavlink1=force_mavlink1)
+                return self.send(self.arp_tm_encode(timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, battery_voltage, log_number), force_mavlink1=force_mavlink1)
 
         def sys_tm_encode(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler):
                 '''
@@ -5761,3 +5902,129 @@ class MAVLink(object):
                 '''
                 return self.send(self.calibration_tm_encode(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale), force_mavlink1=force_mavlink1)
 
+        def gs_discovery_request_encode(self, source_ip, source_port):
+                '''
+                Request for discovery of devices in the GS network
+
+                source_ip                 : IP address of the requesting device (type:uint32_t)
+                source_port               : Port of the requesting device (type:uint16_t)
+
+                '''
+                return MAVLink_gs_discovery_request_message(source_ip, source_port)
+
+        def gs_discovery_request_send(self, source_ip, source_port, force_mavlink1=False):
+                '''
+                Request for discovery of devices in the GS network
+
+                source_ip                 : IP address of the requesting device (type:uint32_t)
+                source_port               : Port of the requesting device (type:uint16_t)
+
+                '''
+                return self.send(self.gs_discovery_request_encode(source_ip, source_port), force_mavlink1=force_mavlink1)
+
+        def gs_discovery_response_encode(self, ip, port, device_id, radio_433_type, radio_868_type, radio_433_frequency, radio_868_frequency):
+                '''
+                Response for discovery of devices in the GS network
+
+                ip                        : IP address of the device (type:uint32_t)
+                port                      : Port of the device (type:uint16_t)
+                device_id                 : Device ID (type:uint8_t)
+                radio_433_type            : Radio 433 type of the device (type:uint8_t, values:Radio433Type)
+                radio_868_type            : Radio 868 type of the device (type:uint8_t, values:Radio868Type)
+                radio_433_frequency        : Radio 433 frequency of the device [Hz] (type:uint32_t)
+                radio_868_frequency        : Radio 868 frequency of the device [Hz] (type:uint32_t)
+
+                '''
+                return MAVLink_gs_discovery_response_message(ip, port, device_id, radio_433_type, radio_868_type, radio_433_frequency, radio_868_frequency)
+
+        def gs_discovery_response_send(self, ip, port, device_id, radio_433_type, radio_868_type, radio_433_frequency, radio_868_frequency, force_mavlink1=False):
+                '''
+                Response for discovery of devices in the GS network
+
+                ip                        : IP address of the device (type:uint32_t)
+                port                      : Port of the device (type:uint16_t)
+                device_id                 : Device ID (type:uint8_t)
+                radio_433_type            : Radio 433 type of the device (type:uint8_t, values:Radio433Type)
+                radio_868_type            : Radio 868 type of the device (type:uint8_t, values:Radio868Type)
+                radio_433_frequency        : Radio 433 frequency of the device [Hz] (type:uint32_t)
+                radio_868_frequency        : Radio 868 frequency of the device [Hz] (type:uint32_t)
+
+                '''
+                return self.send(self.gs_discovery_response_encode(ip, port, device_id, radio_433_type, radio_868_type, radio_433_frequency, radio_868_frequency), force_mavlink1=force_mavlink1)
+
+        def rocket_radio_link_info_tm_encode(self, timestamp, radio_433_type, radio_868_type, main_rssi, main_rx_success_count, main_rx_drop_count, main_bitrate, main_frequency, payload_rssi, payload_rx_success_count, payload_rx_drop_count, payload_bitrate, payload_frequency, ethernet_status):
+                '''
+                Radio link information telemetry
+
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+                radio_433_type            : Radio 433 type of the device (type:uint8_t, values:Radio433Type)
+                radio_868_type            : Radio 868 type of the device (type:uint8_t, values:Radio868Type)
+                main_rssi                 : Main radio RSSI [dBm] (type:int8_t)
+                main_rx_success_count        : Main radio received packet count (type:uint16_t)
+                main_rx_drop_count        : Main radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                main_bitrate              : Main radio bitrate [b/s] (type:uint16_t)
+                main_frequency            : Main radio frequency [Hz] (type:uint32_t)
+                payload_rssi              : Payload radio RSSI [dBm] (type:int8_t)
+                payload_rx_success_count        : Payload radio received packet count (type:uint16_t)
+                payload_rx_drop_count        : Payload radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                payload_bitrate           : Payload radio bitrate [b/s] (type:uint16_t)
+                payload_frequency         : Payload radio frequency [Hz] (type:uint32_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+
+                '''
+                return MAVLink_rocket_radio_link_info_tm_message(timestamp, radio_433_type, radio_868_type, main_rssi, main_rx_success_count, main_rx_drop_count, main_bitrate, main_frequency, payload_rssi, payload_rx_success_count, payload_rx_drop_count, payload_bitrate, payload_frequency, ethernet_status)
+
+        def rocket_radio_link_info_tm_send(self, timestamp, radio_433_type, radio_868_type, main_rssi, main_rx_success_count, main_rx_drop_count, main_bitrate, main_frequency, payload_rssi, payload_rx_success_count, payload_rx_drop_count, payload_bitrate, payload_frequency, ethernet_status, force_mavlink1=False):
+                '''
+                Radio link information telemetry
+
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+                radio_433_type            : Radio 433 type of the device (type:uint8_t, values:Radio433Type)
+                radio_868_type            : Radio 868 type of the device (type:uint8_t, values:Radio868Type)
+                main_rssi                 : Main radio RSSI [dBm] (type:int8_t)
+                main_rx_success_count        : Main radio received packet count (type:uint16_t)
+                main_rx_drop_count        : Main radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                main_bitrate              : Main radio bitrate [b/s] (type:uint16_t)
+                main_frequency            : Main radio frequency [Hz] (type:uint32_t)
+                payload_rssi              : Payload radio RSSI [dBm] (type:int8_t)
+                payload_rx_success_count        : Payload radio received packet count (type:uint16_t)
+                payload_rx_drop_count        : Payload radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                payload_bitrate           : Payload radio bitrate [b/s] (type:uint16_t)
+                payload_frequency         : Payload radio frequency [Hz] (type:uint32_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+
+                '''
+                return self.send(self.rocket_radio_link_info_tm_encode(timestamp, radio_433_type, radio_868_type, main_rssi, main_rx_success_count, main_rx_drop_count, main_bitrate, main_frequency, payload_rssi, payload_rx_success_count, payload_rx_drop_count, payload_bitrate, payload_frequency, ethernet_status), force_mavlink1=force_mavlink1)
+
+        def gse_radio_link_info_tm_encode(self, timestamp, rssi, snr, rx_success_count, rx_drop_count, bitrate, frequency, ethernet_status):
+                '''
+                Radio link information telemetry
+
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+                rssi                      : Radio RSSI [dBm] (type:int8_t)
+                snr                       : Radio Signal to Noise Ratio [dB] (type:int8_t)
+                rx_success_count          : Radio received packet count (type:uint16_t)
+                rx_drop_count             : Radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                bitrate                   : Radio bitrate [b/s] (type:uint16_t)
+                frequency                 : Radio frequency [Hz] (type:uint32_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+
+                '''
+                return MAVLink_gse_radio_link_info_tm_message(timestamp, rssi, snr, rx_success_count, rx_drop_count, bitrate, frequency, ethernet_status)
+
+        def gse_radio_link_info_tm_send(self, timestamp, rssi, snr, rx_success_count, rx_drop_count, bitrate, frequency, ethernet_status, force_mavlink1=False):
+                '''
+                Radio link information telemetry
+
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+                rssi                      : Radio RSSI [dBm] (type:int8_t)
+                snr                       : Radio Signal to Noise Ratio [dB] (type:int8_t)
+                rx_success_count          : Radio received packet count (type:uint16_t)
+                rx_drop_count             : Radio dropped packet count (e.g. CRC mismatch) (type:uint16_t)
+                bitrate                   : Radio bitrate [b/s] (type:uint16_t)
+                frequency                 : Radio frequency [Hz] (type:uint32_t)
+                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
+
+                '''
+                return self.send(self.gse_radio_link_info_tm_encode(timestamp, rssi, snr, rx_success_count, rx_drop_count, bitrate, frequency, ethernet_status), force_mavlink1=force_mavlink1)
+
diff --git a/mavlink_lib/orion/mavlink.h b/mavlink_lib/orion/mavlink.h
index 6b28abbec6a9aa1d2edf7df36fa63ee90ec9a83c..9b0bb07a6b4de436470c08e4248458faacb5e2e8 100644
--- a/mavlink_lib/orion/mavlink.h
+++ b/mavlink_lib/orion/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 1309536867628119565
+#define MAVLINK_PRIMARY_XML_HASH 9073854407394636743
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/orion/mavlink_msg_arp_tm.h b/mavlink_lib/orion/mavlink_msg_arp_tm.h
index b09667d4fa9046d7ceeba28c518c47ef1d4c7d27..d9ea1043f4b5166fe50d59df30fd9a50d6576ca3 100644
--- a/mavlink_lib/orion/mavlink_msg_arp_tm.h
+++ b/mavlink_lib/orion/mavlink_msg_arp_tm.h
@@ -20,35 +20,19 @@ typedef struct __mavlink_arp_tm_t {
  float gps_latitude; /*< [deg] Latitude*/
  float gps_longitude; /*< [deg] Longitude*/
  float gps_height; /*< [m] Altitude*/
- float main_rx_rssi; /*< [dBm] Receive RSSI*/
- float payload_rx_rssi; /*< [dBm] Receive RSSI*/
  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*/
- uint16_t main_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
- uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint16_t payload_packet_tx_error_count; /*<  Number of errors during send*/
- uint16_t payload_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t payload_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
- uint16_t payload_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
- uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
  int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
  uint8_t state; /*<  State Machine Controller State*/
  uint8_t gps_fix; /*<  Wether the GPS has a FIX*/
- 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_arp_tm_t;
 
-#define MAVLINK_MSG_ID_ARP_TM_LEN 104
-#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 104
-#define MAVLINK_MSG_ID_150_LEN 104
-#define MAVLINK_MSG_ID_150_MIN_LEN 104
+#define MAVLINK_MSG_ID_ARP_TM_LEN 72
+#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 72
+#define MAVLINK_MSG_ID_150_LEN 72
+#define MAVLINK_MSG_ID_150_MIN_LEN 72
 
-#define MAVLINK_MSG_ID_ARP_TM_CRC 239
-#define MAVLINK_MSG_ID_150_CRC 239
+#define MAVLINK_MSG_ID_ARP_TM_CRC 17
+#define MAVLINK_MSG_ID_150_CRC 17
 
 
 
@@ -56,9 +40,9 @@ typedef struct __mavlink_arp_tm_t {
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     150, \
     "ARP_TM", \
-    35, \
+    19, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_arp_tm_t, state) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 70, offsetof(mavlink_arp_tm_t, state) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
@@ -73,33 +57,17 @@ typedef struct __mavlink_arp_tm_t {
          { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
          { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
          { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 82, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
-         { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 101, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_arp_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_arp_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 90, offsetof(mavlink_arp_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 92, offsetof(mavlink_arp_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 94, offsetof(mavlink_arp_tm_t, payload_rx_bitrate) }, \
-         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, payload_rx_rssi) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 102, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 103, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
-         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 96, offsetof(mavlink_arp_tm_t, log_number) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 71, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 68, offsetof(mavlink_arp_tm_t, log_number) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     "ARP_TM", \
-    35, \
+    19, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_arp_tm_t, state) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 70, offsetof(mavlink_arp_tm_t, state) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
@@ -114,25 +82,9 @@ typedef struct __mavlink_arp_tm_t {
          { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
          { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
          { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 82, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
-         { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 101, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_arp_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_arp_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 90, offsetof(mavlink_arp_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 92, offsetof(mavlink_arp_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 94, offsetof(mavlink_arp_tm_t, payload_rx_bitrate) }, \
-         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, payload_rx_rssi) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 102, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 103, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
-         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 96, offsetof(mavlink_arp_tm_t, log_number) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 71, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 68, offsetof(mavlink_arp_tm_t, log_number) }, \
          } \
 }
 #endif
@@ -160,28 +112,12 @@ typedef struct __mavlink_arp_tm_t {
  * @param gps_longitude [deg] Longitude
  * @param gps_height [m] Altitude
  * @param gps_fix  Wether the GPS has a FIX
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @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
  * @param log_number  Currently active log file, -1 if the logger is inactive
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, 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, 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, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage, int16_t log_number)
+                               uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, float battery_voltage, int16_t log_number)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -200,26 +136,10 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 52, gps_latitude);
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
-    _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, payload_rx_rssi);
-    _mav_put_float(buf, 72, battery_voltage);
-    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
-    _mav_put_int16_t(buf, 96, log_number);
-    _mav_put_uint8_t(buf, 98, state);
-    _mav_put_uint8_t(buf, 99, gps_fix);
-    _mav_put_uint8_t(buf, 100, main_radio_present);
-    _mav_put_uint8_t(buf, 101, payload_radio_present);
-    _mav_put_uint8_t(buf, 102, ethernet_present);
-    _mav_put_uint8_t(buf, 103, ethernet_status);
+    _mav_put_float(buf, 64, battery_voltage);
+    _mav_put_int16_t(buf, 68, log_number);
+    _mav_put_uint8_t(buf, 70, state);
+    _mav_put_uint8_t(buf, 71, gps_fix);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -239,26 +159,10 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.payload_rx_rssi = payload_rx_rssi;
     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;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.log_number = log_number;
     packet.state = state;
     packet.gps_fix = gps_fix;
-    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_ARP_TM_LEN);
 #endif
@@ -290,29 +194,13 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  * @param gps_longitude [deg] Longitude
  * @param gps_height [m] Altitude
  * @param gps_fix  Wether the GPS has a FIX
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @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
  * @param log_number  Currently active log file, -1 if the logger is inactive
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t state,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,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,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,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage,int16_t log_number)
+                                   uint64_t timestamp,uint8_t state,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,float battery_voltage,int16_t log_number)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -331,26 +219,10 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 52, gps_latitude);
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
-    _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, payload_rx_rssi);
-    _mav_put_float(buf, 72, battery_voltage);
-    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
-    _mav_put_int16_t(buf, 96, log_number);
-    _mav_put_uint8_t(buf, 98, state);
-    _mav_put_uint8_t(buf, 99, gps_fix);
-    _mav_put_uint8_t(buf, 100, main_radio_present);
-    _mav_put_uint8_t(buf, 101, payload_radio_present);
-    _mav_put_uint8_t(buf, 102, ethernet_present);
-    _mav_put_uint8_t(buf, 103, ethernet_status);
+    _mav_put_float(buf, 64, battery_voltage);
+    _mav_put_int16_t(buf, 68, log_number);
+    _mav_put_uint8_t(buf, 70, state);
+    _mav_put_uint8_t(buf, 71, gps_fix);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -370,26 +242,10 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.payload_rx_rssi = payload_rx_rssi;
     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;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.log_number = log_number;
     packet.state = state;
     packet.gps_fix = gps_fix;
-    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_ARP_TM_LEN);
 #endif
@@ -408,7 +264,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage, arp_tm->log_number);
+    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->battery_voltage, arp_tm->log_number);
 }
 
 /**
@@ -422,7 +278,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage, arp_tm->log_number);
+    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->battery_voltage, arp_tm->log_number);
 }
 
 /**
@@ -446,28 +302,12 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  * @param gps_longitude [deg] Longitude
  * @param gps_height [m] Altitude
  * @param gps_fix  Wether the GPS has a FIX
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @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
  * @param log_number  Currently active log file, -1 if the logger is inactive
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, 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, 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, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage, int16_t log_number)
+static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, float battery_voltage, int16_t log_number)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -486,26 +326,10 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 52, gps_latitude);
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
-    _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, payload_rx_rssi);
-    _mav_put_float(buf, 72, battery_voltage);
-    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
-    _mav_put_int16_t(buf, 96, log_number);
-    _mav_put_uint8_t(buf, 98, state);
-    _mav_put_uint8_t(buf, 99, gps_fix);
-    _mav_put_uint8_t(buf, 100, main_radio_present);
-    _mav_put_uint8_t(buf, 101, payload_radio_present);
-    _mav_put_uint8_t(buf, 102, ethernet_present);
-    _mav_put_uint8_t(buf, 103, ethernet_status);
+    _mav_put_float(buf, 64, battery_voltage);
+    _mav_put_int16_t(buf, 68, log_number);
+    _mav_put_uint8_t(buf, 70, state);
+    _mav_put_uint8_t(buf, 71, gps_fix);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -525,26 +349,10 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     packet.gps_latitude = gps_latitude;
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.payload_rx_rssi = payload_rx_rssi;
     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;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.log_number = log_number;
     packet.state = state;
     packet.gps_fix = gps_fix;
-    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_ARP_TM, (const char *)&packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #endif
@@ -558,7 +366,7 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const mavlink_arp_tm_t* arp_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage, arp_tm->log_number);
+    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->state, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->battery_voltage, arp_tm->log_number);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)arp_tm, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #endif
@@ -572,7 +380,7 @@ static inline void mavlink_msg_arp_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_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, 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, 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, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage, int16_t log_number)
+static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t state, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, float battery_voltage, int16_t log_number)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -591,26 +399,10 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 52, gps_latitude);
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
-    _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, payload_rx_rssi);
-    _mav_put_float(buf, 72, battery_voltage);
-    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
-    _mav_put_int16_t(buf, 96, log_number);
-    _mav_put_uint8_t(buf, 98, state);
-    _mav_put_uint8_t(buf, 99, gps_fix);
-    _mav_put_uint8_t(buf, 100, main_radio_present);
-    _mav_put_uint8_t(buf, 101, payload_radio_present);
-    _mav_put_uint8_t(buf, 102, ethernet_present);
-    _mav_put_uint8_t(buf, 103, ethernet_status);
+    _mav_put_float(buf, 64, battery_voltage);
+    _mav_put_int16_t(buf, 68, log_number);
+    _mav_put_uint8_t(buf, 70, state);
+    _mav_put_uint8_t(buf, 71, gps_fix);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -630,26 +422,10 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->gps_latitude = gps_latitude;
     packet->gps_longitude = gps_longitude;
     packet->gps_height = gps_height;
-    packet->main_rx_rssi = main_rx_rssi;
-    packet->payload_rx_rssi = payload_rx_rssi;
     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;
-    packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet->main_rx_bitrate = main_rx_bitrate;
-    packet->payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet->payload_tx_bitrate = payload_tx_bitrate;
-    packet->payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet->payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet->payload_rx_bitrate = payload_rx_bitrate;
     packet->log_number = log_number;
     packet->state = state;
     packet->gps_fix = gps_fix;
-    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_ARP_TM, (const char *)packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #endif
@@ -678,7 +454,7 @@ static inline uint64_t mavlink_msg_arp_tm_get_timestamp(const mavlink_message_t*
  */
 static inline uint8_t mavlink_msg_arp_tm_get_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  98);
+    return _MAV_RETURN_uint8_t(msg,  70);
 }
 
 /**
@@ -828,167 +604,7 @@ static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* m
  */
 static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  99);
-}
-
-/**
- * @brief Get field main_radio_present from arp_tm message
- *
- * @return  Boolean indicating the presence of the main radio
- */
-static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  100);
-}
-
-/**
- * @brief Get field main_packet_tx_error_count from arp_tm message
- *
- * @return  Number of errors during send
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  76);
-}
-
-/**
- * @brief Get field main_tx_bitrate from arp_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  78);
-}
-
-/**
- * @brief Get field main_packet_rx_success_count from arp_tm message
- *
- * @return  Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  80);
-}
-
-/**
- * @brief Get field main_packet_rx_drop_count from arp_tm message
- *
- * @return  Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  82);
-}
-
-/**
- * @brief Get field main_rx_bitrate from arp_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  84);
-}
-
-/**
- * @brief Get field main_rx_rssi from arp_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  64);
-}
-
-/**
- * @brief Get field payload_radio_present from arp_tm message
- *
- * @return  Boolean indicating the presence of the payload radio
- */
-static inline uint8_t mavlink_msg_arp_tm_get_payload_radio_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  101);
-}
-
-/**
- * @brief Get field payload_packet_tx_error_count from arp_tm message
- *
- * @return  Number of errors during send
- */
-static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  86);
-}
-
-/**
- * @brief Get field payload_tx_bitrate from arp_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  88);
-}
-
-/**
- * @brief Get field payload_packet_rx_success_count from arp_tm message
- *
- * @return  Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  90);
-}
-
-/**
- * @brief Get field payload_packet_rx_drop_count from arp_tm message
- *
- * @return  Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  92);
-}
-
-/**
- * @brief Get field payload_rx_bitrate from arp_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  94);
-}
-
-/**
- * @brief Get field payload_rx_rssi from arp_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_arp_tm_get_payload_rx_rssi(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  68);
-}
-
-/**
- * @brief Get field ethernet_present from arp_tm message
- *
- * @return  Boolean indicating the presence of the ethernet module
- */
-static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  102);
-}
-
-/**
- * @brief Get field ethernet_status from arp_tm message
- *
- * @return  Status flag indicating the status of the ethernet PHY
- */
-static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  103);
+    return _MAV_RETURN_uint8_t(msg,  71);
 }
 
 /**
@@ -998,7 +614,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_messa
  */
 static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  72);
+    return _MAV_RETURN_float(msg,  64);
 }
 
 /**
@@ -1008,7 +624,7 @@ static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message
  */
 static inline int16_t mavlink_msg_arp_tm_get_log_number(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int16_t(msg,  96);
+    return _MAV_RETURN_int16_t(msg,  68);
 }
 
 /**
@@ -1035,26 +651,10 @@ static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavli
     arp_tm->gps_latitude = mavlink_msg_arp_tm_get_gps_latitude(msg);
     arp_tm->gps_longitude = mavlink_msg_arp_tm_get_gps_longitude(msg);
     arp_tm->gps_height = mavlink_msg_arp_tm_get_gps_height(msg);
-    arp_tm->main_rx_rssi = mavlink_msg_arp_tm_get_main_rx_rssi(msg);
-    arp_tm->payload_rx_rssi = mavlink_msg_arp_tm_get_payload_rx_rssi(msg);
     arp_tm->battery_voltage = mavlink_msg_arp_tm_get_battery_voltage(msg);
-    arp_tm->main_packet_tx_error_count = mavlink_msg_arp_tm_get_main_packet_tx_error_count(msg);
-    arp_tm->main_tx_bitrate = mavlink_msg_arp_tm_get_main_tx_bitrate(msg);
-    arp_tm->main_packet_rx_success_count = mavlink_msg_arp_tm_get_main_packet_rx_success_count(msg);
-    arp_tm->main_packet_rx_drop_count = mavlink_msg_arp_tm_get_main_packet_rx_drop_count(msg);
-    arp_tm->main_rx_bitrate = mavlink_msg_arp_tm_get_main_rx_bitrate(msg);
-    arp_tm->payload_packet_tx_error_count = mavlink_msg_arp_tm_get_payload_packet_tx_error_count(msg);
-    arp_tm->payload_tx_bitrate = mavlink_msg_arp_tm_get_payload_tx_bitrate(msg);
-    arp_tm->payload_packet_rx_success_count = mavlink_msg_arp_tm_get_payload_packet_rx_success_count(msg);
-    arp_tm->payload_packet_rx_drop_count = mavlink_msg_arp_tm_get_payload_packet_rx_drop_count(msg);
-    arp_tm->payload_rx_bitrate = mavlink_msg_arp_tm_get_payload_rx_bitrate(msg);
     arp_tm->log_number = mavlink_msg_arp_tm_get_log_number(msg);
     arp_tm->state = mavlink_msg_arp_tm_get_state(msg);
     arp_tm->gps_fix = mavlink_msg_arp_tm_get_gps_fix(msg);
-    arp_tm->main_radio_present = mavlink_msg_arp_tm_get_main_radio_present(msg);
-    arp_tm->payload_radio_present = mavlink_msg_arp_tm_get_payload_radio_present(msg);
-    arp_tm->ethernet_present = mavlink_msg_arp_tm_get_ethernet_present(msg);
-    arp_tm->ethernet_status = mavlink_msg_arp_tm_get_ethernet_status(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_ARP_TM_LEN? msg->len : MAVLINK_MSG_ID_ARP_TM_LEN;
         memset(arp_tm, 0, MAVLINK_MSG_ID_ARP_TM_LEN);
diff --git a/mavlink_lib/orion/mavlink_msg_gs_discovery_request.h b/mavlink_lib/orion/mavlink_msg_gs_discovery_request.h
new file mode 100644
index 0000000000000000000000000000000000000000..b54779571247c93f16a6bfb14726c08f950e204b
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_gs_discovery_request.h
@@ -0,0 +1,238 @@
+#pragma once
+// MESSAGE GS_DISCOVERY_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST 240
+
+
+typedef struct __mavlink_gs_discovery_request_t {
+ uint32_t source_ip; /*<  IP address of the requesting device*/
+ uint16_t source_port; /*<  Port of the requesting device*/
+} mavlink_gs_discovery_request_t;
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN 6
+#define MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN 6
+#define MAVLINK_MSG_ID_240_LEN 6
+#define MAVLINK_MSG_ID_240_MIN_LEN 6
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC 234
+#define MAVLINK_MSG_ID_240_CRC 234
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GS_DISCOVERY_REQUEST { \
+    240, \
+    "GS_DISCOVERY_REQUEST", \
+    2, \
+    {  { "source_ip", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gs_discovery_request_t, source_ip) }, \
+         { "source_port", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_gs_discovery_request_t, source_port) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GS_DISCOVERY_REQUEST { \
+    "GS_DISCOVERY_REQUEST", \
+    2, \
+    {  { "source_ip", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gs_discovery_request_t, source_ip) }, \
+         { "source_port", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_gs_discovery_request_t, source_port) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a gs_discovery_request message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param source_ip  IP address of the requesting device
+ * @param source_port  Port of the requesting device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gs_discovery_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t source_ip, uint16_t source_port)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN];
+    _mav_put_uint32_t(buf, 0, source_ip);
+    _mav_put_uint16_t(buf, 4, source_port);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN);
+#else
+    mavlink_gs_discovery_request_t packet;
+    packet.source_ip = source_ip;
+    packet.source_port = source_port;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+}
+
+/**
+ * @brief Pack a gs_discovery_request message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param source_ip  IP address of the requesting device
+ * @param source_port  Port of the requesting device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gs_discovery_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t source_ip,uint16_t source_port)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN];
+    _mav_put_uint32_t(buf, 0, source_ip);
+    _mav_put_uint16_t(buf, 4, source_port);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN);
+#else
+    mavlink_gs_discovery_request_t packet;
+    packet.source_ip = source_ip;
+    packet.source_port = source_port;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+}
+
+/**
+ * @brief Encode a gs_discovery_request struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param gs_discovery_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gs_discovery_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gs_discovery_request_t* gs_discovery_request)
+{
+    return mavlink_msg_gs_discovery_request_pack(system_id, component_id, msg, gs_discovery_request->source_ip, gs_discovery_request->source_port);
+}
+
+/**
+ * @brief Encode a gs_discovery_request struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param gs_discovery_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gs_discovery_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gs_discovery_request_t* gs_discovery_request)
+{
+    return mavlink_msg_gs_discovery_request_pack_chan(system_id, component_id, chan, msg, gs_discovery_request->source_ip, gs_discovery_request->source_port);
+}
+
+/**
+ * @brief Send a gs_discovery_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param source_ip  IP address of the requesting device
+ * @param source_port  Port of the requesting device
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gs_discovery_request_send(mavlink_channel_t chan, uint32_t source_ip, uint16_t source_port)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN];
+    _mav_put_uint32_t(buf, 0, source_ip);
+    _mav_put_uint16_t(buf, 4, source_port);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST, buf, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+#else
+    mavlink_gs_discovery_request_t packet;
+    packet.source_ip = source_ip;
+    packet.source_port = source_port;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gs_discovery_request message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gs_discovery_request_send_struct(mavlink_channel_t chan, const mavlink_gs_discovery_request_t* gs_discovery_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_gs_discovery_request_send(chan, gs_discovery_request->source_ip, gs_discovery_request->source_port);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST, (const char *)gs_discovery_request, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gs_discovery_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t source_ip, uint16_t source_port)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, source_ip);
+    _mav_put_uint16_t(buf, 4, source_port);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST, buf, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+#else
+    mavlink_gs_discovery_request_t *packet = (mavlink_gs_discovery_request_t *)msgbuf;
+    packet->source_ip = source_ip;
+    packet->source_port = source_port;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GS_DISCOVERY_REQUEST UNPACKING
+
+
+/**
+ * @brief Get field source_ip from gs_discovery_request message
+ *
+ * @return  IP address of the requesting device
+ */
+static inline uint32_t mavlink_msg_gs_discovery_request_get_source_ip(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field source_port from gs_discovery_request message
+ *
+ * @return  Port of the requesting device
+ */
+static inline uint16_t mavlink_msg_gs_discovery_request_get_source_port(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  4);
+}
+
+/**
+ * @brief Decode a gs_discovery_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param gs_discovery_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gs_discovery_request_decode(const mavlink_message_t* msg, mavlink_gs_discovery_request_t* gs_discovery_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    gs_discovery_request->source_ip = mavlink_msg_gs_discovery_request_get_source_ip(msg);
+    gs_discovery_request->source_port = mavlink_msg_gs_discovery_request_get_source_port(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN;
+        memset(gs_discovery_request, 0, MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_LEN);
+    memcpy(gs_discovery_request, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/mavlink_msg_gs_discovery_response.h b/mavlink_lib/orion/mavlink_msg_gs_discovery_response.h
new file mode 100644
index 0000000000000000000000000000000000000000..c104a94c99380bfa7a03be3fc684abf818a70030
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_gs_discovery_response.h
@@ -0,0 +1,363 @@
+#pragma once
+// MESSAGE GS_DISCOVERY_RESPONSE PACKING
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE 241
+
+
+typedef struct __mavlink_gs_discovery_response_t {
+ uint32_t ip; /*<  IP address of the device*/
+ uint32_t radio_433_frequency; /*< [Hz] Radio 433 frequency of the device*/
+ uint32_t radio_868_frequency; /*< [Hz] Radio 868 frequency of the device*/
+ uint16_t port; /*<  Port of the device*/
+ uint8_t device_id; /*<  Device ID*/
+ uint8_t radio_433_type; /*<  Radio 433 type of the device*/
+ uint8_t radio_868_type; /*<  Radio 868 type of the device*/
+} mavlink_gs_discovery_response_t;
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN 17
+#define MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN 17
+#define MAVLINK_MSG_ID_241_LEN 17
+#define MAVLINK_MSG_ID_241_MIN_LEN 17
+
+#define MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC 27
+#define MAVLINK_MSG_ID_241_CRC 27
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GS_DISCOVERY_RESPONSE { \
+    241, \
+    "GS_DISCOVERY_RESPONSE", \
+    7, \
+    {  { "ip", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gs_discovery_response_t, ip) }, \
+         { "port", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_gs_discovery_response_t, port) }, \
+         { "device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_gs_discovery_response_t, device_id) }, \
+         { "radio_433_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_gs_discovery_response_t, radio_433_type) }, \
+         { "radio_868_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_gs_discovery_response_t, radio_868_type) }, \
+         { "radio_433_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gs_discovery_response_t, radio_433_frequency) }, \
+         { "radio_868_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gs_discovery_response_t, radio_868_frequency) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GS_DISCOVERY_RESPONSE { \
+    "GS_DISCOVERY_RESPONSE", \
+    7, \
+    {  { "ip", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gs_discovery_response_t, ip) }, \
+         { "port", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_gs_discovery_response_t, port) }, \
+         { "device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_gs_discovery_response_t, device_id) }, \
+         { "radio_433_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_gs_discovery_response_t, radio_433_type) }, \
+         { "radio_868_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_gs_discovery_response_t, radio_868_type) }, \
+         { "radio_433_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gs_discovery_response_t, radio_433_frequency) }, \
+         { "radio_868_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gs_discovery_response_t, radio_868_frequency) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a gs_discovery_response message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param ip  IP address of the device
+ * @param port  Port of the device
+ * @param device_id  Device ID
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param radio_433_frequency [Hz] Radio 433 frequency of the device
+ * @param radio_868_frequency [Hz] Radio 868 frequency of the device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gs_discovery_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t ip, uint16_t port, uint8_t device_id, uint8_t radio_433_type, uint8_t radio_868_type, uint32_t radio_433_frequency, uint32_t radio_868_frequency)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN];
+    _mav_put_uint32_t(buf, 0, ip);
+    _mav_put_uint32_t(buf, 4, radio_433_frequency);
+    _mav_put_uint32_t(buf, 8, radio_868_frequency);
+    _mav_put_uint16_t(buf, 12, port);
+    _mav_put_uint8_t(buf, 14, device_id);
+    _mav_put_uint8_t(buf, 15, radio_433_type);
+    _mav_put_uint8_t(buf, 16, radio_868_type);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN);
+#else
+    mavlink_gs_discovery_response_t packet;
+    packet.ip = ip;
+    packet.radio_433_frequency = radio_433_frequency;
+    packet.radio_868_frequency = radio_868_frequency;
+    packet.port = port;
+    packet.device_id = device_id;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+}
+
+/**
+ * @brief Pack a gs_discovery_response message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param ip  IP address of the device
+ * @param port  Port of the device
+ * @param device_id  Device ID
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param radio_433_frequency [Hz] Radio 433 frequency of the device
+ * @param radio_868_frequency [Hz] Radio 868 frequency of the device
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gs_discovery_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t ip,uint16_t port,uint8_t device_id,uint8_t radio_433_type,uint8_t radio_868_type,uint32_t radio_433_frequency,uint32_t radio_868_frequency)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN];
+    _mav_put_uint32_t(buf, 0, ip);
+    _mav_put_uint32_t(buf, 4, radio_433_frequency);
+    _mav_put_uint32_t(buf, 8, radio_868_frequency);
+    _mav_put_uint16_t(buf, 12, port);
+    _mav_put_uint8_t(buf, 14, device_id);
+    _mav_put_uint8_t(buf, 15, radio_433_type);
+    _mav_put_uint8_t(buf, 16, radio_868_type);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN);
+#else
+    mavlink_gs_discovery_response_t packet;
+    packet.ip = ip;
+    packet.radio_433_frequency = radio_433_frequency;
+    packet.radio_868_frequency = radio_868_frequency;
+    packet.port = port;
+    packet.device_id = device_id;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+}
+
+/**
+ * @brief Encode a gs_discovery_response struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param gs_discovery_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gs_discovery_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gs_discovery_response_t* gs_discovery_response)
+{
+    return mavlink_msg_gs_discovery_response_pack(system_id, component_id, msg, gs_discovery_response->ip, gs_discovery_response->port, gs_discovery_response->device_id, gs_discovery_response->radio_433_type, gs_discovery_response->radio_868_type, gs_discovery_response->radio_433_frequency, gs_discovery_response->radio_868_frequency);
+}
+
+/**
+ * @brief Encode a gs_discovery_response struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param gs_discovery_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gs_discovery_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gs_discovery_response_t* gs_discovery_response)
+{
+    return mavlink_msg_gs_discovery_response_pack_chan(system_id, component_id, chan, msg, gs_discovery_response->ip, gs_discovery_response->port, gs_discovery_response->device_id, gs_discovery_response->radio_433_type, gs_discovery_response->radio_868_type, gs_discovery_response->radio_433_frequency, gs_discovery_response->radio_868_frequency);
+}
+
+/**
+ * @brief Send a gs_discovery_response message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param ip  IP address of the device
+ * @param port  Port of the device
+ * @param device_id  Device ID
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param radio_433_frequency [Hz] Radio 433 frequency of the device
+ * @param radio_868_frequency [Hz] Radio 868 frequency of the device
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gs_discovery_response_send(mavlink_channel_t chan, uint32_t ip, uint16_t port, uint8_t device_id, uint8_t radio_433_type, uint8_t radio_868_type, uint32_t radio_433_frequency, uint32_t radio_868_frequency)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN];
+    _mav_put_uint32_t(buf, 0, ip);
+    _mav_put_uint32_t(buf, 4, radio_433_frequency);
+    _mav_put_uint32_t(buf, 8, radio_868_frequency);
+    _mav_put_uint16_t(buf, 12, port);
+    _mav_put_uint8_t(buf, 14, device_id);
+    _mav_put_uint8_t(buf, 15, radio_433_type);
+    _mav_put_uint8_t(buf, 16, radio_868_type);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE, buf, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+#else
+    mavlink_gs_discovery_response_t packet;
+    packet.ip = ip;
+    packet.radio_433_frequency = radio_433_frequency;
+    packet.radio_868_frequency = radio_868_frequency;
+    packet.port = port;
+    packet.device_id = device_id;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gs_discovery_response message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gs_discovery_response_send_struct(mavlink_channel_t chan, const mavlink_gs_discovery_response_t* gs_discovery_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_gs_discovery_response_send(chan, gs_discovery_response->ip, gs_discovery_response->port, gs_discovery_response->device_id, gs_discovery_response->radio_433_type, gs_discovery_response->radio_868_type, gs_discovery_response->radio_433_frequency, gs_discovery_response->radio_868_frequency);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE, (const char *)gs_discovery_response, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gs_discovery_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t ip, uint16_t port, uint8_t device_id, uint8_t radio_433_type, uint8_t radio_868_type, uint32_t radio_433_frequency, uint32_t radio_868_frequency)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, ip);
+    _mav_put_uint32_t(buf, 4, radio_433_frequency);
+    _mav_put_uint32_t(buf, 8, radio_868_frequency);
+    _mav_put_uint16_t(buf, 12, port);
+    _mav_put_uint8_t(buf, 14, device_id);
+    _mav_put_uint8_t(buf, 15, radio_433_type);
+    _mav_put_uint8_t(buf, 16, radio_868_type);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE, buf, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+#else
+    mavlink_gs_discovery_response_t *packet = (mavlink_gs_discovery_response_t *)msgbuf;
+    packet->ip = ip;
+    packet->radio_433_frequency = radio_433_frequency;
+    packet->radio_868_frequency = radio_868_frequency;
+    packet->port = port;
+    packet->device_id = device_id;
+    packet->radio_433_type = radio_433_type;
+    packet->radio_868_type = radio_868_type;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GS_DISCOVERY_RESPONSE UNPACKING
+
+
+/**
+ * @brief Get field ip from gs_discovery_response message
+ *
+ * @return  IP address of the device
+ */
+static inline uint32_t mavlink_msg_gs_discovery_response_get_ip(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field port from gs_discovery_response message
+ *
+ * @return  Port of the device
+ */
+static inline uint16_t mavlink_msg_gs_discovery_response_get_port(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  12);
+}
+
+/**
+ * @brief Get field device_id from gs_discovery_response message
+ *
+ * @return  Device ID
+ */
+static inline uint8_t mavlink_msg_gs_discovery_response_get_device_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  14);
+}
+
+/**
+ * @brief Get field radio_433_type from gs_discovery_response message
+ *
+ * @return  Radio 433 type of the device
+ */
+static inline uint8_t mavlink_msg_gs_discovery_response_get_radio_433_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  15);
+}
+
+/**
+ * @brief Get field radio_868_type from gs_discovery_response message
+ *
+ * @return  Radio 868 type of the device
+ */
+static inline uint8_t mavlink_msg_gs_discovery_response_get_radio_868_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  16);
+}
+
+/**
+ * @brief Get field radio_433_frequency from gs_discovery_response message
+ *
+ * @return [Hz] Radio 433 frequency of the device
+ */
+static inline uint32_t mavlink_msg_gs_discovery_response_get_radio_433_frequency(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  4);
+}
+
+/**
+ * @brief Get field radio_868_frequency from gs_discovery_response message
+ *
+ * @return [Hz] Radio 868 frequency of the device
+ */
+static inline uint32_t mavlink_msg_gs_discovery_response_get_radio_868_frequency(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
+}
+
+/**
+ * @brief Decode a gs_discovery_response message into a struct
+ *
+ * @param msg The message to decode
+ * @param gs_discovery_response C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gs_discovery_response_decode(const mavlink_message_t* msg, mavlink_gs_discovery_response_t* gs_discovery_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    gs_discovery_response->ip = mavlink_msg_gs_discovery_response_get_ip(msg);
+    gs_discovery_response->radio_433_frequency = mavlink_msg_gs_discovery_response_get_radio_433_frequency(msg);
+    gs_discovery_response->radio_868_frequency = mavlink_msg_gs_discovery_response_get_radio_868_frequency(msg);
+    gs_discovery_response->port = mavlink_msg_gs_discovery_response_get_port(msg);
+    gs_discovery_response->device_id = mavlink_msg_gs_discovery_response_get_device_id(msg);
+    gs_discovery_response->radio_433_type = mavlink_msg_gs_discovery_response_get_radio_433_type(msg);
+    gs_discovery_response->radio_868_type = mavlink_msg_gs_discovery_response_get_radio_868_type(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN;
+        memset(gs_discovery_response, 0, MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_LEN);
+    memcpy(gs_discovery_response, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/mavlink_msg_gse_radio_link_info_tm.h b/mavlink_lib/orion/mavlink_msg_gse_radio_link_info_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..cc89d7a041e1a341a0df19da1ccba6b5f777c00e
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_gse_radio_link_info_tm.h
@@ -0,0 +1,388 @@
+#pragma once
+// MESSAGE GSE_RADIO_LINK_INFO_TM PACKING
+
+#define MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM 243
+
+
+typedef struct __mavlink_gse_radio_link_info_tm_t {
+ uint64_t timestamp; /*< [us] Timestamp in microseconds*/
+ uint32_t frequency; /*< [Hz] Radio frequency*/
+ uint16_t rx_success_count; /*<  Radio received packet count*/
+ uint16_t rx_drop_count; /*<  Radio dropped packet count (e.g. CRC mismatch)*/
+ uint16_t bitrate; /*< [b/s] Radio bitrate*/
+ int8_t rssi; /*< [dBm] Radio RSSI*/
+ int8_t snr; /*< [dB] Radio Signal to Noise Ratio*/
+ uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
+} mavlink_gse_radio_link_info_tm_t;
+
+#define MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN 21
+#define MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN 21
+#define MAVLINK_MSG_ID_243_LEN 21
+#define MAVLINK_MSG_ID_243_MIN_LEN 21
+
+#define MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC 8
+#define MAVLINK_MSG_ID_243_CRC 8
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GSE_RADIO_LINK_INFO_TM { \
+    243, \
+    "GSE_RADIO_LINK_INFO_TM", \
+    8, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_radio_link_info_tm_t, timestamp) }, \
+         { "rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 18, offsetof(mavlink_gse_radio_link_info_tm_t, rssi) }, \
+         { "snr", NULL, MAVLINK_TYPE_INT8_T, 0, 19, offsetof(mavlink_gse_radio_link_info_tm_t, snr) }, \
+         { "rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_gse_radio_link_info_tm_t, rx_success_count) }, \
+         { "rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_gse_radio_link_info_tm_t, rx_drop_count) }, \
+         { "bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_gse_radio_link_info_tm_t, bitrate) }, \
+         { "frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gse_radio_link_info_tm_t, frequency) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gse_radio_link_info_tm_t, ethernet_status) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GSE_RADIO_LINK_INFO_TM { \
+    "GSE_RADIO_LINK_INFO_TM", \
+    8, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_radio_link_info_tm_t, timestamp) }, \
+         { "rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 18, offsetof(mavlink_gse_radio_link_info_tm_t, rssi) }, \
+         { "snr", NULL, MAVLINK_TYPE_INT8_T, 0, 19, offsetof(mavlink_gse_radio_link_info_tm_t, snr) }, \
+         { "rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_gse_radio_link_info_tm_t, rx_success_count) }, \
+         { "rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_gse_radio_link_info_tm_t, rx_drop_count) }, \
+         { "bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_gse_radio_link_info_tm_t, bitrate) }, \
+         { "frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gse_radio_link_info_tm_t, frequency) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gse_radio_link_info_tm_t, ethernet_status) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a gse_radio_link_info_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param rssi [dBm] Radio RSSI
+ * @param snr [dB] Radio Signal to Noise Ratio
+ * @param rx_success_count  Radio received packet count
+ * @param rx_drop_count  Radio dropped packet count (e.g. CRC mismatch)
+ * @param bitrate [b/s] Radio bitrate
+ * @param frequency [Hz] Radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t timestamp, int8_t rssi, int8_t snr, uint16_t rx_success_count, uint16_t rx_drop_count, uint16_t bitrate, uint32_t frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, frequency);
+    _mav_put_uint16_t(buf, 12, rx_success_count);
+    _mav_put_uint16_t(buf, 14, rx_drop_count);
+    _mav_put_uint16_t(buf, 16, bitrate);
+    _mav_put_int8_t(buf, 18, rssi);
+    _mav_put_int8_t(buf, 19, snr);
+    _mav_put_uint8_t(buf, 20, ethernet_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN);
+#else
+    mavlink_gse_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.frequency = frequency;
+    packet.rx_success_count = rx_success_count;
+    packet.rx_drop_count = rx_drop_count;
+    packet.bitrate = bitrate;
+    packet.rssi = rssi;
+    packet.snr = snr;
+    packet.ethernet_status = ethernet_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+}
+
+/**
+ * @brief Pack a gse_radio_link_info_tm message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param timestamp [us] Timestamp in microseconds
+ * @param rssi [dBm] Radio RSSI
+ * @param snr [dB] Radio Signal to Noise Ratio
+ * @param rx_success_count  Radio received packet count
+ * @param rx_drop_count  Radio dropped packet count (e.g. CRC mismatch)
+ * @param bitrate [b/s] Radio bitrate
+ * @param frequency [Hz] Radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t timestamp,int8_t rssi,int8_t snr,uint16_t rx_success_count,uint16_t rx_drop_count,uint16_t bitrate,uint32_t frequency,uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, frequency);
+    _mav_put_uint16_t(buf, 12, rx_success_count);
+    _mav_put_uint16_t(buf, 14, rx_drop_count);
+    _mav_put_uint16_t(buf, 16, bitrate);
+    _mav_put_int8_t(buf, 18, rssi);
+    _mav_put_int8_t(buf, 19, snr);
+    _mav_put_uint8_t(buf, 20, ethernet_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN);
+#else
+    mavlink_gse_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.frequency = frequency;
+    packet.rx_success_count = rx_success_count;
+    packet.rx_drop_count = rx_drop_count;
+    packet.bitrate = bitrate;
+    packet.rssi = rssi;
+    packet.snr = snr;
+    packet.ethernet_status = ethernet_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+}
+
+/**
+ * @brief Encode a gse_radio_link_info_tm struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param gse_radio_link_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_radio_link_info_tm_t* gse_radio_link_info_tm)
+{
+    return mavlink_msg_gse_radio_link_info_tm_pack(system_id, component_id, msg, gse_radio_link_info_tm->timestamp, gse_radio_link_info_tm->rssi, gse_radio_link_info_tm->snr, gse_radio_link_info_tm->rx_success_count, gse_radio_link_info_tm->rx_drop_count, gse_radio_link_info_tm->bitrate, gse_radio_link_info_tm->frequency, gse_radio_link_info_tm->ethernet_status);
+}
+
+/**
+ * @brief Encode a gse_radio_link_info_tm struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param gse_radio_link_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_radio_link_info_tm_t* gse_radio_link_info_tm)
+{
+    return mavlink_msg_gse_radio_link_info_tm_pack_chan(system_id, component_id, chan, msg, gse_radio_link_info_tm->timestamp, gse_radio_link_info_tm->rssi, gse_radio_link_info_tm->snr, gse_radio_link_info_tm->rx_success_count, gse_radio_link_info_tm->rx_drop_count, gse_radio_link_info_tm->bitrate, gse_radio_link_info_tm->frequency, gse_radio_link_info_tm->ethernet_status);
+}
+
+/**
+ * @brief Send a gse_radio_link_info_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param rssi [dBm] Radio RSSI
+ * @param snr [dB] Radio Signal to Noise Ratio
+ * @param rx_success_count  Radio received packet count
+ * @param rx_drop_count  Radio dropped packet count (e.g. CRC mismatch)
+ * @param bitrate [b/s] Radio bitrate
+ * @param frequency [Hz] Radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gse_radio_link_info_tm_send(mavlink_channel_t chan, uint64_t timestamp, int8_t rssi, int8_t snr, uint16_t rx_success_count, uint16_t rx_drop_count, uint16_t bitrate, uint32_t frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, frequency);
+    _mav_put_uint16_t(buf, 12, rx_success_count);
+    _mav_put_uint16_t(buf, 14, rx_drop_count);
+    _mav_put_uint16_t(buf, 16, bitrate);
+    _mav_put_int8_t(buf, 18, rssi);
+    _mav_put_int8_t(buf, 19, snr);
+    _mav_put_uint8_t(buf, 20, ethernet_status);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM, buf, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+#else
+    mavlink_gse_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.frequency = frequency;
+    packet.rx_success_count = rx_success_count;
+    packet.rx_drop_count = rx_drop_count;
+    packet.bitrate = bitrate;
+    packet.rssi = rssi;
+    packet.snr = snr;
+    packet.ethernet_status = ethernet_status;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM, (const char *)&packet, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gse_radio_link_info_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gse_radio_link_info_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_radio_link_info_tm_t* gse_radio_link_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_gse_radio_link_info_tm_send(chan, gse_radio_link_info_tm->timestamp, gse_radio_link_info_tm->rssi, gse_radio_link_info_tm->snr, gse_radio_link_info_tm->rx_success_count, gse_radio_link_info_tm->rx_drop_count, gse_radio_link_info_tm->bitrate, gse_radio_link_info_tm->frequency, gse_radio_link_info_tm->ethernet_status);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM, (const char *)gse_radio_link_info_tm, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gse_radio_link_info_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, int8_t rssi, int8_t snr, uint16_t rx_success_count, uint16_t rx_drop_count, uint16_t bitrate, uint32_t frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, frequency);
+    _mav_put_uint16_t(buf, 12, rx_success_count);
+    _mav_put_uint16_t(buf, 14, rx_drop_count);
+    _mav_put_uint16_t(buf, 16, bitrate);
+    _mav_put_int8_t(buf, 18, rssi);
+    _mav_put_int8_t(buf, 19, snr);
+    _mav_put_uint8_t(buf, 20, ethernet_status);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM, buf, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+#else
+    mavlink_gse_radio_link_info_tm_t *packet = (mavlink_gse_radio_link_info_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->frequency = frequency;
+    packet->rx_success_count = rx_success_count;
+    packet->rx_drop_count = rx_drop_count;
+    packet->bitrate = bitrate;
+    packet->rssi = rssi;
+    packet->snr = snr;
+    packet->ethernet_status = ethernet_status;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM, (const char *)packet, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GSE_RADIO_LINK_INFO_TM UNPACKING
+
+
+/**
+ * @brief Get field timestamp from gse_radio_link_info_tm message
+ *
+ * @return [us] Timestamp in microseconds
+ */
+static inline uint64_t mavlink_msg_gse_radio_link_info_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field rssi from gse_radio_link_info_tm message
+ *
+ * @return [dBm] Radio RSSI
+ */
+static inline int8_t mavlink_msg_gse_radio_link_info_tm_get_rssi(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int8_t(msg,  18);
+}
+
+/**
+ * @brief Get field snr from gse_radio_link_info_tm message
+ *
+ * @return [dB] Radio Signal to Noise Ratio
+ */
+static inline int8_t mavlink_msg_gse_radio_link_info_tm_get_snr(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int8_t(msg,  19);
+}
+
+/**
+ * @brief Get field rx_success_count from gse_radio_link_info_tm message
+ *
+ * @return  Radio received packet count
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_get_rx_success_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  12);
+}
+
+/**
+ * @brief Get field rx_drop_count from gse_radio_link_info_tm message
+ *
+ * @return  Radio dropped packet count (e.g. CRC mismatch)
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_get_rx_drop_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  14);
+}
+
+/**
+ * @brief Get field bitrate from gse_radio_link_info_tm message
+ *
+ * @return [b/s] Radio bitrate
+ */
+static inline uint16_t mavlink_msg_gse_radio_link_info_tm_get_bitrate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  16);
+}
+
+/**
+ * @brief Get field frequency from gse_radio_link_info_tm message
+ *
+ * @return [Hz] Radio frequency
+ */
+static inline uint32_t mavlink_msg_gse_radio_link_info_tm_get_frequency(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
+}
+
+/**
+ * @brief Get field ethernet_status from gse_radio_link_info_tm message
+ *
+ * @return  Status flag indicating the status of the ethernet PHY
+ */
+static inline uint8_t mavlink_msg_gse_radio_link_info_tm_get_ethernet_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  20);
+}
+
+/**
+ * @brief Decode a gse_radio_link_info_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param gse_radio_link_info_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gse_radio_link_info_tm_decode(const mavlink_message_t* msg, mavlink_gse_radio_link_info_tm_t* gse_radio_link_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    gse_radio_link_info_tm->timestamp = mavlink_msg_gse_radio_link_info_tm_get_timestamp(msg);
+    gse_radio_link_info_tm->frequency = mavlink_msg_gse_radio_link_info_tm_get_frequency(msg);
+    gse_radio_link_info_tm->rx_success_count = mavlink_msg_gse_radio_link_info_tm_get_rx_success_count(msg);
+    gse_radio_link_info_tm->rx_drop_count = mavlink_msg_gse_radio_link_info_tm_get_rx_drop_count(msg);
+    gse_radio_link_info_tm->bitrate = mavlink_msg_gse_radio_link_info_tm_get_bitrate(msg);
+    gse_radio_link_info_tm->rssi = mavlink_msg_gse_radio_link_info_tm_get_rssi(msg);
+    gse_radio_link_info_tm->snr = mavlink_msg_gse_radio_link_info_tm_get_snr(msg);
+    gse_radio_link_info_tm->ethernet_status = mavlink_msg_gse_radio_link_info_tm_get_ethernet_status(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN? msg->len : MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN;
+        memset(gse_radio_link_info_tm, 0, MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_LEN);
+    memcpy(gse_radio_link_info_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/mavlink_msg_rocket_radio_link_info_tm.h b/mavlink_lib/orion/mavlink_msg_rocket_radio_link_info_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..40b6b9f7bc80ca47d9c0916144d1a8330fe000e0
--- /dev/null
+++ b/mavlink_lib/orion/mavlink_msg_rocket_radio_link_info_tm.h
@@ -0,0 +1,538 @@
+#pragma once
+// MESSAGE ROCKET_RADIO_LINK_INFO_TM PACKING
+
+#define MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM 242
+
+
+typedef struct __mavlink_rocket_radio_link_info_tm_t {
+ uint64_t timestamp; /*< [us] Timestamp in microseconds*/
+ uint32_t main_frequency; /*< [Hz] Main radio frequency*/
+ uint32_t payload_frequency; /*< [Hz] Payload radio frequency*/
+ uint16_t main_rx_success_count; /*<  Main radio received packet count*/
+ uint16_t main_rx_drop_count; /*<  Main radio dropped packet count (e.g. CRC mismatch)*/
+ uint16_t main_bitrate; /*< [b/s] Main radio bitrate*/
+ uint16_t payload_rx_success_count; /*<  Payload radio received packet count*/
+ uint16_t payload_rx_drop_count; /*<  Payload radio dropped packet count (e.g. CRC mismatch)*/
+ uint16_t payload_bitrate; /*< [b/s] Payload radio bitrate*/
+ uint8_t radio_433_type; /*<  Radio 433 type of the device*/
+ uint8_t radio_868_type; /*<  Radio 868 type of the device*/
+ int8_t main_rssi; /*< [dBm] Main radio RSSI*/
+ int8_t payload_rssi; /*< [dBm] Payload radio RSSI*/
+ uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
+} mavlink_rocket_radio_link_info_tm_t;
+
+#define MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN 33
+#define MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN 33
+#define MAVLINK_MSG_ID_242_LEN 33
+#define MAVLINK_MSG_ID_242_MIN_LEN 33
+
+#define MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC 97
+#define MAVLINK_MSG_ID_242_CRC 97
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ROCKET_RADIO_LINK_INFO_TM { \
+    242, \
+    "ROCKET_RADIO_LINK_INFO_TM", \
+    14, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_radio_link_info_tm_t, timestamp) }, \
+         { "radio_433_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_rocket_radio_link_info_tm_t, radio_433_type) }, \
+         { "radio_868_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_rocket_radio_link_info_tm_t, radio_868_type) }, \
+         { "main_rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rssi) }, \
+         { "main_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rx_success_count) }, \
+         { "main_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rx_drop_count) }, \
+         { "main_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rocket_radio_link_info_tm_t, main_bitrate) }, \
+         { "main_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_rocket_radio_link_info_tm_t, main_frequency) }, \
+         { "payload_rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 31, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rssi) }, \
+         { "payload_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rx_success_count) }, \
+         { "payload_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rx_drop_count) }, \
+         { "payload_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_bitrate) }, \
+         { "payload_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_frequency) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_rocket_radio_link_info_tm_t, ethernet_status) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ROCKET_RADIO_LINK_INFO_TM { \
+    "ROCKET_RADIO_LINK_INFO_TM", \
+    14, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_radio_link_info_tm_t, timestamp) }, \
+         { "radio_433_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_rocket_radio_link_info_tm_t, radio_433_type) }, \
+         { "radio_868_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_rocket_radio_link_info_tm_t, radio_868_type) }, \
+         { "main_rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rssi) }, \
+         { "main_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rx_success_count) }, \
+         { "main_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rocket_radio_link_info_tm_t, main_rx_drop_count) }, \
+         { "main_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rocket_radio_link_info_tm_t, main_bitrate) }, \
+         { "main_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_rocket_radio_link_info_tm_t, main_frequency) }, \
+         { "payload_rssi", NULL, MAVLINK_TYPE_INT8_T, 0, 31, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rssi) }, \
+         { "payload_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rx_success_count) }, \
+         { "payload_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_rx_drop_count) }, \
+         { "payload_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_bitrate) }, \
+         { "payload_frequency", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_rocket_radio_link_info_tm_t, payload_frequency) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_rocket_radio_link_info_tm_t, ethernet_status) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a rocket_radio_link_info_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param main_rssi [dBm] Main radio RSSI
+ * @param main_rx_success_count  Main radio received packet count
+ * @param main_rx_drop_count  Main radio dropped packet count (e.g. CRC mismatch)
+ * @param main_bitrate [b/s] Main radio bitrate
+ * @param main_frequency [Hz] Main radio frequency
+ * @param payload_rssi [dBm] Payload radio RSSI
+ * @param payload_rx_success_count  Payload radio received packet count
+ * @param payload_rx_drop_count  Payload radio dropped packet count (e.g. CRC mismatch)
+ * @param payload_bitrate [b/s] Payload radio bitrate
+ * @param payload_frequency [Hz] Payload radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t radio_433_type, uint8_t radio_868_type, int8_t main_rssi, uint16_t main_rx_success_count, uint16_t main_rx_drop_count, uint16_t main_bitrate, uint32_t main_frequency, int8_t payload_rssi, uint16_t payload_rx_success_count, uint16_t payload_rx_drop_count, uint16_t payload_bitrate, uint32_t payload_frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, main_frequency);
+    _mav_put_uint32_t(buf, 12, payload_frequency);
+    _mav_put_uint16_t(buf, 16, main_rx_success_count);
+    _mav_put_uint16_t(buf, 18, main_rx_drop_count);
+    _mav_put_uint16_t(buf, 20, main_bitrate);
+    _mav_put_uint16_t(buf, 22, payload_rx_success_count);
+    _mav_put_uint16_t(buf, 24, payload_rx_drop_count);
+    _mav_put_uint16_t(buf, 26, payload_bitrate);
+    _mav_put_uint8_t(buf, 28, radio_433_type);
+    _mav_put_uint8_t(buf, 29, radio_868_type);
+    _mav_put_int8_t(buf, 30, main_rssi);
+    _mav_put_int8_t(buf, 31, payload_rssi);
+    _mav_put_uint8_t(buf, 32, ethernet_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN);
+#else
+    mavlink_rocket_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.main_frequency = main_frequency;
+    packet.payload_frequency = payload_frequency;
+    packet.main_rx_success_count = main_rx_success_count;
+    packet.main_rx_drop_count = main_rx_drop_count;
+    packet.main_bitrate = main_bitrate;
+    packet.payload_rx_success_count = payload_rx_success_count;
+    packet.payload_rx_drop_count = payload_rx_drop_count;
+    packet.payload_bitrate = payload_bitrate;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+    packet.main_rssi = main_rssi;
+    packet.payload_rssi = payload_rssi;
+    packet.ethernet_status = ethernet_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+}
+
+/**
+ * @brief Pack a rocket_radio_link_info_tm message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param timestamp [us] Timestamp in microseconds
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param main_rssi [dBm] Main radio RSSI
+ * @param main_rx_success_count  Main radio received packet count
+ * @param main_rx_drop_count  Main radio dropped packet count (e.g. CRC mismatch)
+ * @param main_bitrate [b/s] Main radio bitrate
+ * @param main_frequency [Hz] Main radio frequency
+ * @param payload_rssi [dBm] Payload radio RSSI
+ * @param payload_rx_success_count  Payload radio received packet count
+ * @param payload_rx_drop_count  Payload radio dropped packet count (e.g. CRC mismatch)
+ * @param payload_bitrate [b/s] Payload radio bitrate
+ * @param payload_frequency [Hz] Payload radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t timestamp,uint8_t radio_433_type,uint8_t radio_868_type,int8_t main_rssi,uint16_t main_rx_success_count,uint16_t main_rx_drop_count,uint16_t main_bitrate,uint32_t main_frequency,int8_t payload_rssi,uint16_t payload_rx_success_count,uint16_t payload_rx_drop_count,uint16_t payload_bitrate,uint32_t payload_frequency,uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, main_frequency);
+    _mav_put_uint32_t(buf, 12, payload_frequency);
+    _mav_put_uint16_t(buf, 16, main_rx_success_count);
+    _mav_put_uint16_t(buf, 18, main_rx_drop_count);
+    _mav_put_uint16_t(buf, 20, main_bitrate);
+    _mav_put_uint16_t(buf, 22, payload_rx_success_count);
+    _mav_put_uint16_t(buf, 24, payload_rx_drop_count);
+    _mav_put_uint16_t(buf, 26, payload_bitrate);
+    _mav_put_uint8_t(buf, 28, radio_433_type);
+    _mav_put_uint8_t(buf, 29, radio_868_type);
+    _mav_put_int8_t(buf, 30, main_rssi);
+    _mav_put_int8_t(buf, 31, payload_rssi);
+    _mav_put_uint8_t(buf, 32, ethernet_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN);
+#else
+    mavlink_rocket_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.main_frequency = main_frequency;
+    packet.payload_frequency = payload_frequency;
+    packet.main_rx_success_count = main_rx_success_count;
+    packet.main_rx_drop_count = main_rx_drop_count;
+    packet.main_bitrate = main_bitrate;
+    packet.payload_rx_success_count = payload_rx_success_count;
+    packet.payload_rx_drop_count = payload_rx_drop_count;
+    packet.payload_bitrate = payload_bitrate;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+    packet.main_rssi = main_rssi;
+    packet.payload_rssi = payload_rssi;
+    packet.ethernet_status = ethernet_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+}
+
+/**
+ * @brief Encode a rocket_radio_link_info_tm struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param rocket_radio_link_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_radio_link_info_tm_t* rocket_radio_link_info_tm)
+{
+    return mavlink_msg_rocket_radio_link_info_tm_pack(system_id, component_id, msg, rocket_radio_link_info_tm->timestamp, rocket_radio_link_info_tm->radio_433_type, rocket_radio_link_info_tm->radio_868_type, rocket_radio_link_info_tm->main_rssi, rocket_radio_link_info_tm->main_rx_success_count, rocket_radio_link_info_tm->main_rx_drop_count, rocket_radio_link_info_tm->main_bitrate, rocket_radio_link_info_tm->main_frequency, rocket_radio_link_info_tm->payload_rssi, rocket_radio_link_info_tm->payload_rx_success_count, rocket_radio_link_info_tm->payload_rx_drop_count, rocket_radio_link_info_tm->payload_bitrate, rocket_radio_link_info_tm->payload_frequency, rocket_radio_link_info_tm->ethernet_status);
+}
+
+/**
+ * @brief Encode a rocket_radio_link_info_tm struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param rocket_radio_link_info_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_radio_link_info_tm_t* rocket_radio_link_info_tm)
+{
+    return mavlink_msg_rocket_radio_link_info_tm_pack_chan(system_id, component_id, chan, msg, rocket_radio_link_info_tm->timestamp, rocket_radio_link_info_tm->radio_433_type, rocket_radio_link_info_tm->radio_868_type, rocket_radio_link_info_tm->main_rssi, rocket_radio_link_info_tm->main_rx_success_count, rocket_radio_link_info_tm->main_rx_drop_count, rocket_radio_link_info_tm->main_bitrate, rocket_radio_link_info_tm->main_frequency, rocket_radio_link_info_tm->payload_rssi, rocket_radio_link_info_tm->payload_rx_success_count, rocket_radio_link_info_tm->payload_rx_drop_count, rocket_radio_link_info_tm->payload_bitrate, rocket_radio_link_info_tm->payload_frequency, rocket_radio_link_info_tm->ethernet_status);
+}
+
+/**
+ * @brief Send a rocket_radio_link_info_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param radio_433_type  Radio 433 type of the device
+ * @param radio_868_type  Radio 868 type of the device
+ * @param main_rssi [dBm] Main radio RSSI
+ * @param main_rx_success_count  Main radio received packet count
+ * @param main_rx_drop_count  Main radio dropped packet count (e.g. CRC mismatch)
+ * @param main_bitrate [b/s] Main radio bitrate
+ * @param main_frequency [Hz] Main radio frequency
+ * @param payload_rssi [dBm] Payload radio RSSI
+ * @param payload_rx_success_count  Payload radio received packet count
+ * @param payload_rx_drop_count  Payload radio dropped packet count (e.g. CRC mismatch)
+ * @param payload_bitrate [b/s] Payload radio bitrate
+ * @param payload_frequency [Hz] Payload radio frequency
+ * @param ethernet_status  Status flag indicating the status of the ethernet PHY
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rocket_radio_link_info_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t radio_433_type, uint8_t radio_868_type, int8_t main_rssi, uint16_t main_rx_success_count, uint16_t main_rx_drop_count, uint16_t main_bitrate, uint32_t main_frequency, int8_t payload_rssi, uint16_t payload_rx_success_count, uint16_t payload_rx_drop_count, uint16_t payload_bitrate, uint32_t payload_frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, main_frequency);
+    _mav_put_uint32_t(buf, 12, payload_frequency);
+    _mav_put_uint16_t(buf, 16, main_rx_success_count);
+    _mav_put_uint16_t(buf, 18, main_rx_drop_count);
+    _mav_put_uint16_t(buf, 20, main_bitrate);
+    _mav_put_uint16_t(buf, 22, payload_rx_success_count);
+    _mav_put_uint16_t(buf, 24, payload_rx_drop_count);
+    _mav_put_uint16_t(buf, 26, payload_bitrate);
+    _mav_put_uint8_t(buf, 28, radio_433_type);
+    _mav_put_uint8_t(buf, 29, radio_868_type);
+    _mav_put_int8_t(buf, 30, main_rssi);
+    _mav_put_int8_t(buf, 31, payload_rssi);
+    _mav_put_uint8_t(buf, 32, ethernet_status);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM, buf, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+#else
+    mavlink_rocket_radio_link_info_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.main_frequency = main_frequency;
+    packet.payload_frequency = payload_frequency;
+    packet.main_rx_success_count = main_rx_success_count;
+    packet.main_rx_drop_count = main_rx_drop_count;
+    packet.main_bitrate = main_bitrate;
+    packet.payload_rx_success_count = payload_rx_success_count;
+    packet.payload_rx_drop_count = payload_rx_drop_count;
+    packet.payload_bitrate = payload_bitrate;
+    packet.radio_433_type = radio_433_type;
+    packet.radio_868_type = radio_868_type;
+    packet.main_rssi = main_rssi;
+    packet.payload_rssi = payload_rssi;
+    packet.ethernet_status = ethernet_status;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a rocket_radio_link_info_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_rocket_radio_link_info_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_radio_link_info_tm_t* rocket_radio_link_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_rocket_radio_link_info_tm_send(chan, rocket_radio_link_info_tm->timestamp, rocket_radio_link_info_tm->radio_433_type, rocket_radio_link_info_tm->radio_868_type, rocket_radio_link_info_tm->main_rssi, rocket_radio_link_info_tm->main_rx_success_count, rocket_radio_link_info_tm->main_rx_drop_count, rocket_radio_link_info_tm->main_bitrate, rocket_radio_link_info_tm->main_frequency, rocket_radio_link_info_tm->payload_rssi, rocket_radio_link_info_tm->payload_rx_success_count, rocket_radio_link_info_tm->payload_rx_drop_count, rocket_radio_link_info_tm->payload_bitrate, rocket_radio_link_info_tm->payload_frequency, rocket_radio_link_info_tm->ethernet_status);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM, (const char *)rocket_radio_link_info_tm, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rocket_radio_link_info_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t radio_433_type, uint8_t radio_868_type, int8_t main_rssi, uint16_t main_rx_success_count, uint16_t main_rx_drop_count, uint16_t main_bitrate, uint32_t main_frequency, int8_t payload_rssi, uint16_t payload_rx_success_count, uint16_t payload_rx_drop_count, uint16_t payload_bitrate, uint32_t payload_frequency, uint8_t ethernet_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, main_frequency);
+    _mav_put_uint32_t(buf, 12, payload_frequency);
+    _mav_put_uint16_t(buf, 16, main_rx_success_count);
+    _mav_put_uint16_t(buf, 18, main_rx_drop_count);
+    _mav_put_uint16_t(buf, 20, main_bitrate);
+    _mav_put_uint16_t(buf, 22, payload_rx_success_count);
+    _mav_put_uint16_t(buf, 24, payload_rx_drop_count);
+    _mav_put_uint16_t(buf, 26, payload_bitrate);
+    _mav_put_uint8_t(buf, 28, radio_433_type);
+    _mav_put_uint8_t(buf, 29, radio_868_type);
+    _mav_put_int8_t(buf, 30, main_rssi);
+    _mav_put_int8_t(buf, 31, payload_rssi);
+    _mav_put_uint8_t(buf, 32, ethernet_status);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM, buf, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+#else
+    mavlink_rocket_radio_link_info_tm_t *packet = (mavlink_rocket_radio_link_info_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->main_frequency = main_frequency;
+    packet->payload_frequency = payload_frequency;
+    packet->main_rx_success_count = main_rx_success_count;
+    packet->main_rx_drop_count = main_rx_drop_count;
+    packet->main_bitrate = main_bitrate;
+    packet->payload_rx_success_count = payload_rx_success_count;
+    packet->payload_rx_drop_count = payload_rx_drop_count;
+    packet->payload_bitrate = payload_bitrate;
+    packet->radio_433_type = radio_433_type;
+    packet->radio_868_type = radio_868_type;
+    packet->main_rssi = main_rssi;
+    packet->payload_rssi = payload_rssi;
+    packet->ethernet_status = ethernet_status;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ROCKET_RADIO_LINK_INFO_TM UNPACKING
+
+
+/**
+ * @brief Get field timestamp from rocket_radio_link_info_tm message
+ *
+ * @return [us] Timestamp in microseconds
+ */
+static inline uint64_t mavlink_msg_rocket_radio_link_info_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field radio_433_type from rocket_radio_link_info_tm message
+ *
+ * @return  Radio 433 type of the device
+ */
+static inline uint8_t mavlink_msg_rocket_radio_link_info_tm_get_radio_433_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  28);
+}
+
+/**
+ * @brief Get field radio_868_type from rocket_radio_link_info_tm message
+ *
+ * @return  Radio 868 type of the device
+ */
+static inline uint8_t mavlink_msg_rocket_radio_link_info_tm_get_radio_868_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  29);
+}
+
+/**
+ * @brief Get field main_rssi from rocket_radio_link_info_tm message
+ *
+ * @return [dBm] Main radio RSSI
+ */
+static inline int8_t mavlink_msg_rocket_radio_link_info_tm_get_main_rssi(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int8_t(msg,  30);
+}
+
+/**
+ * @brief Get field main_rx_success_count from rocket_radio_link_info_tm message
+ *
+ * @return  Main radio received packet count
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_main_rx_success_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  16);
+}
+
+/**
+ * @brief Get field main_rx_drop_count from rocket_radio_link_info_tm message
+ *
+ * @return  Main radio dropped packet count (e.g. CRC mismatch)
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_main_rx_drop_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  18);
+}
+
+/**
+ * @brief Get field main_bitrate from rocket_radio_link_info_tm message
+ *
+ * @return [b/s] Main radio bitrate
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_main_bitrate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  20);
+}
+
+/**
+ * @brief Get field main_frequency from rocket_radio_link_info_tm message
+ *
+ * @return [Hz] Main radio frequency
+ */
+static inline uint32_t mavlink_msg_rocket_radio_link_info_tm_get_main_frequency(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
+}
+
+/**
+ * @brief Get field payload_rssi from rocket_radio_link_info_tm message
+ *
+ * @return [dBm] Payload radio RSSI
+ */
+static inline int8_t mavlink_msg_rocket_radio_link_info_tm_get_payload_rssi(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int8_t(msg,  31);
+}
+
+/**
+ * @brief Get field payload_rx_success_count from rocket_radio_link_info_tm message
+ *
+ * @return  Payload radio received packet count
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_payload_rx_success_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  22);
+}
+
+/**
+ * @brief Get field payload_rx_drop_count from rocket_radio_link_info_tm message
+ *
+ * @return  Payload radio dropped packet count (e.g. CRC mismatch)
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_payload_rx_drop_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  24);
+}
+
+/**
+ * @brief Get field payload_bitrate from rocket_radio_link_info_tm message
+ *
+ * @return [b/s] Payload radio bitrate
+ */
+static inline uint16_t mavlink_msg_rocket_radio_link_info_tm_get_payload_bitrate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  26);
+}
+
+/**
+ * @brief Get field payload_frequency from rocket_radio_link_info_tm message
+ *
+ * @return [Hz] Payload radio frequency
+ */
+static inline uint32_t mavlink_msg_rocket_radio_link_info_tm_get_payload_frequency(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  12);
+}
+
+/**
+ * @brief Get field ethernet_status from rocket_radio_link_info_tm message
+ *
+ * @return  Status flag indicating the status of the ethernet PHY
+ */
+static inline uint8_t mavlink_msg_rocket_radio_link_info_tm_get_ethernet_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  32);
+}
+
+/**
+ * @brief Decode a rocket_radio_link_info_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param rocket_radio_link_info_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rocket_radio_link_info_tm_decode(const mavlink_message_t* msg, mavlink_rocket_radio_link_info_tm_t* rocket_radio_link_info_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    rocket_radio_link_info_tm->timestamp = mavlink_msg_rocket_radio_link_info_tm_get_timestamp(msg);
+    rocket_radio_link_info_tm->main_frequency = mavlink_msg_rocket_radio_link_info_tm_get_main_frequency(msg);
+    rocket_radio_link_info_tm->payload_frequency = mavlink_msg_rocket_radio_link_info_tm_get_payload_frequency(msg);
+    rocket_radio_link_info_tm->main_rx_success_count = mavlink_msg_rocket_radio_link_info_tm_get_main_rx_success_count(msg);
+    rocket_radio_link_info_tm->main_rx_drop_count = mavlink_msg_rocket_radio_link_info_tm_get_main_rx_drop_count(msg);
+    rocket_radio_link_info_tm->main_bitrate = mavlink_msg_rocket_radio_link_info_tm_get_main_bitrate(msg);
+    rocket_radio_link_info_tm->payload_rx_success_count = mavlink_msg_rocket_radio_link_info_tm_get_payload_rx_success_count(msg);
+    rocket_radio_link_info_tm->payload_rx_drop_count = mavlink_msg_rocket_radio_link_info_tm_get_payload_rx_drop_count(msg);
+    rocket_radio_link_info_tm->payload_bitrate = mavlink_msg_rocket_radio_link_info_tm_get_payload_bitrate(msg);
+    rocket_radio_link_info_tm->radio_433_type = mavlink_msg_rocket_radio_link_info_tm_get_radio_433_type(msg);
+    rocket_radio_link_info_tm->radio_868_type = mavlink_msg_rocket_radio_link_info_tm_get_radio_868_type(msg);
+    rocket_radio_link_info_tm->main_rssi = mavlink_msg_rocket_radio_link_info_tm_get_main_rssi(msg);
+    rocket_radio_link_info_tm->payload_rssi = mavlink_msg_rocket_radio_link_info_tm_get_payload_rssi(msg);
+    rocket_radio_link_info_tm->ethernet_status = mavlink_msg_rocket_radio_link_info_tm_get_ethernet_status(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN;
+        memset(rocket_radio_link_info_tm, 0, MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_LEN);
+    memcpy(rocket_radio_link_info_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/orion/orion.h b/mavlink_lib/orion/orion.h
index 6ce4e363b712577b0ced2ed184e63b97fa3aaa07..00afdb88576dc9223ef2a631d357a1db5c21d0ba 100644
--- a/mavlink_lib/orion/orion.h
+++ b/mavlink_lib/orion/orion.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 1309536867628119565
+#define MAVLINK_THIS_XML_HASH 9073854407394636743
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +20,11 @@ extern "C" {
 // MESSAGE LENGTHS AND CRCS
 
 #ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 14, 4, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 12, 12, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 4, 4, 74, 64, 32, 60, 32, 32, 32, 32, 56, 22, 5, 19, 36, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 16, 46, 28, 20, 44, 53, 77, 29, 178, 158, 180, 170, 88, 43, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 14, 4, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 12, 12, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 4, 4, 74, 64, 32, 60, 32, 32, 32, 32, 56, 22, 5, 19, 36, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 178, 158, 180, 170, 88, 43, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 17, 33, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 238, 79, 167, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 246, 173, 183, 220, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 251, 51, 57, 72, 87, 229, 245, 212, 140, 148, 6, 165, 87, 255, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 188, 195, 99, 84, 135, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 238, 79, 167, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 246, 173, 183, 220, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 251, 51, 57, 72, 87, 229, 245, 212, 140, 148, 6, 165, 87, 255, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 188, 195, 99, 84, 135, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 234, 27, 97, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #include "../protocol.h"
@@ -42,11 +42,12 @@ typedef enum SysIDs
    MAV_SYSID_MAIN=1, /*  | */
    MAV_SYSID_PAYLOAD=2, /*  | */
    MAV_SYSID_RIG=3, /*  | */
-   MAV_SYSID_GS=4, /*  | */
-   MAV_SYSID_ARP=5, /*  | */
-   MAV_SYSID_GS_BACKUP=6, /*  | */
-   MAV_SYSID_ARP_BACKUP=7, /*  | */
-   SysIDs_ENUM_END=8, /*  | */
+   MAV_SYSID_CONRIG=4, /*  | */
+   MAV_SYSID_GS=5, /*  | */
+   MAV_SYSID_ARP=6, /*  | */
+   MAV_SYSID_GS_BACKUP=7, /*  | */
+   MAV_SYSID_ARP_BACKUP=8, /*  | */
+   SysIDs_ENUM_END=9, /*  | */
 } SysIDs;
 #endif
 
@@ -197,6 +198,31 @@ typedef enum PinsList
 } PinsList;
 #endif
 
+/** @brief Enumeration of 433 Mhz transceiver types */
+#ifndef HAVE_ENUM_Radio433Type
+#define HAVE_ENUM_Radio433Type
+typedef enum Radio433Type
+{
+   RADIO_433_TYPE_NONE=0, /* No 433 Mhz transceiver | */
+   RADIO_433_TYPE_SKYWARD=1, /* Skyward 433 Mhz transceiver | */
+   RADIO_433_TYPE_EBYTE=2, /* Ebyte 433 Mhz transceiver (backup) | */
+   RADIO_433_TYPE_LORA=3, /* LoRa (Ebyte) 433 Mhz transceiver | */
+   Radio433Type_ENUM_END=4, /*  | */
+} Radio433Type;
+#endif
+
+/** @brief Enumeration of 868 Mhz transceiver types */
+#ifndef HAVE_ENUM_Radio868Type
+#define HAVE_ENUM_Radio868Type
+typedef enum Radio868Type
+{
+   RADIO_868_TYPE_NONE=0, /* No 868 Mhz transceiver | */
+   RADIO_868_TYPE_SKYWARD=1, /* Skyward 868 Mhz transceiver | */
+   RADIO_868_TYPE_EBYTE=2, /* Ebyte 868 Mhz transceiver (backup) | */
+   Radio868Type_ENUM_END=3, /*  | */
+} Radio868Type;
+#endif
+
 // MAVLINK VERSION
 
 #ifndef MAVLINK_VERSION
@@ -275,16 +301,20 @@ typedef enum PinsList
 #include "./mavlink_msg_gse_tm.h"
 #include "./mavlink_msg_motor_tm.h"
 #include "./mavlink_msg_calibration_tm.h"
+#include "./mavlink_msg_gs_discovery_request.h"
+#include "./mavlink_msg_gs_discovery_response.h"
+#include "./mavlink_msg_rocket_radio_link_info_tm.h"
+#include "./mavlink_msg_gse_radio_link_info_tm.h"
 
 // base include
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 1309536867628119565
+#define MAVLINK_THIS_XML_HASH 9073854407394636743
 
 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_CALIBRATION_PRESSURE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_MEA_MASS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REFERENCE_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, MAVLINK_MESSAGE_INFO_CALIBRATION_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 106 }, { "ARP_COMMAND_TC", 65 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "CALIBRATION_TM", 214 }, { "CAN_STATS_TM", 203 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 32 }, { "CURRENT_TM", 108 }, { "GPS_TM", 103 }, { "GSE_TM", 212 }, { "IMU_TM", 104 }, { "LOAD_TM", 110 }, { "LOGGER_TM", 201 }, { "MAVLINK_STATS_TM", 202 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 114 }, { "PRESSURE_TM", 105 }, { "RAW_EVENT_TC", 14 }, { "REFERENCE_TM", 115 }, { "REGISTRY_COORD_TM", 118 }, { "REGISTRY_FLOAT_TM", 116 }, { "REGISTRY_INT_TM", 117 }, { "RESET_SERVO_TC", 7 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 112 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 113 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 17 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 63 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_CALIBRATION_PRESSURE_TC", 18 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "SET_INITIAL_MEA_MASS_TC", 19 }, { "SET_NITROGEN_TIME_TC", 34 }, { "SET_ORIENTATION_QUAT_TC", 12 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 64 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "SET_STEPPER_MULTIPLIER_TC", 62 }, { "SET_STEPPER_STEPS_TC", 61 }, { "SET_TARGET_COORDINATES_TC", 16 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 31 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 109 }, { "VOLTAGE_TM", 107 }, { "WACK_TM", 102 }, { "WIGGLE_SERVO_TC", 8 }}
+# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_CALIBRATION_PRESSURE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_MEA_MASS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REFERENCE_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, MAVLINK_MESSAGE_INFO_CALIBRATION_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_REQUEST, MAVLINK_MESSAGE_INFO_GS_DISCOVERY_RESPONSE, MAVLINK_MESSAGE_INFO_ROCKET_RADIO_LINK_INFO_TM, MAVLINK_MESSAGE_INFO_GSE_RADIO_LINK_INFO_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 106 }, { "ARP_COMMAND_TC", 65 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "CALIBRATION_TM", 214 }, { "CAN_STATS_TM", 203 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 32 }, { "CURRENT_TM", 108 }, { "GPS_TM", 103 }, { "GSE_RADIO_LINK_INFO_TM", 243 }, { "GSE_TM", 212 }, { "GS_DISCOVERY_REQUEST", 240 }, { "GS_DISCOVERY_RESPONSE", 241 }, { "IMU_TM", 104 }, { "LOAD_TM", 110 }, { "LOGGER_TM", 201 }, { "MAVLINK_STATS_TM", 202 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 114 }, { "PRESSURE_TM", 105 }, { "RAW_EVENT_TC", 14 }, { "REFERENCE_TM", 115 }, { "REGISTRY_COORD_TM", 118 }, { "REGISTRY_FLOAT_TM", 116 }, { "REGISTRY_INT_TM", 117 }, { "RESET_SERVO_TC", 7 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_RADIO_LINK_INFO_TM", 242 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 112 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 113 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 17 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 63 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_CALIBRATION_PRESSURE_TC", 18 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "SET_INITIAL_MEA_MASS_TC", 19 }, { "SET_NITROGEN_TIME_TC", 34 }, { "SET_ORIENTATION_QUAT_TC", 12 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 64 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "SET_STEPPER_MULTIPLIER_TC", 62 }, { "SET_STEPPER_STEPS_TC", 61 }, { "SET_TARGET_COORDINATES_TC", 16 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 31 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 109 }, { "VOLTAGE_TM", 107 }, { "WACK_TM", 102 }, { "WIGGLE_SERVO_TC", 8 }}
 # if MAVLINK_COMMAND_24BIT
 #  include "../mavlink_get_info.h"
 # endif
diff --git a/mavlink_lib/orion/testsuite.h b/mavlink_lib/orion/testsuite.h
index d766439a39c269f129f0ce47fc990e8d707ece78..b24dc532632c5113bb3ea35d2bd7bbaf8e9669c4 100644
--- a/mavlink_lib/orion/testsuite.h
+++ b/mavlink_lib/orion/testsuite.h
@@ -3095,7 +3095,7 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_arp_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,21187,21291,21395,21499,21603,21707,21811,21915,22019,22123,22227,171,238,49,116,183,250
+        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,20771,87,154
     };
     mavlink_arp_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3114,26 +3114,10 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.gps_latitude = packet_in.gps_latitude;
         packet1.gps_longitude = packet_in.gps_longitude;
         packet1.gps_height = packet_in.gps_height;
-        packet1.main_rx_rssi = packet_in.main_rx_rssi;
-        packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
         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;
-        packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
-        packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
-        packet1.payload_packet_tx_error_count = packet_in.payload_packet_tx_error_count;
-        packet1.payload_tx_bitrate = packet_in.payload_tx_bitrate;
-        packet1.payload_packet_rx_success_count = packet_in.payload_packet_rx_success_count;
-        packet1.payload_packet_rx_drop_count = packet_in.payload_packet_rx_drop_count;
-        packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
         packet1.log_number = packet_in.log_number;
         packet1.state = packet_in.state;
         packet1.gps_fix = packet_in.gps_fix;
-        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
@@ -3148,12 +3132,12 @@ static void mavlink_test_arp_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_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , 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.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.ethernet_present , packet1.ethernet_status , packet1.battery_voltage , packet1.log_number );
+    mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.battery_voltage , packet1.log_number );
     mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , 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.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.ethernet_present , packet1.ethernet_status , packet1.battery_voltage , packet1.log_number );
+    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.battery_voltage , packet1.log_number );
     mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3166,7 +3150,7 @@ static void mavlink_test_arp_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_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , 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.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.ethernet_present , packet1.ethernet_status , packet1.battery_voltage , packet1.log_number );
+    mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.battery_voltage , packet1.log_number );
     mavlink_msg_arp_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -4376,6 +4360,269 @@ static void mavlink_test_calibration_tm(uint8_t system_id, uint8_t component_id,
 #endif
 }
 
+static void mavlink_test_gs_discovery_request(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_gs_discovery_request_t packet_in = {
+        963497464,17443
+    };
+    mavlink_gs_discovery_request_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.source_ip = packet_in.source_ip;
+        packet1.source_port = packet_in.source_port;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_request_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_gs_discovery_request_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_request_pack(system_id, component_id, &msg , packet1.source_ip , packet1.source_port );
+    mavlink_msg_gs_discovery_request_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.source_ip , packet1.source_port );
+    mavlink_msg_gs_discovery_request_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_gs_discovery_request_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_request_send(MAVLINK_COMM_1 , packet1.source_ip , packet1.source_port );
+    mavlink_msg_gs_discovery_request_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("GS_DISCOVERY_REQUEST") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GS_DISCOVERY_REQUEST) != NULL);
+#endif
+}
+
+static void mavlink_test_gs_discovery_response(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_gs_discovery_response_t packet_in = {
+        963497464,963497672,963497880,17859,175,242,53
+    };
+    mavlink_gs_discovery_response_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.ip = packet_in.ip;
+        packet1.radio_433_frequency = packet_in.radio_433_frequency;
+        packet1.radio_868_frequency = packet_in.radio_868_frequency;
+        packet1.port = packet_in.port;
+        packet1.device_id = packet_in.device_id;
+        packet1.radio_433_type = packet_in.radio_433_type;
+        packet1.radio_868_type = packet_in.radio_868_type;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_response_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_gs_discovery_response_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_response_pack(system_id, component_id, &msg , packet1.ip , packet1.port , packet1.device_id , packet1.radio_433_type , packet1.radio_868_type , packet1.radio_433_frequency , packet1.radio_868_frequency );
+    mavlink_msg_gs_discovery_response_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ip , packet1.port , packet1.device_id , packet1.radio_433_type , packet1.radio_868_type , packet1.radio_433_frequency , packet1.radio_868_frequency );
+    mavlink_msg_gs_discovery_response_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_gs_discovery_response_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gs_discovery_response_send(MAVLINK_COMM_1 , packet1.ip , packet1.port , packet1.device_id , packet1.radio_433_type , packet1.radio_868_type , packet1.radio_433_frequency , packet1.radio_868_frequency );
+    mavlink_msg_gs_discovery_response_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("GS_DISCOVERY_RESPONSE") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GS_DISCOVERY_RESPONSE) != NULL);
+#endif
+}
+
+static void mavlink_test_rocket_radio_link_info_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_rocket_radio_link_info_tm_t packet_in = {
+        93372036854775807ULL,963497880,963498088,18067,18171,18275,18379,18483,18587,89,156,223,34,101
+    };
+    mavlink_rocket_radio_link_info_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.main_frequency = packet_in.main_frequency;
+        packet1.payload_frequency = packet_in.payload_frequency;
+        packet1.main_rx_success_count = packet_in.main_rx_success_count;
+        packet1.main_rx_drop_count = packet_in.main_rx_drop_count;
+        packet1.main_bitrate = packet_in.main_bitrate;
+        packet1.payload_rx_success_count = packet_in.payload_rx_success_count;
+        packet1.payload_rx_drop_count = packet_in.payload_rx_drop_count;
+        packet1.payload_bitrate = packet_in.payload_bitrate;
+        packet1.radio_433_type = packet_in.radio_433_type;
+        packet1.radio_868_type = packet_in.radio_868_type;
+        packet1.main_rssi = packet_in.main_rssi;
+        packet1.payload_rssi = packet_in.payload_rssi;
+        packet1.ethernet_status = packet_in.ethernet_status;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_rocket_radio_link_info_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_rocket_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_rocket_radio_link_info_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.radio_433_type , packet1.radio_868_type , packet1.main_rssi , packet1.main_rx_success_count , packet1.main_rx_drop_count , packet1.main_bitrate , packet1.main_frequency , packet1.payload_rssi , packet1.payload_rx_success_count , packet1.payload_rx_drop_count , packet1.payload_bitrate , packet1.payload_frequency , packet1.ethernet_status );
+    mavlink_msg_rocket_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_rocket_radio_link_info_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.radio_433_type , packet1.radio_868_type , packet1.main_rssi , packet1.main_rx_success_count , packet1.main_rx_drop_count , packet1.main_bitrate , packet1.main_frequency , packet1.payload_rssi , packet1.payload_rx_success_count , packet1.payload_rx_drop_count , packet1.payload_bitrate , packet1.payload_frequency , packet1.ethernet_status );
+    mavlink_msg_rocket_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_rocket_radio_link_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_rocket_radio_link_info_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.radio_433_type , packet1.radio_868_type , packet1.main_rssi , packet1.main_rx_success_count , packet1.main_rx_drop_count , packet1.main_bitrate , packet1.main_frequency , packet1.payload_rssi , packet1.payload_rx_success_count , packet1.payload_rx_drop_count , packet1.payload_bitrate , packet1.payload_frequency , packet1.ethernet_status );
+    mavlink_msg_rocket_radio_link_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_RADIO_LINK_INFO_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_RADIO_LINK_INFO_TM) != NULL);
+#endif
+}
+
+static void mavlink_test_gse_radio_link_info_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_gse_radio_link_info_tm_t packet_in = {
+        93372036854775807ULL,963497880,17859,17963,18067,187,254,65
+    };
+    mavlink_gse_radio_link_info_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.frequency = packet_in.frequency;
+        packet1.rx_success_count = packet_in.rx_success_count;
+        packet1.rx_drop_count = packet_in.rx_drop_count;
+        packet1.bitrate = packet_in.bitrate;
+        packet1.rssi = packet_in.rssi;
+        packet1.snr = packet_in.snr;
+        packet1.ethernet_status = packet_in.ethernet_status;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gse_radio_link_info_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_gse_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gse_radio_link_info_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.rssi , packet1.snr , packet1.rx_success_count , packet1.rx_drop_count , packet1.bitrate , packet1.frequency , packet1.ethernet_status );
+    mavlink_msg_gse_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gse_radio_link_info_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.rssi , packet1.snr , packet1.rx_success_count , packet1.rx_drop_count , packet1.bitrate , packet1.frequency , packet1.ethernet_status );
+    mavlink_msg_gse_radio_link_info_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_gse_radio_link_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_gse_radio_link_info_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.rssi , packet1.snr , packet1.rx_success_count , packet1.rx_drop_count , packet1.bitrate , packet1.frequency , packet1.ethernet_status );
+    mavlink_msg_gse_radio_link_info_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("GSE_RADIO_LINK_INFO_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GSE_RADIO_LINK_INFO_TM) != NULL);
+#endif
+}
+
 static void mavlink_test_orion(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
     mavlink_test_ping_tc(system_id, component_id, last_msg);
@@ -4444,6 +4691,10 @@ static void mavlink_test_orion(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_gse_tm(system_id, component_id, last_msg);
     mavlink_test_motor_tm(system_id, component_id, last_msg);
     mavlink_test_calibration_tm(system_id, component_id, last_msg);
+    mavlink_test_gs_discovery_request(system_id, component_id, last_msg);
+    mavlink_test_gs_discovery_response(system_id, component_id, last_msg);
+    mavlink_test_rocket_radio_link_info_tm(system_id, component_id, last_msg);
+    mavlink_test_gse_radio_link_info_tm(system_id, component_id, last_msg);
 }
 
 #ifdef __cplusplus
diff --git a/mavlink_lib/orion/version.h b/mavlink_lib/orion/version.h
index 6126ea993ae13734738f435df1793abe3a0905e4..5eb96632484058155fa5673b55cc95910e74323f 100644
--- a/mavlink_lib/orion/version.h
+++ b/mavlink_lib/orion/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Apr 08 2025"
+#define MAVLINK_BUILD_DATE "Fri May 02 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 180
  
diff --git a/message_definitions/orion.xml b/message_definitions/orion.xml
index 8d7914f1dbead79169f4002e3647f322d2a6ada1..9c8a33a449bd4cbc74b0e709dbd69bb27de4bbae 100644
--- a/message_definitions/orion.xml
+++ b/message_definitions/orion.xml
@@ -7,10 +7,11 @@
             <entry name="MAV_SYSID_MAIN" value="1"></entry>
             <entry name="MAV_SYSID_PAYLOAD" value="2"></entry>
             <entry name="MAV_SYSID_RIG" value="3"></entry>
-            <entry name="MAV_SYSID_GS" value="4"></entry>
-            <entry name="MAV_SYSID_ARP" value="5"></entry>
-            <entry name="MAV_SYSID_GS_BACKUP" value="6"></entry>
-            <entry name="MAV_SYSID_ARP_BACKUP" value="7"></entry>
+            <entry name="MAV_SYSID_CONRIG" value="4"></entry>
+            <entry name="MAV_SYSID_GS" value="5"></entry>
+            <entry name="MAV_SYSID_ARP" value="6"></entry>
+            <entry name="MAV_SYSID_GS_BACKUP" value="7"></entry>
+            <entry name="MAV_SYSID_ARP_BACKUP" value="8"></entry>
         </enum>
         <enum name="SystemTMList">
             <description>Enum list for all the telemetries that can be requested</description>
@@ -97,7 +98,7 @@
                 <description>Pressure sensor data</description>
             </entry>
             <entry name="MAV_LSM6DSRX_ID" value="10">
-                <description>IMU data</description> 
+                <description>IMU data</description>
             </entry>
             <entry name="MAV_H3LIS331DL_ID" value="11">
                 <description>400G accelerometer</description>
@@ -306,6 +307,33 @@
             <entry name="RAMP_PIN" value="1"></entry>
             <entry name="NOSECONE_PIN" value="2"></entry>
         </enum>
+        <enum name="Radio433Type">
+            <description>Enumeration of 433 Mhz transceiver types</description>
+            <entry name="RADIO_433_TYPE_NONE" value="0">
+                <description>No 433 Mhz transceiver</description>
+            </entry>
+            <entry name="RADIO_433_TYPE_SKYWARD" value="1">
+                <description>Skyward 433 Mhz transceiver</description>
+            </entry>
+            <entry name="RADIO_433_TYPE_EBYTE" value="2">
+                <description>Ebyte 433 Mhz transceiver (backup)</description>
+            </entry>
+            <entry name="RADIO_433_TYPE_LORA" value="3">
+                <description>LoRa (Ebyte) 433 Mhz transceiver</description>
+            </entry>
+        </enum>
+        <enum name="Radio868Type">
+            <description>Enumeration of 868 Mhz transceiver types</description>
+            <entry name="RADIO_868_TYPE_NONE" value="0">
+                <description>No 868 Mhz transceiver</description>
+            </entry>
+            <entry name="RADIO_868_TYPE_SKYWARD" value="1">
+                <description>Skyward 868 Mhz transceiver</description>
+            </entry>
+            <entry name="RADIO_868_TYPE_EBYTE" value="2">
+                <description>Ebyte 868 Mhz transceiver (backup)</description>
+            </entry>
+        </enum>
     </enums>
     <messages>
         <!-- FROM GROUND TO ROCKET -->
@@ -623,7 +651,7 @@
             <field name="latitude" type="float" units="deg">Latitude in this configuration</field>
             <field name="longitude" type="float" units="deg">Latitude in this configuration</field>
         </message>
-        
+
         <!-- FROM AUTOMATED ROCKET POINTER TO GROUNDSTATION -->
         <message id="150" name="ARP_TM">
             <description></description>
@@ -644,22 +672,6 @@
             <field name="gps_longitude" type="float" units="deg">Longitude</field>
             <field name="gps_height" type="float" units="m">Altitude</field>
             <field name="gps_fix" type="uint8_t">Wether the GPS has a FIX</field>
-            <field name="main_radio_present" type="uint8_t">Boolean indicating the presence of the main radio</field>
-            <field name="main_packet_tx_error_count" type="uint16_t">Number of errors during send</field>
-            <field name="main_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field>
-            <field name="main_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field>
-            <field name="main_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
-            <field name="main_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
-            <field name="main_rx_rssi" type="float" units="dBm">Receive RSSI</field>
-            <field name="payload_radio_present" type="uint8_t">Boolean indicating the presence of the payload radio</field>
-            <field name="payload_packet_tx_error_count" type="uint16_t">Number of errors during send</field>
-            <field name="payload_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field>
-            <field name="payload_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field>
-            <field name="payload_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
-            <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="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>
             <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
         </message>
@@ -1040,5 +1052,50 @@
             <field name="dynamic_press_bias" type="float" units="Pa">Dynamic pressure bias</field>
             <field name="dynamic_press_scale" type="float">Dynamic pressure scale</field>
         </message>
+
+        <!-- Ground Station Messages -->
+        <message id="240" name="GS_DISCOVERY_REQUEST">
+            <description>Request for discovery of devices in the GS network</description>
+            <field name="source_ip" type="uint32_t">IP address of the requesting device</field>
+            <field name="source_port" type="uint16_t">Port of the requesting device</field>
+        </message>
+        <message id="241" name="GS_DISCOVERY_RESPONSE">
+            <description>Response for discovery of devices in the GS network</description>
+            <field name="ip" type="uint32_t">IP address of the device</field>
+            <field name="port" type="uint16_t">Port of the device</field>
+            <field name="device_id" type="uint8_t">Device ID</field>
+            <field name="radio_433_type" type="uint8_t" enum="Radio433Type">Radio 433 type of the device</field>
+            <field name="radio_868_type" type="uint8_t" enum="Radio868Type">Radio 868 type of the device</field>
+            <field name="radio_433_frequency" type="uint32_t" units="Hz">Radio 433 frequency of the device</field>
+            <field name="radio_868_frequency" type="uint32_t" units="Hz">Radio 868 frequency of the device</field>
+        </message>
+        <message id="242" name="ROCKET_RADIO_LINK_INFO_TM">
+            <description>Radio link information telemetry</description>
+            <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
+            <field name="radio_433_type" type="uint8_t" enum="Radio433Type">Radio 433 type of the device</field>
+            <field name="radio_868_type" type="uint8_t" enum="Radio868Type">Radio 868 type of the device</field>
+            <field name="main_rssi" type="int8_t" units="dBm">Main radio RSSI</field>
+            <field name="main_rx_success_count" type="uint16_t">Main radio received packet count</field>
+            <field name="main_rx_drop_count" type="uint16_t">Main radio dropped packet count (e.g. CRC mismatch)</field>
+            <field name="main_bitrate" type="uint16_t" units="b/s">Main radio bitrate</field>
+            <field name="main_frequency" type="uint32_t" units="Hz">Main radio frequency</field>
+            <field name="payload_rssi" type="int8_t" units="dBm">Payload radio RSSI</field>
+            <field name="payload_rx_success_count" type="uint16_t">Payload radio received packet count</field>
+            <field name="payload_rx_drop_count" type="uint16_t">Payload radio dropped packet count (e.g. CRC mismatch)</field>
+            <field name="payload_bitrate" type="uint16_t" units="b/s">Payload radio bitrate</field>
+            <field name="payload_frequency" type="uint32_t" units="Hz">Payload radio frequency</field>
+            <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field>
+        </message>
+        <message id="243" name="GSE_RADIO_LINK_INFO_TM">
+            <description>Radio link information telemetry</description>
+            <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
+            <field name="rssi" type="int8_t" units="dBm">Radio RSSI</field>
+            <field name="snr" type="int8_t" units="dB">Radio Signal to Noise Ratio</field>
+            <field name="rx_success_count" type="uint16_t">Radio received packet count</field>
+            <field name="rx_drop_count" type="uint16_t">Radio dropped packet count (e.g. CRC mismatch)</field>
+            <field name="bitrate" type="uint16_t" units="b/s">Radio bitrate</field>
+            <field name="frequency" type="uint32_t" units="Hz">Radio frequency</field>
+            <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field>
+        </message>
     </messages>
 </mavlink>